diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index d458790979..661bfe1830 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 diff --git a/Marlin/src/HAL/AVR/HAL_SPI.cpp b/Marlin/src/HAL/AVR/HAL_SPI.cpp index 32c0361d03..db6a12734d 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI.cpp @@ -119,7 +119,6 @@ void spiBegin() { while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } } - /** begin spi transaction */ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { // Based on Arduino SPI library @@ -175,7 +174,6 @@ void spiBegin() { SPSR = clockDiv | 0x01; } - #else // SOFTWARE_SPI || FORCE_SOFT_SPI // ------------------------ diff --git a/Marlin/src/HAL/AVR/Servo.cpp b/Marlin/src/HAL/AVR/Servo.cpp index 0a1ef5337a..8ce9bc11b8 100644 --- a/Marlin/src/HAL/AVR/Servo.cpp +++ b/Marlin/src/HAL/AVR/Servo.cpp @@ -63,7 +63,6 @@ static volatile int8_t Channel[_Nbr_16timers]; // counter for the servo being pulsed for each timer (or -1 if refresh interval) - /************ static functions common to all instances ***********************/ static inline void handle_interrupts(const timer16_Sequence_t timer, volatile uint16_t* TCNTn, volatile uint16_t* OCRnA) { diff --git a/Marlin/src/HAL/AVR/endstop_interrupts.h b/Marlin/src/HAL/AVR/endstop_interrupts.h index 5511aa406f..306fa700f4 100644 --- a/Marlin/src/HAL/AVR/endstop_interrupts.h +++ b/Marlin/src/HAL/AVR/endstop_interrupts.h @@ -91,7 +91,6 @@ void endstop_ISR() { endstops.update(); } #endif - // Install Pin change interrupt for a pin. Can be called multiple times. void pciSetup(const int8_t pin) { if (digitalPinHasPCICR(pin)) { diff --git a/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h b/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h index d2a8aca6f3..7057c1e777 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h @@ -682,7 +682,6 @@ #define PF7_PWM 0 #define PF7_DDR DDRF - /** * Some of the pin mapping functions of the Teensduino extension to the Arduino IDE * do not function the same as the other Arduino extensions. diff --git a/Marlin/src/HAL/AVR/pinsDebug.h b/Marlin/src/HAL/AVR/pinsDebug.h index fb2aace7e4..78b10f1333 100644 --- a/Marlin/src/HAL/AVR/pinsDebug.h +++ b/Marlin/src/HAL/AVR/pinsDebug.h @@ -90,7 +90,6 @@ void PRINT_ARRAY_NAME(uint8_t x) { #define GET_ARRAY_IS_DIGITAL(x) pgm_read_byte(&pin_array[x].is_digital) - #if defined(__AVR_ATmega1284P__) // 1284 IDE extensions set this to the number of #undef NUM_DIGITAL_PINS // digital only pins while all other CPUs have it #define NUM_DIGITAL_PINS 32 // set to digital only + digital/analog @@ -164,7 +163,6 @@ static bool pwm_status(uint8_t pin) { SERIAL_ECHO_SP(2); } // pwm_status - const volatile uint8_t* const PWM_other[][3] PROGMEM = { { &TCCR0A, &TCCR0B, &TIMSK0 }, { &TCCR1A, &TCCR1B, &TIMSK1 }, @@ -182,7 +180,6 @@ const volatile uint8_t* const PWM_other[][3] PROGMEM = { #endif }; - const volatile uint8_t* const PWM_OCR[][3] PROGMEM = { #ifdef TIMER0A @@ -218,7 +215,6 @@ const volatile uint8_t* const PWM_OCR[][3] PROGMEM = { #endif }; - #define TCCR_A(T) pgm_read_word(&PWM_other[T][0]) #define TCCR_B(T) pgm_read_word(&PWM_other[T][1]) #define TIMSK(T) pgm_read_word(&PWM_other[T][2]) diff --git a/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h b/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h index 582ae79ba7..c812d4fb11 100644 --- a/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h +++ b/Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h @@ -22,11 +22,10 @@ #pragma once // -// some of the pin mapping functions of the Teensduino extension to the Arduino IDE -// do not function the same as the other Arduino extensions +// Some of the pin mapping functions of the Arduino IDE Teensduino extension +// function differently from other Arduino extensions. // - #define TEENSYDUINO_IDE //digitalPinToTimer(pin) function works like Arduino but Timers are not defined @@ -48,8 +47,6 @@ #define PE 5 #define PF 6 -#undef digitalPinToPort - const uint8_t PROGMEM digital_pin_to_port_PGM[] = { PD, // 0 - PD0 - INT0 - PWM PD, // 1 - PD1 - INT1 - PWM @@ -101,7 +98,7 @@ const uint8_t PROGMEM digital_pin_to_port_PGM[] = { PE, // 47 - PE3 (not defined in teensyduino) }; -#define digitalPinToPort(P) ( pgm_read_byte( digital_pin_to_port_PGM + (P) ) ) +#define digitalPinToPort(P) pgm_read_byte(digital_pin_to_port_PGM[P]) // digitalPinToBitMask(pin) is OK diff --git a/Marlin/src/HAL/AVR/pinsDebug_plus_70.h b/Marlin/src/HAL/AVR/pinsDebug_plus_70.h index d9aa44c3cb..fa479cfe8f 100644 --- a/Marlin/src/HAL/AVR/pinsDebug_plus_70.h +++ b/Marlin/src/HAL/AVR/pinsDebug_plus_70.h @@ -231,7 +231,6 @@ const uint8_t PROGMEM digital_pin_to_bit_mask_PGM_plus_70[] = { #define digitalPinToBitMask_plus_70(P) ( pgm_read_byte( digital_pin_to_bit_mask_PGM_plus_70 + (P) ) ) - const uint8_t PROGMEM digital_pin_to_timer_PGM_plus_70[] = { // TIMERS // ------------------------ diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h index d9cdfc4f01..94b17f3102 100644 --- a/Marlin/src/HAL/AVR/timers.h +++ b/Marlin/src/HAL/AVR/timers.h @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 diff --git a/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp b/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp index 79bafe2939..131174b06c 100644 --- a/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp +++ b/Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp @@ -120,7 +120,6 @@ void u8g_spiSend_sw_AVR_mode_3(uint8_t val) { U8G_ATOMIC_END(); } - #if ENABLED(FYSETC_MINI_12864) #define SPISEND_SW_AVR u8g_spiSend_sw_AVR_mode_3 #else diff --git a/Marlin/src/HAL/DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp index 1b57bdb2fa..763091cb00 100644 --- a/Marlin/src/HAL/DUE/HAL.cpp +++ b/Marlin/src/HAL/DUE/HAL.cpp @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 585b893841..8ab1003296 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp index 638f7a1007..90efe55fc2 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp @@ -474,7 +474,6 @@ void MarlinSerial::flushTX() { } } - // If not using the USB port as serial port #if defined(SERIAL_PORT) && SERIAL_PORT >= 0 template class MarlinSerial< MarlinSerialCfg >; diff --git a/Marlin/src/HAL/DUE/MinSerial.cpp b/Marlin/src/HAL/DUE/MinSerial.cpp index e5b3dbfe6f..bee3cc4fd3 100644 --- a/Marlin/src/HAL/DUE/MinSerial.cpp +++ b/Marlin/src/HAL/DUE/MinSerial.cpp @@ -73,11 +73,17 @@ void install_min_serial() { } #if DISABLED(DYNAMIC_VECTORTABLE) -extern "C" { - __attribute__((naked)) void JumpHandler_ASM() { - __asm__ __volatile__ ( - "b CommonHandler_ASM\n" - ); + extern "C" { + __attribute__((naked)) void JumpHandler_ASM() { + __asm__ __volatile__ ( + "b CommonHandler_ASM\n" + ); + } + void __attribute__((naked, alias("JumpHandler_ASM"))) HardFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) BusFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) UsageFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) MemManage_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) NMI_Handler(); } void __attribute__((naked, alias("JumpHandler_ASM"))) HardFault_Handler(); void __attribute__((naked, alias("JumpHandler_ASM"))) BusFault_Handler(); diff --git a/Marlin/src/HAL/DUE/eeprom_flash.cpp b/Marlin/src/HAL/DUE/eeprom_flash.cpp index 607764155b..a0ed6cc843 100644 --- a/Marlin/src/HAL/DUE/eeprom_flash.cpp +++ b/Marlin/src/HAL/DUE/eeprom_flash.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/DUE/eeprom_wired.cpp b/Marlin/src/HAL/DUE/eeprom_wired.cpp index 557a2f2cff..24f8c06d2e 100644 --- a/Marlin/src/HAL/DUE/eeprom_wired.cpp +++ b/Marlin/src/HAL/DUE/eeprom_wired.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/DUE/fastio/G2_PWM.h b/Marlin/src/HAL/DUE/fastio/G2_PWM.h index 2afe246cea..054eb2cf80 100644 --- a/Marlin/src/HAL/DUE/fastio/G2_PWM.h +++ b/Marlin/src/HAL/DUE/fastio/G2_PWM.h @@ -49,7 +49,6 @@ extern volatile uint32_t *SODR_A, *SODR_B, *CODR_A, *CODR_B; #define PWM_MAP_INIT_ROW(IO,ZZ) { ZZ == 'A' ? SODR_A : SODR_B, ZZ == 'A' ? CODR_A : CODR_B, 1 << _PIN(IO) } - #define PWM_MAP_INIT { PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_X_PIN, 'B'), \ PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_Y_PIN, 'B'), \ PWM_MAP_INIT_ROW(MOTOR_CURRENT_PWM_Z_PIN, 'B'), \ diff --git a/Marlin/src/HAL/DUE/fastio/G2_pins.h b/Marlin/src/HAL/DUE/fastio/G2_pins.h index 80c87bd392..38fcc5e5df 100644 --- a/Marlin/src/HAL/DUE/fastio/G2_pins.h +++ b/Marlin/src/HAL/DUE/fastio/G2_pins.h @@ -168,7 +168,6 @@ const G2_PinDescription G2_g_APinDescription[] = { { PIOB, PIO_PB21, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 52 { PIOB, PIO_PB14, ID_PIOB, PIO_OUTPUT_0, PIO_DEFAULT, PIN_ATTR_DIGITAL, NO_ADC, NO_ADC, NOT_ON_PWM, NOT_ON_TIMER }, // PIN 53 - // 54 .. 65 - Analog pins // ---------------------- { PIOA, PIO_PA16X1_AD7, ID_PIOA, PIO_INPUT, PIO_DEFAULT, PIN_ATTR_ANALOG, ADC0, ADC7, NOT_ON_PWM, NOT_ON_TIMER }, // AD0 diff --git a/Marlin/src/HAL/DUE/timers.cpp b/Marlin/src/HAL/DUE/timers.cpp index e5647817b6..e388255c08 100644 --- a/Marlin/src/HAL/DUE/timers.cpp +++ b/Marlin/src/HAL/DUE/timers.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index dc35c77e63..db5d83a06f 100644 --- a/Marlin/src/HAL/DUE/timers.h +++ b/Marlin/src/HAL/DUE/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 diff --git a/Marlin/src/HAL/DUE/usb/compiler.h b/Marlin/src/HAL/DUE/usb/compiler.h index 633197914e..27c554cdb7 100644 --- a/Marlin/src/HAL/DUE/usb/compiler.h +++ b/Marlin/src/HAL/DUE/usb/compiler.h @@ -142,7 +142,6 @@ */ #define COMPILER_PACK_RESET() COMPILER_PRAGMA(pack()) - /** * \brief Set aligned boundary. */ @@ -283,7 +282,6 @@ typedef double F64; //!< 64-bit floating-point number. typedef uint32_t iram_size_t; //! @} - /*! \name Status Types */ //! @{ @@ -291,7 +289,6 @@ typedef bool Status_bool_t; //!< Boolean status. typedef U8 Status_t; //!< 8-bit-coded status. //! @} - /*! \name Aliasing Aggregate Types */ //! @{ @@ -462,7 +459,6 @@ typedef struct #endif //! @} - #ifndef __ASSEMBLY__ // not for assembling. //! \name Optimization Control @@ -581,7 +577,6 @@ typedef struct //! @} - /*! \name Zero-Bit Counting * * Under GCC, __builtin_clz and __builtin_ctz behave like macros when @@ -692,7 +687,6 @@ typedef struct //! @} - /*! \name Bit Reversing */ //! @{ @@ -732,7 +726,6 @@ typedef struct //! @} - /*! \name Alignment */ //! @{ @@ -798,7 +791,6 @@ typedef struct */ #define Long_call(addr) ((*(void (*)(void))(addr))()) - /*! \name MCU Endianism Handling * ARM is MCU little endianism. */ @@ -868,7 +860,6 @@ typedef struct #define CPU_TO_BE32(x) swap32(x) //! @} - /*! \name Endianism Conversion * * The same considerations as for clz and ctz apply here but GCC's @@ -955,7 +946,6 @@ typedef struct //! @} - /*! \name Target Abstraction */ //! @{ @@ -997,7 +987,6 @@ typedef U8 Byte; //!< 8-bit unsigned integer. #endif // #ifndef __ASSEMBLY__ - #ifdef __ICCARM__ #define SHORTENUM __packed #elif defined(__GNUC__) diff --git a/Marlin/src/HAL/DUE/usb/conf_access.h b/Marlin/src/HAL/DUE/usb/conf_access.h index f401685223..0ea5fe2287 100644 --- a/Marlin/src/HAL/DUE/usb/conf_access.h +++ b/Marlin/src/HAL/DUE/usb/conf_access.h @@ -81,7 +81,6 @@ #define LUN_0_NAME "\"SD/MMC Card\"" //! @} - /*! \name Actions Associated with Memory Accesses * * Write here the action to associate with each memory access. @@ -112,5 +111,4 @@ #define GLOBAL_WR_PROTECT false //!< Management of a global write protection. //! @} - #endif // _CONF_ACCESS_H_ diff --git a/Marlin/src/HAL/DUE/usb/conf_clock.h b/Marlin/src/HAL/DUE/usb/conf_clock.h index 97e70e99a5..0c7815ee4d 100644 --- a/Marlin/src/HAL/DUE/usb/conf_clock.h +++ b/Marlin/src/HAL/DUE/usb/conf_clock.h @@ -96,5 +96,4 @@ // - UPLL frequency: 480MHz // - USB clock: 480 / 1 = 480MHz - #endif /* CONF_CLOCK_H_INCLUDED */ diff --git a/Marlin/src/HAL/DUE/usb/conf_usb.h b/Marlin/src/HAL/DUE/usb/conf_usb.h index f66194c6e6..fb4ef34241 100644 --- a/Marlin/src/HAL/DUE/usb/conf_usb.h +++ b/Marlin/src/HAL/DUE/usb/conf_usb.h @@ -88,7 +88,6 @@ #endif //@} - /** * USB Device Callbacks definitions (Optional) * @{ @@ -150,7 +149,6 @@ //@} - /** * USB Interface Configuration * @{ @@ -210,7 +208,6 @@ //@} //@} - /** * Configuration of MSC interface * @{ @@ -245,7 +242,6 @@ //@} - /** * Description of Composite Device * @{ diff --git a/Marlin/src/HAL/DUE/usb/ctrl_access.c b/Marlin/src/HAL/DUE/usb/ctrl_access.c index 99f97f62cb..b766ed1273 100644 --- a/Marlin/src/HAL/DUE/usb/ctrl_access.c +++ b/Marlin/src/HAL/DUE/usb/ctrl_access.c @@ -68,7 +68,6 @@ #endif #include "ctrl_access.h" - //_____ D E F I N I T I O N S ______________________________________________ #ifdef FREERTOS_USED @@ -112,7 +111,6 @@ static xSemaphoreHandle ctrl_access_semphr = NULL; #endif // FREERTOS_USED - #if MAX_LUN /*! \brief Initializes an entry of the LUN descriptor table. @@ -242,17 +240,14 @@ static const struct #endif - #if GLOBAL_WR_PROTECT == true bool g_wr_protect; #endif - /*! \name Control Interface */ //! @{ - #ifdef FREERTOS_USED bool ctrl_access_init(void) @@ -270,7 +265,6 @@ bool ctrl_access_init(void) return true; } - /*! \brief Locks accesses to LUNs. * * \return \c true if the access was successfully locked, else \c false. @@ -288,7 +282,6 @@ static bool ctrl_access_lock(void) #endif // FREERTOS_USED - U8 get_nb_lun(void) { #if MEM_USB == ENABLE @@ -309,13 +302,11 @@ U8 get_nb_lun(void) #endif } - U8 get_cur_lun(void) { return LUN_ID_0; } - Ctrl_status mem_test_unit_ready(U8 lun) { Ctrl_status status; @@ -337,7 +328,6 @@ Ctrl_status mem_test_unit_ready(U8 lun) return status; } - Ctrl_status mem_read_capacity(U8 lun, U32 *u32_nb_sector) { Ctrl_status status; @@ -359,7 +349,6 @@ Ctrl_status mem_read_capacity(U8 lun, U32 *u32_nb_sector) return status; } - U8 mem_sector_size(U8 lun) { U8 sector_size; @@ -381,7 +370,6 @@ U8 mem_sector_size(U8 lun) return sector_size; } - bool mem_unload(U8 lun, bool unload) { bool unloaded; @@ -433,7 +421,6 @@ bool mem_wr_protect(U8 lun) return wr_protect; } - bool mem_removal(U8 lun) { bool removal; @@ -458,7 +445,6 @@ bool mem_removal(U8 lun) return removal; } - const char *mem_name(U8 lun) { #if MAX_LUN==0 @@ -475,17 +461,14 @@ const char *mem_name(U8 lun) #endif } - //! @} - #if ACCESS_USB == true /*! \name MEM <-> USB Interface */ //! @{ - Ctrl_status memory_2_usb(U8 lun, U32 addr, U16 nb_sector) { Ctrl_status status; @@ -505,7 +488,6 @@ Ctrl_status memory_2_usb(U8 lun, U32 addr, U16 nb_sector) return status; } - Ctrl_status usb_2_memory(U8 lun, U32 addr, U16 nb_sector) { Ctrl_status status; @@ -525,19 +507,16 @@ Ctrl_status usb_2_memory(U8 lun, U32 addr, U16 nb_sector) return status; } - //! @} #endif // ACCESS_USB == true - #if ACCESS_MEM_TO_RAM == true /*! \name MEM <-> RAM Interface */ //! @{ - Ctrl_status memory_2_ram(U8 lun, U32 addr, void *ram) { Ctrl_status status; @@ -564,7 +543,6 @@ Ctrl_status memory_2_ram(U8 lun, U32 addr, void *ram) return status; } - Ctrl_status ram_2_memory(U8 lun, U32 addr, const void *ram) { Ctrl_status status; @@ -591,19 +569,16 @@ Ctrl_status ram_2_memory(U8 lun, U32 addr, const void *ram) return status; } - //! @} #endif // ACCESS_MEM_TO_RAM == true - #if ACCESS_STREAM == true /*! \name Streaming MEM <-> MEM Interface */ //! @{ - #if ACCESS_MEM_TO_MEM == true #include "fat.h" @@ -625,21 +600,18 @@ Ctrl_status stream_mem_to_mem(U8 src_lun, U32 src_addr, U8 dest_lun, U32 dest_ad #endif // ACCESS_MEM_TO_MEM == true - Ctrl_status stream_state(U8 id) { UNUSED(id); return CTRL_GOOD; } - U16 stream_stop(U8 id) { UNUSED(id); return 0; } - //! @} #endif // ACCESS_STREAM diff --git a/Marlin/src/HAL/DUE/usb/ctrl_access.h b/Marlin/src/HAL/DUE/usb/ctrl_access.h index b33839076e..d9cb05da74 100644 --- a/Marlin/src/HAL/DUE/usb/ctrl_access.h +++ b/Marlin/src/HAL/DUE/usb/ctrl_access.h @@ -56,7 +56,6 @@ * Support and FAQ: visit Atmel Support */ - #ifndef _CTRL_ACCESS_H_ #define _CTRL_ACCESS_H_ @@ -89,7 +88,6 @@ typedef enum CTRL_BUSY = FAIL + 2 //!< Memory not initialized or changed. } Ctrl_status; - // FYI: Each Logical Unit Number (LUN) corresponds to a memory. // Check LUN defines. @@ -136,7 +134,6 @@ typedef enum #define LUN_ID_USB (MAX_LUN) //!< First dynamic LUN (USB host mass storage). //! @} - // Include LUN header files. #if LUN_0 == ENABLE #include LUN_0_INCLUDE @@ -166,13 +163,11 @@ typedef enum #include LUN_USB_INCLUDE #endif - // Check the configuration of write protection in conf_access.h. #ifndef GLOBAL_WR_PROTECT #error GLOBAL_WR_PROTECT must be defined as true or false in conf_access.h #endif - #if GLOBAL_WR_PROTECT == true //! Write protect. @@ -180,7 +175,6 @@ extern bool g_wr_protect; #endif - /*! \name Control Interface */ //! @{ @@ -279,7 +273,6 @@ extern const char *mem_name(U8 lun); //! @} - #if ACCESS_USB == true /*! \name MEM <-> USB Interface @@ -310,7 +303,6 @@ extern Ctrl_status usb_2_memory(U8 lun, U32 addr, U16 nb_sector); #endif // ACCESS_USB == true - #if ACCESS_MEM_TO_RAM == true /*! \name MEM <-> RAM Interface @@ -341,7 +333,6 @@ extern Ctrl_status ram_2_memory(U8 lun, U32 addr, const void *ram); #endif // ACCESS_MEM_TO_RAM == true - #if ACCESS_STREAM == true /*! \name Streaming MEM <-> MEM Interface diff --git a/Marlin/src/HAL/DUE/usb/genclk.h b/Marlin/src/HAL/DUE/usb/genclk.h index cde03bc0d1..45eba5873f 100644 --- a/Marlin/src/HAL/DUE/usb/genclk.h +++ b/Marlin/src/HAL/DUE/usb/genclk.h @@ -74,17 +74,17 @@ extern "C" { //@{ enum genclk_source { - GENCLK_PCK_SRC_SLCK_RC = 0, //!< Internal 32kHz RC oscillator as PCK source clock - GENCLK_PCK_SRC_SLCK_XTAL = 1, //!< External 32kHz crystal oscillator as PCK source clock - GENCLK_PCK_SRC_SLCK_BYPASS = 2, //!< External 32kHz bypass oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_4M_RC = 3, //!< Internal 4MHz RC oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_8M_RC = 4, //!< Internal 8MHz RC oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_12M_RC = 5, //!< Internal 12MHz RC oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_XTAL = 6, //!< External crystal oscillator as PCK source clock - GENCLK_PCK_SRC_MAINCK_BYPASS = 7, //!< External bypass oscillator as PCK source clock - GENCLK_PCK_SRC_PLLACK = 8, //!< Use PLLACK as PCK source clock - GENCLK_PCK_SRC_PLLBCK = 9, //!< Use PLLBCK as PCK source clock - GENCLK_PCK_SRC_MCK = 10, //!< Use Master Clk as PCK source clock + GENCLK_PCK_SRC_SLCK_RC = 0, //!< Internal 32kHz RC oscillator as PCK source clock + GENCLK_PCK_SRC_SLCK_XTAL = 1, //!< External 32kHz crystal oscillator as PCK source clock + GENCLK_PCK_SRC_SLCK_BYPASS = 2, //!< External 32kHz bypass oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_4M_RC = 3, //!< Internal 4MHz RC oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_8M_RC = 4, //!< Internal 8MHz RC oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_12M_RC = 5, //!< Internal 12MHz RC oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_XTAL = 6, //!< External crystal oscillator as PCK source clock + GENCLK_PCK_SRC_MAINCK_BYPASS = 7, //!< External bypass oscillator as PCK source clock + GENCLK_PCK_SRC_PLLACK = 8, //!< Use PLLACK as PCK source clock + GENCLK_PCK_SRC_PLLBCK = 9, //!< Use PLLBCK as PCK source clock + GENCLK_PCK_SRC_MCK = 10, //!< Use Master Clk as PCK source clock }; //@} @@ -93,176 +93,162 @@ enum genclk_source { //@{ enum genclk_divider { - GENCLK_PCK_PRES_1 = PMC_PCK_PRES_CLK_1, //!< Set PCK clock prescaler to 1 - GENCLK_PCK_PRES_2 = PMC_PCK_PRES_CLK_2, //!< Set PCK clock prescaler to 2 - GENCLK_PCK_PRES_4 = PMC_PCK_PRES_CLK_4, //!< Set PCK clock prescaler to 4 - GENCLK_PCK_PRES_8 = PMC_PCK_PRES_CLK_8, //!< Set PCK clock prescaler to 8 - GENCLK_PCK_PRES_16 = PMC_PCK_PRES_CLK_16, //!< Set PCK clock prescaler to 16 - GENCLK_PCK_PRES_32 = PMC_PCK_PRES_CLK_32, //!< Set PCK clock prescaler to 32 - GENCLK_PCK_PRES_64 = PMC_PCK_PRES_CLK_64, //!< Set PCK clock prescaler to 64 + GENCLK_PCK_PRES_1 = PMC_PCK_PRES_CLK_1, //!< Set PCK clock prescaler to 1 + GENCLK_PCK_PRES_2 = PMC_PCK_PRES_CLK_2, //!< Set PCK clock prescaler to 2 + GENCLK_PCK_PRES_4 = PMC_PCK_PRES_CLK_4, //!< Set PCK clock prescaler to 4 + GENCLK_PCK_PRES_8 = PMC_PCK_PRES_CLK_8, //!< Set PCK clock prescaler to 8 + GENCLK_PCK_PRES_16 = PMC_PCK_PRES_CLK_16, //!< Set PCK clock prescaler to 16 + GENCLK_PCK_PRES_32 = PMC_PCK_PRES_CLK_32, //!< Set PCK clock prescaler to 32 + GENCLK_PCK_PRES_64 = PMC_PCK_PRES_CLK_64, //!< Set PCK clock prescaler to 64 }; //@} struct genclk_config { - uint32_t ctrl; + uint32_t ctrl; }; -static inline void genclk_config_defaults(struct genclk_config *p_cfg, - uint32_t ul_id) -{ - ul_id = ul_id; - p_cfg->ctrl = 0; +static inline void genclk_config_defaults(struct genclk_config *p_cfg, uint32_t ul_id) { + ul_id = ul_id; + p_cfg->ctrl = 0; } -static inline void genclk_config_read(struct genclk_config *p_cfg, - uint32_t ul_id) -{ - p_cfg->ctrl = PMC->PMC_PCK[ul_id]; +static inline void genclk_config_read(struct genclk_config *p_cfg, uint32_t ul_id) { + p_cfg->ctrl = PMC->PMC_PCK[ul_id]; } -static inline void genclk_config_write(const struct genclk_config *p_cfg, - uint32_t ul_id) -{ - PMC->PMC_PCK[ul_id] = p_cfg->ctrl; +static inline void genclk_config_write(const struct genclk_config *p_cfg, uint32_t ul_id) { + PMC->PMC_PCK[ul_id] = p_cfg->ctrl; } //! \name Programmable Clock Source and Prescaler configuration //@{ -static inline void genclk_config_set_source(struct genclk_config *p_cfg, - enum genclk_source e_src) -{ - p_cfg->ctrl &= (~PMC_PCK_CSS_Msk); +static inline void genclk_config_set_source(struct genclk_config *p_cfg, enum genclk_source e_src) { + p_cfg->ctrl &= (~PMC_PCK_CSS_Msk); - switch (e_src) { - case GENCLK_PCK_SRC_SLCK_RC: - case GENCLK_PCK_SRC_SLCK_XTAL: - case GENCLK_PCK_SRC_SLCK_BYPASS: - p_cfg->ctrl |= (PMC_PCK_CSS_SLOW_CLK); - break; + switch (e_src) { + case GENCLK_PCK_SRC_SLCK_RC: + case GENCLK_PCK_SRC_SLCK_XTAL: + case GENCLK_PCK_SRC_SLCK_BYPASS: + p_cfg->ctrl |= (PMC_PCK_CSS_SLOW_CLK); + break; - case GENCLK_PCK_SRC_MAINCK_4M_RC: - case GENCLK_PCK_SRC_MAINCK_8M_RC: - case GENCLK_PCK_SRC_MAINCK_12M_RC: - case GENCLK_PCK_SRC_MAINCK_XTAL: - case GENCLK_PCK_SRC_MAINCK_BYPASS: - p_cfg->ctrl |= (PMC_PCK_CSS_MAIN_CLK); - break; + case GENCLK_PCK_SRC_MAINCK_4M_RC: + case GENCLK_PCK_SRC_MAINCK_8M_RC: + case GENCLK_PCK_SRC_MAINCK_12M_RC: + case GENCLK_PCK_SRC_MAINCK_XTAL: + case GENCLK_PCK_SRC_MAINCK_BYPASS: + p_cfg->ctrl |= (PMC_PCK_CSS_MAIN_CLK); + break; - case GENCLK_PCK_SRC_PLLACK: - p_cfg->ctrl |= (PMC_PCK_CSS_PLLA_CLK); - break; + case GENCLK_PCK_SRC_PLLACK: + p_cfg->ctrl |= (PMC_PCK_CSS_PLLA_CLK); + break; - case GENCLK_PCK_SRC_PLLBCK: - p_cfg->ctrl |= (PMC_PCK_CSS_UPLL_CLK); - break; + case GENCLK_PCK_SRC_PLLBCK: + p_cfg->ctrl |= (PMC_PCK_CSS_UPLL_CLK); + break; - case GENCLK_PCK_SRC_MCK: - p_cfg->ctrl |= (PMC_PCK_CSS_MCK); - break; - } + case GENCLK_PCK_SRC_MCK: + p_cfg->ctrl |= (PMC_PCK_CSS_MCK); + break; + } } -static inline void genclk_config_set_divider(struct genclk_config *p_cfg, - uint32_t e_divider) -{ - p_cfg->ctrl &= ~PMC_PCK_PRES_Msk; - p_cfg->ctrl |= e_divider; +static inline void genclk_config_set_divider(struct genclk_config *p_cfg, uint32_t e_divider) { + p_cfg->ctrl &= ~PMC_PCK_PRES_Msk; + p_cfg->ctrl |= e_divider; } //@} -static inline void genclk_enable(const struct genclk_config *p_cfg, - uint32_t ul_id) -{ - PMC->PMC_PCK[ul_id] = p_cfg->ctrl; - pmc_enable_pck(ul_id); +static inline void genclk_enable(const struct genclk_config *p_cfg, uint32_t ul_id) { + PMC->PMC_PCK[ul_id] = p_cfg->ctrl; + pmc_enable_pck(ul_id); } -static inline void genclk_disable(uint32_t ul_id) -{ - pmc_disable_pck(ul_id); +static inline void genclk_disable(uint32_t ul_id) { + pmc_disable_pck(ul_id); } -static inline void genclk_enable_source(enum genclk_source e_src) -{ - switch (e_src) { - case GENCLK_PCK_SRC_SLCK_RC: - if (!osc_is_ready(OSC_SLCK_32K_RC)) { - osc_enable(OSC_SLCK_32K_RC); - osc_wait_ready(OSC_SLCK_32K_RC); - } - break; +static inline void genclk_enable_source(enum genclk_source e_src) { + switch (e_src) { + case GENCLK_PCK_SRC_SLCK_RC: + if (!osc_is_ready(OSC_SLCK_32K_RC)) { + osc_enable(OSC_SLCK_32K_RC); + osc_wait_ready(OSC_SLCK_32K_RC); + } + break; - case GENCLK_PCK_SRC_SLCK_XTAL: - if (!osc_is_ready(OSC_SLCK_32K_XTAL)) { - osc_enable(OSC_SLCK_32K_XTAL); - osc_wait_ready(OSC_SLCK_32K_XTAL); - } - break; + case GENCLK_PCK_SRC_SLCK_XTAL: + if (!osc_is_ready(OSC_SLCK_32K_XTAL)) { + osc_enable(OSC_SLCK_32K_XTAL); + osc_wait_ready(OSC_SLCK_32K_XTAL); + } + break; - case GENCLK_PCK_SRC_SLCK_BYPASS: - if (!osc_is_ready(OSC_SLCK_32K_BYPASS)) { - osc_enable(OSC_SLCK_32K_BYPASS); - osc_wait_ready(OSC_SLCK_32K_BYPASS); - } - break; + case GENCLK_PCK_SRC_SLCK_BYPASS: + if (!osc_is_ready(OSC_SLCK_32K_BYPASS)) { + osc_enable(OSC_SLCK_32K_BYPASS); + osc_wait_ready(OSC_SLCK_32K_BYPASS); + } + break; - case GENCLK_PCK_SRC_MAINCK_4M_RC: - if (!osc_is_ready(OSC_MAINCK_4M_RC)) { - osc_enable(OSC_MAINCK_4M_RC); - osc_wait_ready(OSC_MAINCK_4M_RC); - } - break; + case GENCLK_PCK_SRC_MAINCK_4M_RC: + if (!osc_is_ready(OSC_MAINCK_4M_RC)) { + osc_enable(OSC_MAINCK_4M_RC); + osc_wait_ready(OSC_MAINCK_4M_RC); + } + break; - case GENCLK_PCK_SRC_MAINCK_8M_RC: - if (!osc_is_ready(OSC_MAINCK_8M_RC)) { - osc_enable(OSC_MAINCK_8M_RC); - osc_wait_ready(OSC_MAINCK_8M_RC); - } - break; + case GENCLK_PCK_SRC_MAINCK_8M_RC: + if (!osc_is_ready(OSC_MAINCK_8M_RC)) { + osc_enable(OSC_MAINCK_8M_RC); + osc_wait_ready(OSC_MAINCK_8M_RC); + } + break; - case GENCLK_PCK_SRC_MAINCK_12M_RC: - if (!osc_is_ready(OSC_MAINCK_12M_RC)) { - osc_enable(OSC_MAINCK_12M_RC); - osc_wait_ready(OSC_MAINCK_12M_RC); - } - break; + case GENCLK_PCK_SRC_MAINCK_12M_RC: + if (!osc_is_ready(OSC_MAINCK_12M_RC)) { + osc_enable(OSC_MAINCK_12M_RC); + osc_wait_ready(OSC_MAINCK_12M_RC); + } + break; - case GENCLK_PCK_SRC_MAINCK_XTAL: - if (!osc_is_ready(OSC_MAINCK_XTAL)) { - osc_enable(OSC_MAINCK_XTAL); - osc_wait_ready(OSC_MAINCK_XTAL); - } - break; + case GENCLK_PCK_SRC_MAINCK_XTAL: + if (!osc_is_ready(OSC_MAINCK_XTAL)) { + osc_enable(OSC_MAINCK_XTAL); + osc_wait_ready(OSC_MAINCK_XTAL); + } + break; - case GENCLK_PCK_SRC_MAINCK_BYPASS: - if (!osc_is_ready(OSC_MAINCK_BYPASS)) { - osc_enable(OSC_MAINCK_BYPASS); - osc_wait_ready(OSC_MAINCK_BYPASS); - } - break; + case GENCLK_PCK_SRC_MAINCK_BYPASS: + if (!osc_is_ready(OSC_MAINCK_BYPASS)) { + osc_enable(OSC_MAINCK_BYPASS); + osc_wait_ready(OSC_MAINCK_BYPASS); + } + break; -#ifdef CONFIG_PLL0_SOURCE - case GENCLK_PCK_SRC_PLLACK: - pll_enable_config_defaults(0); - break; -#endif + #ifdef CONFIG_PLL0_SOURCE + case GENCLK_PCK_SRC_PLLACK: + pll_enable_config_defaults(0); + break; + #endif -#ifdef CONFIG_PLL1_SOURCE - case GENCLK_PCK_SRC_PLLBCK: - pll_enable_config_defaults(1); - break; -#endif + #ifdef CONFIG_PLL1_SOURCE + case GENCLK_PCK_SRC_PLLBCK: + pll_enable_config_defaults(1); + break; + #endif - case GENCLK_PCK_SRC_MCK: - break; + case GENCLK_PCK_SRC_MCK: + break; - default: - Assert(false); - break; - } + default: + Assert(false); + break; + } } //! @} diff --git a/Marlin/src/HAL/DUE/usb/mrepeat.h b/Marlin/src/HAL/DUE/usb/mrepeat.h index 8363d9cde3..10a8237545 100644 --- a/Marlin/src/HAL/DUE/usb/mrepeat.h +++ b/Marlin/src/HAL/DUE/usb/mrepeat.h @@ -57,7 +57,6 @@ #include "preprocessor.h" - //! Maximal number of repetitions supported by MREPEAT. #define MREPEAT_LIMIT 256 diff --git a/Marlin/src/HAL/DUE/usb/osc.h b/Marlin/src/HAL/DUE/usb/osc.h index 953bcbbed1..1585018ed8 100644 --- a/Marlin/src/HAL/DUE/usb/osc.h +++ b/Marlin/src/HAL/DUE/usb/osc.h @@ -62,28 +62,28 @@ extern "C" { * should be defined by the board code, otherwise default value are used. */ #ifndef BOARD_FREQ_SLCK_XTAL -# warning The board slow clock xtal frequency has not been defined. -# define BOARD_FREQ_SLCK_XTAL (32768UL) + #warning The board slow clock xtal frequency has not been defined. + #define BOARD_FREQ_SLCK_XTAL (32768UL) #endif #ifndef BOARD_FREQ_SLCK_BYPASS -# warning The board slow clock bypass frequency has not been defined. -# define BOARD_FREQ_SLCK_BYPASS (32768UL) + #warning The board slow clock bypass frequency has not been defined. + #define BOARD_FREQ_SLCK_BYPASS (32768UL) #endif #ifndef BOARD_FREQ_MAINCK_XTAL -# warning The board main clock xtal frequency has not been defined. -# define BOARD_FREQ_MAINCK_XTAL (12000000UL) + #warning The board main clock xtal frequency has not been defined. + #define BOARD_FREQ_MAINCK_XTAL (12000000UL) #endif #ifndef BOARD_FREQ_MAINCK_BYPASS -# warning The board main clock bypass frequency has not been defined. -# define BOARD_FREQ_MAINCK_BYPASS (12000000UL) + #warning The board main clock bypass frequency has not been defined. + #define BOARD_FREQ_MAINCK_BYPASS (12000000UL) #endif #ifndef BOARD_OSC_STARTUP_US -# warning The board main clock xtal startup time has not been defined. -# define BOARD_OSC_STARTUP_US (15625UL) + #warning The board main clock xtal startup time has not been defined. + #define BOARD_OSC_STARTUP_US (15625UL) #endif /** @@ -115,122 +115,116 @@ extern "C" { #define OSC_MAINCK_BYPASS_HZ BOARD_FREQ_MAINCK_BYPASS //!< External bypass oscillator. //@} -static inline void osc_enable(uint32_t ul_id) -{ - switch (ul_id) { - case OSC_SLCK_32K_RC: - break; +static inline void osc_enable(uint32_t ul_id) { + switch (ul_id) { + case OSC_SLCK_32K_RC: + break; - case OSC_SLCK_32K_XTAL: - pmc_switch_sclk_to_32kxtal(PMC_OSC_XTAL); - break; + case OSC_SLCK_32K_XTAL: + pmc_switch_sclk_to_32kxtal(PMC_OSC_XTAL); + break; - case OSC_SLCK_32K_BYPASS: - pmc_switch_sclk_to_32kxtal(PMC_OSC_BYPASS); - break; + case OSC_SLCK_32K_BYPASS: + pmc_switch_sclk_to_32kxtal(PMC_OSC_BYPASS); + break; + case OSC_MAINCK_4M_RC: + pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_4_MHz); + break; - case OSC_MAINCK_4M_RC: - pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_4_MHz); - break; + case OSC_MAINCK_8M_RC: + pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_8_MHz); + break; - case OSC_MAINCK_8M_RC: - pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_8_MHz); - break; + case OSC_MAINCK_12M_RC: + pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_12_MHz); + break; - case OSC_MAINCK_12M_RC: - pmc_switch_mainck_to_fastrc(CKGR_MOR_MOSCRCF_12_MHz); - break; + case OSC_MAINCK_XTAL: + pmc_switch_mainck_to_xtal(PMC_OSC_XTAL/*, + pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US, + OSC_SLCK_32K_RC_HZ)*/); + break; - - case OSC_MAINCK_XTAL: - pmc_switch_mainck_to_xtal(PMC_OSC_XTAL/*, - pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US, - OSC_SLCK_32K_RC_HZ)*/); - break; - - case OSC_MAINCK_BYPASS: - pmc_switch_mainck_to_xtal(PMC_OSC_BYPASS/*, - pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US, - OSC_SLCK_32K_RC_HZ)*/); - break; - } + case OSC_MAINCK_BYPASS: + pmc_switch_mainck_to_xtal(PMC_OSC_BYPASS/*, + pmc_us_to_moscxtst(BOARD_OSC_STARTUP_US, + OSC_SLCK_32K_RC_HZ)*/); + break; + } } -static inline void osc_disable(uint32_t ul_id) -{ - switch (ul_id) { - case OSC_SLCK_32K_RC: - case OSC_SLCK_32K_XTAL: - case OSC_SLCK_32K_BYPASS: - break; +static inline void osc_disable(uint32_t ul_id) { + switch (ul_id) { + case OSC_SLCK_32K_RC: + case OSC_SLCK_32K_XTAL: + case OSC_SLCK_32K_BYPASS: + break; - case OSC_MAINCK_4M_RC: - case OSC_MAINCK_8M_RC: - case OSC_MAINCK_12M_RC: - pmc_osc_disable_fastrc(); - break; + case OSC_MAINCK_4M_RC: + case OSC_MAINCK_8M_RC: + case OSC_MAINCK_12M_RC: + pmc_osc_disable_fastrc(); + break; - case OSC_MAINCK_XTAL: - pmc_osc_disable_xtal(PMC_OSC_XTAL); - break; + case OSC_MAINCK_XTAL: + pmc_osc_disable_xtal(PMC_OSC_XTAL); + break; - case OSC_MAINCK_BYPASS: - pmc_osc_disable_xtal(PMC_OSC_BYPASS); - break; - } + case OSC_MAINCK_BYPASS: + pmc_osc_disable_xtal(PMC_OSC_BYPASS); + break; + } } -static inline bool osc_is_ready(uint32_t ul_id) -{ - switch (ul_id) { - case OSC_SLCK_32K_RC: - return 1; +static inline bool osc_is_ready(uint32_t ul_id) { + switch (ul_id) { + case OSC_SLCK_32K_RC: + return 1; - case OSC_SLCK_32K_XTAL: - case OSC_SLCK_32K_BYPASS: - return pmc_osc_is_ready_32kxtal(); + case OSC_SLCK_32K_XTAL: + case OSC_SLCK_32K_BYPASS: + return pmc_osc_is_ready_32kxtal(); - case OSC_MAINCK_4M_RC: - case OSC_MAINCK_8M_RC: - case OSC_MAINCK_12M_RC: - case OSC_MAINCK_XTAL: - case OSC_MAINCK_BYPASS: - return pmc_osc_is_ready_mainck(); - } + case OSC_MAINCK_4M_RC: + case OSC_MAINCK_8M_RC: + case OSC_MAINCK_12M_RC: + case OSC_MAINCK_XTAL: + case OSC_MAINCK_BYPASS: + return pmc_osc_is_ready_mainck(); + } - return 0; + return 0; } -static inline uint32_t osc_get_rate(uint32_t ul_id) -{ - switch (ul_id) { - case OSC_SLCK_32K_RC: - return OSC_SLCK_32K_RC_HZ; +static inline uint32_t osc_get_rate(uint32_t ul_id) { + switch (ul_id) { + case OSC_SLCK_32K_RC: + return OSC_SLCK_32K_RC_HZ; - case OSC_SLCK_32K_XTAL: - return BOARD_FREQ_SLCK_XTAL; + case OSC_SLCK_32K_XTAL: + return BOARD_FREQ_SLCK_XTAL; - case OSC_SLCK_32K_BYPASS: - return BOARD_FREQ_SLCK_BYPASS; + case OSC_SLCK_32K_BYPASS: + return BOARD_FREQ_SLCK_BYPASS; - case OSC_MAINCK_4M_RC: - return OSC_MAINCK_4M_RC_HZ; + case OSC_MAINCK_4M_RC: + return OSC_MAINCK_4M_RC_HZ; - case OSC_MAINCK_8M_RC: - return OSC_MAINCK_8M_RC_HZ; + case OSC_MAINCK_8M_RC: + return OSC_MAINCK_8M_RC_HZ; - case OSC_MAINCK_12M_RC: - return OSC_MAINCK_12M_RC_HZ; + case OSC_MAINCK_12M_RC: + return OSC_MAINCK_12M_RC_HZ; - case OSC_MAINCK_XTAL: - return BOARD_FREQ_MAINCK_XTAL; + case OSC_MAINCK_XTAL: + return BOARD_FREQ_MAINCK_XTAL; - case OSC_MAINCK_BYPASS: - return BOARD_FREQ_MAINCK_BYPASS; - } + case OSC_MAINCK_BYPASS: + return BOARD_FREQ_MAINCK_BYPASS; + } - return 0; + return 0; } /** @@ -241,11 +235,10 @@ static inline uint32_t osc_get_rate(uint32_t ul_id) * * \param id A number identifying the oscillator to wait for. */ -static inline void osc_wait_ready(uint8_t id) -{ - while (!osc_is_ready(id)) { - /* Do nothing */ - } +static inline void osc_wait_ready(uint8_t id) { + while (!osc_is_ready(id)) { + /* Do nothing */ + } } //! @} diff --git a/Marlin/src/HAL/DUE/usb/pll.h b/Marlin/src/HAL/DUE/usb/pll.h index 8eaf27672b..d25a1f65d0 100644 --- a/Marlin/src/HAL/DUE/usb/pll.h +++ b/Marlin/src/HAL/DUE/usb/pll.h @@ -77,22 +77,22 @@ extern "C" { #define PLL_COUNT 0x3FU enum pll_source { - PLL_SRC_MAINCK_4M_RC = OSC_MAINCK_4M_RC, //!< Internal 4MHz RC oscillator. - PLL_SRC_MAINCK_8M_RC = OSC_MAINCK_8M_RC, //!< Internal 8MHz RC oscillator. - PLL_SRC_MAINCK_12M_RC = OSC_MAINCK_12M_RC, //!< Internal 12MHz RC oscillator. - PLL_SRC_MAINCK_XTAL = OSC_MAINCK_XTAL, //!< External crystal oscillator. - PLL_SRC_MAINCK_BYPASS = OSC_MAINCK_BYPASS, //!< External bypass oscillator. - PLL_NR_SOURCES, //!< Number of PLL sources. + PLL_SRC_MAINCK_4M_RC = OSC_MAINCK_4M_RC, //!< Internal 4MHz RC oscillator. + PLL_SRC_MAINCK_8M_RC = OSC_MAINCK_8M_RC, //!< Internal 8MHz RC oscillator. + PLL_SRC_MAINCK_12M_RC = OSC_MAINCK_12M_RC, //!< Internal 12MHz RC oscillator. + PLL_SRC_MAINCK_XTAL = OSC_MAINCK_XTAL, //!< External crystal oscillator. + PLL_SRC_MAINCK_BYPASS = OSC_MAINCK_BYPASS, //!< External bypass oscillator. + PLL_NR_SOURCES, //!< Number of PLL sources. }; struct pll_config { - uint32_t ctrl; + uint32_t ctrl; }; #define pll_get_default_rate(pll_id) \ - ((osc_get_rate(CONFIG_PLL##pll_id##_SOURCE) \ - * CONFIG_PLL##pll_id##_MUL) \ - / CONFIG_PLL##pll_id##_DIV) + ((osc_get_rate(CONFIG_PLL##pll_id##_SOURCE) \ + * CONFIG_PLL##pll_id##_MUL) \ + / CONFIG_PLL##pll_id##_DIV) /* Force UTMI PLL parameters (Hardware defined) */ #ifdef CONFIG_PLL1_SOURCE @@ -113,145 +113,130 @@ struct pll_config { * is hidden in this implementation. Use mul as mul effective value. */ static inline void pll_config_init(struct pll_config *p_cfg, - enum pll_source e_src, uint32_t ul_div, uint32_t ul_mul) -{ - uint32_t vco_hz; + enum pll_source e_src, uint32_t ul_div, uint32_t ul_mul) { + uint32_t vco_hz; - Assert(e_src < PLL_NR_SOURCES); + Assert(e_src < PLL_NR_SOURCES); - if (ul_div == 0 && ul_mul == 0) { /* Must only be true for UTMI PLL */ - p_cfg->ctrl = CKGR_UCKR_UPLLCOUNT(PLL_COUNT); - } else { /* PLLA */ - /* Calculate internal VCO frequency */ - vco_hz = osc_get_rate(e_src) / ul_div; - Assert(vco_hz >= PLL_INPUT_MIN_HZ); - Assert(vco_hz <= PLL_INPUT_MAX_HZ); + if (ul_div == 0 && ul_mul == 0) { /* Must only be true for UTMI PLL */ + p_cfg->ctrl = CKGR_UCKR_UPLLCOUNT(PLL_COUNT); + } + else { /* PLLA */ + /* Calculate internal VCO frequency */ + vco_hz = osc_get_rate(e_src) / ul_div; + Assert(vco_hz >= PLL_INPUT_MIN_HZ); + Assert(vco_hz <= PLL_INPUT_MAX_HZ); - vco_hz *= ul_mul; - Assert(vco_hz >= PLL_OUTPUT_MIN_HZ); - Assert(vco_hz <= PLL_OUTPUT_MAX_HZ); + vco_hz *= ul_mul; + Assert(vco_hz >= PLL_OUTPUT_MIN_HZ); + Assert(vco_hz <= PLL_OUTPUT_MAX_HZ); - /* PMC hardware will automatically make it mul+1 */ - p_cfg->ctrl = CKGR_PLLAR_MULA(ul_mul - 1) | CKGR_PLLAR_DIVA(ul_div) | CKGR_PLLAR_PLLACOUNT(PLL_COUNT); - } + /* PMC hardware will automatically make it mul+1 */ + p_cfg->ctrl = CKGR_PLLAR_MULA(ul_mul - 1) | CKGR_PLLAR_DIVA(ul_div) | CKGR_PLLAR_PLLACOUNT(PLL_COUNT); + } } -#define pll_config_defaults(cfg, pll_id) \ - pll_config_init(cfg, \ - CONFIG_PLL##pll_id##_SOURCE, \ - CONFIG_PLL##pll_id##_DIV, \ - CONFIG_PLL##pll_id##_MUL) +#define pll_config_defaults(cfg, pll_id) \ + pll_config_init(cfg, \ + CONFIG_PLL##pll_id##_SOURCE, \ + CONFIG_PLL##pll_id##_DIV, \ + CONFIG_PLL##pll_id##_MUL) -static inline void pll_config_read(struct pll_config *p_cfg, uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); - - if (ul_pll_id == PLLA_ID) { - p_cfg->ctrl = PMC->CKGR_PLLAR; - } else { - p_cfg->ctrl = PMC->CKGR_UCKR; - } +static inline void pll_config_read(struct pll_config *p_cfg, uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); + p_cfg->ctrl = ul_pll_id == PLLA_ID ? PMC->CKGR_PLLAR : PMC->CKGR_UCKR; } -static inline void pll_config_write(const struct pll_config *p_cfg, uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); +static inline void pll_config_write(const struct pll_config *p_cfg, uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); - if (ul_pll_id == PLLA_ID) { - pmc_disable_pllack(); // Always stop PLL first! - PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl; - } else { - PMC->CKGR_UCKR = p_cfg->ctrl; - } + if (ul_pll_id == PLLA_ID) { + pmc_disable_pllack(); // Always stop PLL first! + PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl; + } + else + PMC->CKGR_UCKR = p_cfg->ctrl; } -static inline void pll_enable(const struct pll_config *p_cfg, uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); +static inline void pll_enable(const struct pll_config *p_cfg, uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); - if (ul_pll_id == PLLA_ID) { - pmc_disable_pllack(); // Always stop PLL first! - PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl; - } else { - PMC->CKGR_UCKR = p_cfg->ctrl | CKGR_UCKR_UPLLEN; - } + if (ul_pll_id == PLLA_ID) { + pmc_disable_pllack(); // Always stop PLL first! + PMC->CKGR_PLLAR = CKGR_PLLAR_ONE | p_cfg->ctrl; + } + else + PMC->CKGR_UCKR = p_cfg->ctrl | CKGR_UCKR_UPLLEN; } /** * \note This will only disable the selected PLL, not the underlying oscillator (mainck). */ -static inline void pll_disable(uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); +static inline void pll_disable(uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); - if (ul_pll_id == PLLA_ID) { - pmc_disable_pllack(); - } else { - PMC->CKGR_UCKR &= ~CKGR_UCKR_UPLLEN; - } + if (ul_pll_id == PLLA_ID) + pmc_disable_pllack(); + else + PMC->CKGR_UCKR &= ~CKGR_UCKR_UPLLEN; } -static inline uint32_t pll_is_locked(uint32_t ul_pll_id) -{ - Assert(ul_pll_id < NR_PLLS); +static inline uint32_t pll_is_locked(uint32_t ul_pll_id) { + Assert(ul_pll_id < NR_PLLS); - if (ul_pll_id == PLLA_ID) { - return pmc_is_locked_pllack(); - } else { - return pmc_is_locked_upll(); - } + if (ul_pll_id == PLLA_ID) + return pmc_is_locked_pllack(); + else + return pmc_is_locked_upll(); } -static inline void pll_enable_source(enum pll_source e_src) -{ - switch (e_src) { - case PLL_SRC_MAINCK_4M_RC: - case PLL_SRC_MAINCK_8M_RC: - case PLL_SRC_MAINCK_12M_RC: - case PLL_SRC_MAINCK_XTAL: - case PLL_SRC_MAINCK_BYPASS: - osc_enable(e_src); - osc_wait_ready(e_src); - break; +static inline void pll_enable_source(enum pll_source e_src) { + switch (e_src) { + case PLL_SRC_MAINCK_4M_RC: + case PLL_SRC_MAINCK_8M_RC: + case PLL_SRC_MAINCK_12M_RC: + case PLL_SRC_MAINCK_XTAL: + case PLL_SRC_MAINCK_BYPASS: + osc_enable(e_src); + osc_wait_ready(e_src); + break; - default: - Assert(false); - break; - } + default: + Assert(false); + break; + } } -static inline void pll_enable_config_defaults(unsigned int ul_pll_id) -{ - struct pll_config pllcfg; +static inline void pll_enable_config_defaults(unsigned int ul_pll_id) { + struct pll_config pllcfg; - if (pll_is_locked(ul_pll_id)) { - return; // Pll already running - } - switch (ul_pll_id) { -#ifdef CONFIG_PLL0_SOURCE - case 0: - pll_enable_source(CONFIG_PLL0_SOURCE); - pll_config_init(&pllcfg, - CONFIG_PLL0_SOURCE, - CONFIG_PLL0_DIV, - CONFIG_PLL0_MUL); - break; -#endif -#ifdef CONFIG_PLL1_SOURCE - case 1: - pll_enable_source(CONFIG_PLL1_SOURCE); - pll_config_init(&pllcfg, - CONFIG_PLL1_SOURCE, - CONFIG_PLL1_DIV, - CONFIG_PLL1_MUL); - break; -#endif - default: - Assert(false); - break; - } - pll_enable(&pllcfg, ul_pll_id); - while (!pll_is_locked(ul_pll_id)); + if (pll_is_locked(ul_pll_id)) return; // Pll already running + + switch (ul_pll_id) { + #ifdef CONFIG_PLL0_SOURCE + case 0: + pll_enable_source(CONFIG_PLL0_SOURCE); + pll_config_init(&pllcfg, + CONFIG_PLL0_SOURCE, + CONFIG_PLL0_DIV, + CONFIG_PLL0_MUL); + break; + #endif + #ifdef CONFIG_PLL1_SOURCE + case 1: + pll_enable_source(CONFIG_PLL1_SOURCE); + pll_config_init(&pllcfg, + CONFIG_PLL1_SOURCE, + CONFIG_PLL1_DIV, + CONFIG_PLL1_MUL); + break; + #endif + default: + Assert(false); + break; + } + pll_enable(&pllcfg, ul_pll_id); + while (!pll_is_locked(ul_pll_id)); } /** @@ -264,15 +249,12 @@ static inline void pll_enable_config_defaults(unsigned int ul_pll_id) * \retval STATUS_OK The PLL is now locked. * \retval ERR_TIMEOUT Timed out waiting for PLL to become locked. */ -static inline int pll_wait_for_lock(unsigned int pll_id) -{ - Assert(pll_id < NR_PLLS); +static inline int pll_wait_for_lock(unsigned int pll_id) { + Assert(pll_id < NR_PLLS); - while (!pll_is_locked(pll_id)) { - /* Do nothing */ - } + while (!pll_is_locked(pll_id)) { /* Do nothing */ } - return 0; + return 0; } //! @} diff --git a/Marlin/src/HAL/DUE/usb/preprocessor.h b/Marlin/src/HAL/DUE/usb/preprocessor.h index c12d01cb64..fe796c4fb8 100644 --- a/Marlin/src/HAL/DUE/usb/preprocessor.h +++ b/Marlin/src/HAL/DUE/usb/preprocessor.h @@ -51,5 +51,4 @@ #include "stringz.h" #include "mrepeat.h" - #endif // _PREPROCESSOR_H_ diff --git a/Marlin/src/HAL/DUE/usb/sbc_protocol.h b/Marlin/src/HAL/DUE/usb/sbc_protocol.h index ab845739fd..cdd4caa3cd 100644 --- a/Marlin/src/HAL/DUE/usb/sbc_protocol.h +++ b/Marlin/src/HAL/DUE/usb/sbc_protocol.h @@ -57,7 +57,6 @@ #ifndef _SBC_PROTOCOL_H_ #define _SBC_PROTOCOL_H_ - /** * \ingroup usb_msc_protocol * \defgroup usb_sbc_protocol SCSI Block Commands protocol definitions @@ -81,82 +80,81 @@ //@{ enum scsi_sbc_mode { - SCSI_MS_MODE_RW_ERR_RECOV = 0x01, //!< Read-Write Error Recovery mode page - SCSI_MS_MODE_FORMAT_DEVICE = 0x03, //!< Format Device mode page - SCSI_MS_MODE_FLEXIBLE_DISK = 0x05, //!< Flexible Disk mode page - SCSI_MS_MODE_CACHING = 0x08, //!< Caching mode page + SCSI_MS_MODE_RW_ERR_RECOV = 0x01, //!< Read-Write Error Recovery mode page + SCSI_MS_MODE_FORMAT_DEVICE = 0x03, //!< Format Device mode page + SCSI_MS_MODE_FLEXIBLE_DISK = 0x05, //!< Flexible Disk mode page + SCSI_MS_MODE_CACHING = 0x08, //!< Caching mode page }; - //! \name SBC-2 Device-Specific Parameter //@{ -#define SCSI_MS_SBC_WP 0x80 //!< Write Protected -#define SCSI_MS_SBC_DPOFUA 0x10 //!< DPO and FUA supported +#define SCSI_MS_SBC_WP 0x80 //!< Write Protected +#define SCSI_MS_SBC_DPOFUA 0x10 //!< DPO and FUA supported //@} /** * \brief SBC-2 Short LBA mode parameter block descriptor */ struct sbc_slba_block_desc { - be32_t nr_blocks; //!< Number of Blocks - be32_t block_len; //!< Block Length -#define SBC_SLBA_BLOCK_LEN_MASK 0x00FFFFFFU //!< Mask reserved bits + be32_t nr_blocks; //!< Number of Blocks + be32_t block_len; //!< Block Length +#define SBC_SLBA_BLOCK_LEN_MASK 0x00FFFFFFU //!< Mask reserved bits }; /** * \brief SBC-2 Caching mode page */ struct sbc_caching_mode_page { - uint8_t page_code; - uint8_t page_length; - uint8_t flags2; -#define SBC_MP_CACHE_IC (1 << 7) //!< Initiator Control -#define SBC_MP_CACHE_ABPF (1 << 6) //!< Abort Pre-Fetch -#define SBC_MP_CACHE_CAP (1 << 5) //!< Catching Analysis Permitted -#define SBC_MP_CACHE_DISC (1 << 4) //!< Discontinuity -#define SBC_MP_CACHE_SIZE (1 << 3) //!< Size enable -#define SBC_MP_CACHE_WCE (1 << 2) //!< Write back Cache Enable -#define SBC_MP_CACHE_MF (1 << 1) //!< Multiplication Factor -#define SBC_MP_CACHE_RCD (1 << 0) //!< Read Cache Disable - uint8_t retention; - be16_t dis_pf_transfer_len; - be16_t min_prefetch; - be16_t max_prefetch; - be16_t max_prefetch_ceil; - uint8_t flags12; -#define SBC_MP_CACHE_FSW (1 << 7) //!< Force Sequential Write -#define SBC_MP_CACHE_LBCSS (1 << 6) //!< Logical Blk Cache Seg Sz -#define SBC_MP_CACHE_DRA (1 << 5) //!< Disable Read-Ahead -#define SBC_MP_CACHE_NV_DIS (1 << 0) //!< Non-Volatile Cache Disable - uint8_t nr_cache_segments; - be16_t cache_segment_size; - uint8_t reserved[4]; + uint8_t page_code; + uint8_t page_length; + uint8_t flags2; +#define SBC_MP_CACHE_IC (1 << 7) //!< Initiator Control +#define SBC_MP_CACHE_ABPF (1 << 6) //!< Abort Pre-Fetch +#define SBC_MP_CACHE_CAP (1 << 5) //!< Catching Analysis Permitted +#define SBC_MP_CACHE_DISC (1 << 4) //!< Discontinuity +#define SBC_MP_CACHE_SIZE (1 << 3) //!< Size enable +#define SBC_MP_CACHE_WCE (1 << 2) //!< Write back Cache Enable +#define SBC_MP_CACHE_MF (1 << 1) //!< Multiplication Factor +#define SBC_MP_CACHE_RCD (1 << 0) //!< Read Cache Disable + uint8_t retention; + be16_t dis_pf_transfer_len; + be16_t min_prefetch; + be16_t max_prefetch; + be16_t max_prefetch_ceil; + uint8_t flags12; +#define SBC_MP_CACHE_FSW (1 << 7) //!< Force Sequential Write +#define SBC_MP_CACHE_LBCSS (1 << 6) //!< Logical Blk Cache Seg Sz +#define SBC_MP_CACHE_DRA (1 << 5) //!< Disable Read-Ahead +#define SBC_MP_CACHE_NV_DIS (1 << 0) //!< Non-Volatile Cache Disable + uint8_t nr_cache_segments; + be16_t cache_segment_size; + uint8_t reserved[4]; }; /** * \brief SBC-2 Read-Write Error Recovery mode page */ struct sbc_rdwr_error_recovery_mode_page { - uint8_t page_code; - uint8_t page_length; -#define SPC_MP_RW_ERR_RECOV_PAGE_LENGTH 0x0A - uint8_t flags1; -#define SBC_MP_RW_ERR_RECOV_AWRE (1 << 7) -#define SBC_MP_RW_ERR_RECOV_ARRE (1 << 6) -#define SBC_MP_RW_ERR_RECOV_TB (1 << 5) -#define SBC_MP_RW_ERR_RECOV_RC (1 << 4) -#define SBC_MP_RW_ERR_RECOV_ERR (1 << 3) -#define SBC_MP_RW_ERR_RECOV_PER (1 << 2) -#define SBC_MP_RW_ERR_RECOV_DTE (1 << 1) -#define SBC_MP_RW_ERR_RECOV_DCR (1 << 0) - uint8_t read_retry_count; - uint8_t correction_span; - uint8_t head_offset_count; - uint8_t data_strobe_offset_count; - uint8_t flags2; - uint8_t write_retry_count; - uint8_t flags3; - be16_t recovery_time_limit; + uint8_t page_code; + uint8_t page_length; + #define SPC_MP_RW_ERR_RECOV_PAGE_LENGTH 0x0A + uint8_t flags1; + #define SBC_MP_RW_ERR_RECOV_AWRE (1 << 7) + #define SBC_MP_RW_ERR_RECOV_ARRE (1 << 6) + #define SBC_MP_RW_ERR_RECOV_TB (1 << 5) + #define SBC_MP_RW_ERR_RECOV_RC (1 << 4) + #define SBC_MP_RW_ERR_RECOV_ERR (1 << 3) + #define SBC_MP_RW_ERR_RECOV_PER (1 << 2) + #define SBC_MP_RW_ERR_RECOV_DTE (1 << 1) + #define SBC_MP_RW_ERR_RECOV_DCR (1 << 0) + uint8_t read_retry_count; + uint8_t correction_span; + uint8_t head_offset_count; + uint8_t data_strobe_offset_count; + uint8_t flags2; + uint8_t write_retry_count; + uint8_t flags3; + be16_t recovery_time_limit; }; //@} @@ -164,8 +162,8 @@ struct sbc_rdwr_error_recovery_mode_page { * \brief SBC-2 READ CAPACITY (10) parameter data */ struct sbc_read_capacity10_data { - be32_t max_lba; //!< LBA of last logical block - be32_t block_len; //!< Number of bytes in the last logical block + be32_t max_lba; //!< LBA of last logical block + be32_t block_len; //!< Number of bytes in the last logical block }; //@} diff --git a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h index 553fd3c29a..c0d3c925e8 100644 --- a/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h +++ b/Marlin/src/HAL/DUE/usb/sd_mmc_spi_mem.h @@ -45,7 +45,6 @@ * Support and FAQ: visit Atmel Support */ - #ifndef _SD_MMC_SPI_MEM_H_ #define _SD_MMC_SPI_MEM_H_ @@ -63,17 +62,14 @@ #error sd_mmc_spi_mem.h is #included although SD_MMC_SPI_MEM is disabled #endif - #include "ctrl_access.h" - //_____ D E F I N I T I O N S ______________________________________________ #define SD_MMC_REMOVED 0 #define SD_MMC_INSERTED 1 #define SD_MMC_REMOVING 2 - //---- CONTROL FUNCTIONS ---- //! //! @brief This function initializes the hw/sw resources required to drive the SD_MMC_SPI. @@ -133,7 +129,6 @@ extern bool sd_mmc_spi_wr_protect(void); //! extern bool sd_mmc_spi_removal(void); - //---- ACCESS DATA FUNCTIONS ---- #if ACCESS_USB == true diff --git a/Marlin/src/HAL/DUE/usb/spc_protocol.h b/Marlin/src/HAL/DUE/usb/spc_protocol.h index d67cc5c788..808c388f4f 100644 --- a/Marlin/src/HAL/DUE/usb/spc_protocol.h +++ b/Marlin/src/HAL/DUE/usb/spc_protocol.h @@ -59,23 +59,23 @@ //! \name SCSI commands defined by SPC-2 //@{ -#define SPC_TEST_UNIT_READY 0x00 -#define SPC_REQUEST_SENSE 0x03 -#define SPC_INQUIRY 0x12 -#define SPC_MODE_SELECT6 0x15 -#define SPC_MODE_SENSE6 0x1A -#define SPC_SEND_DIAGNOSTIC 0x1D -#define SPC_PREVENT_ALLOW_MEDIUM_REMOVAL 0x1E -#define SPC_MODE_SENSE10 0x5A -#define SPC_REPORT_LUNS 0xA0 +#define SPC_TEST_UNIT_READY 0x00 +#define SPC_REQUEST_SENSE 0x03 +#define SPC_INQUIRY 0x12 +#define SPC_MODE_SELECT6 0x15 +#define SPC_MODE_SENSE6 0x1A +#define SPC_SEND_DIAGNOSTIC 0x1D +#define SPC_PREVENT_ALLOW_MEDIUM_REMOVAL 0x1E +#define SPC_MODE_SENSE10 0x5A +#define SPC_REPORT_LUNS 0xA0 //@} //! \brief May be set in byte 0 of the INQUIRY CDB //@{ //! Enable Vital Product Data -#define SCSI_INQ_REQ_EVPD 0x01 +#define SCSI_INQ_REQ_EVPD 0x01 //! Command Support Data specified by the PAGE OR OPERATION CODE field -#define SCSI_INQ_REQ_CMDT 0x02 +#define SCSI_INQ_REQ_CMDT 0x02 //@} COMPILER_PACK_SET(1) @@ -84,110 +84,110 @@ COMPILER_PACK_SET(1) * \brief SCSI Standard Inquiry data structure */ struct scsi_inquiry_data { - uint8_t pq_pdt; //!< Peripheral Qual / Peripheral Dev Type -#define SCSI_INQ_PQ_CONNECTED 0x00 //!< Peripheral connected -#define SCSI_INQ_PQ_NOT_CONN 0x20 //!< Peripheral not connected -#define SCSI_INQ_PQ_NOT_SUPP 0x60 //!< Peripheral not supported -#define SCSI_INQ_DT_DIR_ACCESS 0x00 //!< Direct Access (SBC) -#define SCSI_INQ_DT_SEQ_ACCESS 0x01 //!< Sequential Access -#define SCSI_INQ_DT_PRINTER 0x02 //!< Printer -#define SCSI_INQ_DT_PROCESSOR 0x03 //!< Processor device -#define SCSI_INQ_DT_WRITE_ONCE 0x04 //!< Write-once device -#define SCSI_INQ_DT_CD_DVD 0x05 //!< CD/DVD device -#define SCSI_INQ_DT_OPTICAL 0x07 //!< Optical Memory -#define SCSI_INQ_DT_MC 0x08 //!< Medium Changer -#define SCSI_INQ_DT_ARRAY 0x0C //!< Storage Array Controller -#define SCSI_INQ_DT_ENCLOSURE 0x0D //!< Enclosure Services -#define SCSI_INQ_DT_RBC 0x0E //!< Simplified Direct Access -#define SCSI_INQ_DT_OCRW 0x0F //!< Optical card reader/writer -#define SCSI_INQ_DT_BCC 0x10 //!< Bridge Controller Commands -#define SCSI_INQ_DT_OSD 0x11 //!< Object-based Storage -#define SCSI_INQ_DT_NONE 0x1F //!< No Peripheral - uint8_t flags1; //!< Flags (byte 1) -#define SCSI_INQ_RMB 0x80 //!< Removable Medium - uint8_t version; //!< Version -#define SCSI_INQ_VER_NONE 0x00 //!< No standards conformance -#define SCSI_INQ_VER_SPC 0x03 //!< SCSI Primary Commands (link to SBC) -#define SCSI_INQ_VER_SPC2 0x04 //!< SCSI Primary Commands - 2 (link to SBC-2) -#define SCSI_INQ_VER_SPC3 0x05 //!< SCSI Primary Commands - 3 (link to SBC-2) -#define SCSI_INQ_VER_SPC4 0x06 //!< SCSI Primary Commands - 4 (link to SBC-3) - uint8_t flags3; //!< Flags (byte 3) -#define SCSI_INQ_NORMACA 0x20 //!< Normal ACA Supported -#define SCSI_INQ_HISUP 0x10 //!< Hierarchal LUN addressing -#define SCSI_INQ_RSP_SPC2 0x02 //!< SPC-2 / SPC-3 response format - uint8_t addl_len; //!< Additional Length (n-4) -#define SCSI_INQ_ADDL_LEN(tot) ((tot)-5) //!< Total length is \a tot - uint8_t flags5; //!< Flags (byte 5) -#define SCSI_INQ_SCCS 0x80 - uint8_t flags6; //!< Flags (byte 6) -#define SCSI_INQ_BQUE 0x80 -#define SCSI_INQ_ENCSERV 0x40 -#define SCSI_INQ_MULTIP 0x10 -#define SCSI_INQ_MCHGR 0x08 -#define SCSI_INQ_ADDR16 0x01 - uint8_t flags7; //!< Flags (byte 7) -#define SCSI_INQ_WBUS16 0x20 -#define SCSI_INQ_SYNC 0x10 -#define SCSI_INQ_LINKED 0x08 -#define SCSI_INQ_CMDQUE 0x02 - uint8_t vendor_id[8]; //!< T10 Vendor Identification - uint8_t product_id[16]; //!< Product Identification - uint8_t product_rev[4]; //!< Product Revision Level + uint8_t pq_pdt; //!< Peripheral Qual / Peripheral Dev Type + #define SCSI_INQ_PQ_CONNECTED 0x00 //!< Peripheral connected + #define SCSI_INQ_PQ_NOT_CONN 0x20 //!< Peripheral not connected + #define SCSI_INQ_PQ_NOT_SUPP 0x60 //!< Peripheral not supported + #define SCSI_INQ_DT_DIR_ACCESS 0x00 //!< Direct Access (SBC) + #define SCSI_INQ_DT_SEQ_ACCESS 0x01 //!< Sequential Access + #define SCSI_INQ_DT_PRINTER 0x02 //!< Printer + #define SCSI_INQ_DT_PROCESSOR 0x03 //!< Processor device + #define SCSI_INQ_DT_WRITE_ONCE 0x04 //!< Write-once device + #define SCSI_INQ_DT_CD_DVD 0x05 //!< CD/DVD device + #define SCSI_INQ_DT_OPTICAL 0x07 //!< Optical Memory + #define SCSI_INQ_DT_MC 0x08 //!< Medium Changer + #define SCSI_INQ_DT_ARRAY 0x0C //!< Storage Array Controller + #define SCSI_INQ_DT_ENCLOSURE 0x0D //!< Enclosure Services + #define SCSI_INQ_DT_RBC 0x0E //!< Simplified Direct Access + #define SCSI_INQ_DT_OCRW 0x0F //!< Optical card reader/writer + #define SCSI_INQ_DT_BCC 0x10 //!< Bridge Controller Commands + #define SCSI_INQ_DT_OSD 0x11 //!< Object-based Storage + #define SCSI_INQ_DT_NONE 0x1F //!< No Peripheral + uint8_t flags1; //!< Flags (byte 1) + #define SCSI_INQ_RMB 0x80 //!< Removable Medium + uint8_t version; //!< Version + #define SCSI_INQ_VER_NONE 0x00 //!< No standards conformance + #define SCSI_INQ_VER_SPC 0x03 //!< SCSI Primary Commands (link to SBC) + #define SCSI_INQ_VER_SPC2 0x04 //!< SCSI Primary Commands - 2 (link to SBC-2) + #define SCSI_INQ_VER_SPC3 0x05 //!< SCSI Primary Commands - 3 (link to SBC-2) + #define SCSI_INQ_VER_SPC4 0x06 //!< SCSI Primary Commands - 4 (link to SBC-3) + uint8_t flags3; //!< Flags (byte 3) + #define SCSI_INQ_NORMACA 0x20 //!< Normal ACA Supported + #define SCSI_INQ_HISUP 0x10 //!< Hierarchal LUN addressing + #define SCSI_INQ_RSP_SPC2 0x02 //!< SPC-2 / SPC-3 response format + uint8_t addl_len; //!< Additional Length (n-4) + #define SCSI_INQ_ADDL_LEN(tot) ((tot)-5) //!< Total length is \a tot + uint8_t flags5; //!< Flags (byte 5) + #define SCSI_INQ_SCCS 0x80 + uint8_t flags6; //!< Flags (byte 6) + #define SCSI_INQ_BQUE 0x80 + #define SCSI_INQ_ENCSERV 0x40 + #define SCSI_INQ_MULTIP 0x10 + #define SCSI_INQ_MCHGR 0x08 + #define SCSI_INQ_ADDR16 0x01 + uint8_t flags7; //!< Flags (byte 7) + #define SCSI_INQ_WBUS16 0x20 + #define SCSI_INQ_SYNC 0x10 + #define SCSI_INQ_LINKED 0x08 + #define SCSI_INQ_CMDQUE 0x02 + uint8_t vendor_id[8]; //!< T10 Vendor Identification + uint8_t product_id[16]; //!< Product Identification + uint8_t product_rev[4]; //!< Product Revision Level }; /** * \brief SCSI Standard Request sense data structure */ struct scsi_request_sense_data { - /* 1st byte: REQUEST SENSE response flags*/ - uint8_t valid_reponse_code; -#define SCSI_SENSE_VALID 0x80 //!< Indicates the INFORMATION field contains valid information -#define SCSI_SENSE_RESPONSE_CODE_MASK 0x7F -#define SCSI_SENSE_CURRENT 0x70 //!< Response code 70h (current errors) -#define SCSI_SENSE_DEFERRED 0x71 + /* 1st byte: REQUEST SENSE response flags*/ + uint8_t valid_reponse_code; + #define SCSI_SENSE_VALID 0x80 //!< Indicates the INFORMATION field contains valid information + #define SCSI_SENSE_RESPONSE_CODE_MASK 0x7F + #define SCSI_SENSE_CURRENT 0x70 //!< Response code 70h (current errors) + #define SCSI_SENSE_DEFERRED 0x71 - /* 2nd byte */ - uint8_t obsolete; + /* 2nd byte */ + uint8_t obsolete; - /* 3rd byte */ - uint8_t sense_flag_key; -#define SCSI_SENSE_FILEMARK 0x80 //!< Indicates that the current command has read a filemark or setmark. -#define SCSI_SENSE_EOM 0x40 //!< Indicates that an end-of-medium condition exists. -#define SCSI_SENSE_ILI 0x20 //!< Indicates that the requested logical block length did not match the logical block length of the data on the medium. -#define SCSI_SENSE_RESERVED 0x10 //!< Reserved -#define SCSI_SENSE_KEY(x) (x&0x0F) //!< Sense Key + /* 3rd byte */ + uint8_t sense_flag_key; + #define SCSI_SENSE_FILEMARK 0x80 //!< Indicates that the current command has read a filemark or setmark. + #define SCSI_SENSE_EOM 0x40 //!< Indicates that an end-of-medium condition exists. + #define SCSI_SENSE_ILI 0x20 //!< Indicates that the requested logical block length did not match the logical block length of the data on the medium. + #define SCSI_SENSE_RESERVED 0x10 //!< Reserved + #define SCSI_SENSE_KEY(x) (x&0x0F) //!< Sense Key - /* 4th to 7th bytes - INFORMATION field */ - uint8_t information[4]; + /* 4th to 7th bytes - INFORMATION field */ + uint8_t information[4]; - /* 8th byte - ADDITIONAL SENSE LENGTH field */ - uint8_t AddSenseLen; -#define SCSI_SENSE_ADDL_LEN(total_len) ((total_len) - 8) + /* 8th byte - ADDITIONAL SENSE LENGTH field */ + uint8_t AddSenseLen; + #define SCSI_SENSE_ADDL_LEN(total_len) ((total_len) - 8) - /* 9th to 12th byte - COMMAND-SPECIFIC INFORMATION field */ - uint8_t CmdSpecINFO[4]; + /* 9th to 12th byte - COMMAND-SPECIFIC INFORMATION field */ + uint8_t CmdSpecINFO[4]; - /* 13th byte - ADDITIONAL SENSE CODE field */ - uint8_t AddSenseCode; + /* 13th byte - ADDITIONAL SENSE CODE field */ + uint8_t AddSenseCode; - /* 14th byte - ADDITIONAL SENSE CODE QUALIFIER field */ - uint8_t AddSnsCodeQlfr; + /* 14th byte - ADDITIONAL SENSE CODE QUALIFIER field */ + uint8_t AddSnsCodeQlfr; - /* 15th byte - FIELD REPLACEABLE UNIT CODE field */ - uint8_t FldReplUnitCode; + /* 15th byte - FIELD REPLACEABLE UNIT CODE field */ + uint8_t FldReplUnitCode; - /* 16th byte */ - uint8_t SenseKeySpec[3]; -#define SCSI_SENSE_SKSV 0x80 //!< Indicates the SENSE-KEY SPECIFIC field contains valid information + /* 16th byte */ + uint8_t SenseKeySpec[3]; + #define SCSI_SENSE_SKSV 0x80 //!< Indicates the SENSE-KEY SPECIFIC field contains valid information }; COMPILER_PACK_RESET() /* Vital Product Data page codes */ enum scsi_vpd_page_code { - SCSI_VPD_SUPPORTED_PAGES = 0x00, - SCSI_VPD_UNIT_SERIAL_NUMBER = 0x80, - SCSI_VPD_DEVICE_IDENTIFICATION = 0x83, + SCSI_VPD_SUPPORTED_PAGES = 0x00, + SCSI_VPD_UNIT_SERIAL_NUMBER = 0x80, + SCSI_VPD_DEVICE_IDENTIFICATION = 0x83, }; #define SCSI_VPD_HEADER_SIZE 4 @@ -200,37 +200,36 @@ enum scsi_vpd_page_code { #define SCSI_VPD_ID_TYPE_T10 1 - /* Sense keys */ enum scsi_sense_key { - SCSI_SK_NO_SENSE = 0x0, - SCSI_SK_RECOVERED_ERROR = 0x1, - SCSI_SK_NOT_READY = 0x2, - SCSI_SK_MEDIUM_ERROR = 0x3, - SCSI_SK_HARDWARE_ERROR = 0x4, - SCSI_SK_ILLEGAL_REQUEST = 0x5, - SCSI_SK_UNIT_ATTENTION = 0x6, - SCSI_SK_DATA_PROTECT = 0x7, - SCSI_SK_BLANK_CHECK = 0x8, - SCSI_SK_VENDOR_SPECIFIC = 0x9, - SCSI_SK_COPY_ABORTED = 0xA, - SCSI_SK_ABORTED_COMMAND = 0xB, - SCSI_SK_VOLUME_OVERFLOW = 0xD, - SCSI_SK_MISCOMPARE = 0xE, + SCSI_SK_NO_SENSE = 0x0, + SCSI_SK_RECOVERED_ERROR = 0x1, + SCSI_SK_NOT_READY = 0x2, + SCSI_SK_MEDIUM_ERROR = 0x3, + SCSI_SK_HARDWARE_ERROR = 0x4, + SCSI_SK_ILLEGAL_REQUEST = 0x5, + SCSI_SK_UNIT_ATTENTION = 0x6, + SCSI_SK_DATA_PROTECT = 0x7, + SCSI_SK_BLANK_CHECK = 0x8, + SCSI_SK_VENDOR_SPECIFIC = 0x9, + SCSI_SK_COPY_ABORTED = 0xA, + SCSI_SK_ABORTED_COMMAND = 0xB, + SCSI_SK_VOLUME_OVERFLOW = 0xD, + SCSI_SK_MISCOMPARE = 0xE, }; /* Additional Sense Code / Additional Sense Code Qualifier pairs */ enum scsi_asc_ascq { - SCSI_ASC_NO_ADDITIONAL_SENSE_INFO = 0x0000, - SCSI_ASC_LU_NOT_READY_REBUILD_IN_PROGRESS = 0x0405, - SCSI_ASC_WRITE_ERROR = 0x0C00, - SCSI_ASC_UNRECOVERED_READ_ERROR = 0x1100, - SCSI_ASC_INVALID_COMMAND_OPERATION_CODE = 0x2000, - SCSI_ASC_INVALID_FIELD_IN_CDB = 0x2400, - SCSI_ASC_WRITE_PROTECTED = 0x2700, - SCSI_ASC_NOT_READY_TO_READY_CHANGE = 0x2800, - SCSI_ASC_MEDIUM_NOT_PRESENT = 0x3A00, - SCSI_ASC_INTERNAL_TARGET_FAILURE = 0x4400, + SCSI_ASC_NO_ADDITIONAL_SENSE_INFO = 0x0000, + SCSI_ASC_LU_NOT_READY_REBUILD_IN_PROGRESS = 0x0405, + SCSI_ASC_WRITE_ERROR = 0x0C00, + SCSI_ASC_UNRECOVERED_READ_ERROR = 0x1100, + SCSI_ASC_INVALID_COMMAND_OPERATION_CODE = 0x2000, + SCSI_ASC_INVALID_FIELD_IN_CDB = 0x2400, + SCSI_ASC_WRITE_PROTECTED = 0x2700, + SCSI_ASC_NOT_READY_TO_READY_CHANGE = 0x2800, + SCSI_ASC_MEDIUM_NOT_PRESENT = 0x3A00, + SCSI_ASC_INTERNAL_TARGET_FAILURE = 0x4400, }; /** @@ -240,9 +239,9 @@ enum scsi_asc_ascq { * that are applicable to all SCSI devices. */ enum scsi_spc_mode { - SCSI_MS_MODE_VENDOR_SPEC = 0x00, - SCSI_MS_MODE_INFEXP = 0x1C, // Informational exceptions control page - SCSI_MS_MODE_ALL = 0x3F, + SCSI_MS_MODE_VENDOR_SPEC = 0x00, + SCSI_MS_MODE_INFEXP = 0x1C, // Informational exceptions control page + SCSI_MS_MODE_ALL = 0x3F, }; /** @@ -250,51 +249,45 @@ enum scsi_spc_mode { * See chapter 8.3.8 */ struct spc_control_page_info_execpt { - uint8_t page_code; - uint8_t page_length; -#define SPC_MP_INFEXP_PAGE_LENGTH 0x0A - uint8_t flags1; -#define SPC_MP_INFEXP_PERF (1<<7) //!< Initiator Control -#define SPC_MP_INFEXP_EBF (1<<5) //!< Caching Analysis Permitted -#define SPC_MP_INFEXP_EWASC (1<<4) //!< Discontinuity -#define SPC_MP_INFEXP_DEXCPT (1<<3) //!< Size enable -#define SPC_MP_INFEXP_TEST (1<<2) //!< Writeback Cache Enable -#define SPC_MP_INFEXP_LOGERR (1<<0) //!< Log errors bit - uint8_t mrie; -#define SPC_MP_INFEXP_MRIE_NO_REPORT 0x00 -#define SPC_MP_INFEXP_MRIE_ASYNC_EVENT 0x01 -#define SPC_MP_INFEXP_MRIE_GEN_UNIT 0x02 -#define SPC_MP_INFEXP_MRIE_COND_RECOV_ERROR 0x03 -#define SPC_MP_INFEXP_MRIE_UNCOND_RECOV_ERROR 0x04 -#define SPC_MP_INFEXP_MRIE_NO_SENSE 0x05 -#define SPC_MP_INFEXP_MRIE_ONLY_REPORT 0x06 - be32_t interval_timer; - be32_t report_count; + uint8_t page_code; + uint8_t page_length; + #define SPC_MP_INFEXP_PAGE_LENGTH 0x0A + uint8_t flags1; + #define SPC_MP_INFEXP_PERF (1<<7) //!< Initiator Control + #define SPC_MP_INFEXP_EBF (1<<5) //!< Caching Analysis Permitted + #define SPC_MP_INFEXP_EWASC (1<<4) //!< Discontinuity + #define SPC_MP_INFEXP_DEXCPT (1<<3) //!< Size enable + #define SPC_MP_INFEXP_TEST (1<<2) //!< Writeback Cache Enable + #define SPC_MP_INFEXP_LOGERR (1<<0) //!< Log errors bit + uint8_t mrie; + #define SPC_MP_INFEXP_MRIE_NO_REPORT 0x00 + #define SPC_MP_INFEXP_MRIE_ASYNC_EVENT 0x01 + #define SPC_MP_INFEXP_MRIE_GEN_UNIT 0x02 + #define SPC_MP_INFEXP_MRIE_COND_RECOV_ERROR 0x03 + #define SPC_MP_INFEXP_MRIE_UNCOND_RECOV_ERROR 0x04 + #define SPC_MP_INFEXP_MRIE_NO_SENSE 0x05 + #define SPC_MP_INFEXP_MRIE_ONLY_REPORT 0x06 + be32_t interval_timer; + be32_t report_count; }; - enum scsi_spc_mode_sense_pc { - SCSI_MS_SENSE_PC_CURRENT = 0, - SCSI_MS_SENSE_PC_CHANGEABLE = 1, - SCSI_MS_SENSE_PC_DEFAULT = 2, - SCSI_MS_SENSE_PC_SAVED = 3, + SCSI_MS_SENSE_PC_CURRENT = 0, + SCSI_MS_SENSE_PC_CHANGEABLE = 1, + SCSI_MS_SENSE_PC_DEFAULT = 2, + SCSI_MS_SENSE_PC_SAVED = 3, }; - - -static inline bool scsi_mode_sense_dbd_is_set(const uint8_t * cdb) -{ - return (cdb[1] >> 3) & 1; +static inline bool scsi_mode_sense_dbd_is_set(const uint8_t * cdb) { + return (cdb[1] >> 3) & 1; } -static inline uint8_t scsi_mode_sense_get_page_code(const uint8_t * cdb) -{ - return cdb[2] & 0x3F; +static inline uint8_t scsi_mode_sense_get_page_code(const uint8_t * cdb) { + return cdb[2] & 0x3F; } -static inline uint8_t scsi_mode_sense_get_pc(const uint8_t * cdb) -{ - return cdb[2] >> 6; +static inline uint8_t scsi_mode_sense_get_pc(const uint8_t * cdb) { + return cdb[2] >> 6; } /** @@ -302,10 +295,10 @@ static inline uint8_t scsi_mode_sense_get_pc(const uint8_t * cdb) * SENSE(6) */ struct scsi_mode_param_header6 { - uint8_t mode_data_length; //!< Number of bytes after this - uint8_t medium_type; //!< Medium Type - uint8_t device_specific_parameter; //!< Defined by command set - uint8_t block_descriptor_length; //!< Length of block descriptors + uint8_t mode_data_length; //!< Number of bytes after this + uint8_t medium_type; //!< Medium Type + uint8_t device_specific_parameter; //!< Defined by command set + uint8_t block_descriptor_length; //!< Length of block descriptors }; /** @@ -313,23 +306,23 @@ struct scsi_mode_param_header6 { * SENSE(10) */ struct scsi_mode_param_header10 { - be16_t mode_data_length; //!< Number of bytes after this - uint8_t medium_type; //!< Medium Type - uint8_t device_specific_parameter; //!< Defined by command set - uint8_t flags4; //!< LONGLBA in bit 0 - uint8_t reserved; - be16_t block_descriptor_length; //!< Length of block descriptors + be16_t mode_data_length; //!< Number of bytes after this + uint8_t medium_type; //!< Medium Type + uint8_t device_specific_parameter; //!< Defined by command set + uint8_t flags4; //!< LONGLBA in bit 0 + uint8_t reserved; + be16_t block_descriptor_length; //!< Length of block descriptors }; /** * \brief SCSI Page_0 Mode Page header (SPF not set) */ struct scsi_mode_page_0_header { - uint8_t page_code; -#define SCSI_PAGE_CODE_PS (1 << 7) //!< Parameters Saveable -#define SCSI_PAGE_CODE_SPF (1 << 6) //!< SubPage Format - uint8_t page_length; //!< Number of bytes after this -#define SCSI_MS_PAGE_LEN(total) ((total) - 2) + uint8_t page_code; +#define SCSI_PAGE_CODE_PS (1 << 7) //!< Parameters Saveable +#define SCSI_PAGE_CODE_SPF (1 << 6) //!< SubPage Format + uint8_t page_length; //!< Number of bytes after this +#define SCSI_MS_PAGE_LEN(total) ((total) - 2) }; //@} diff --git a/Marlin/src/HAL/DUE/usb/sysclk.h b/Marlin/src/HAL/DUE/usb/sysclk.h index 16db8c86d3..4001366868 100644 --- a/Marlin/src/HAL/DUE/usb/sysclk.h +++ b/Marlin/src/HAL/DUE/usb/sysclk.h @@ -71,7 +71,7 @@ * \subsection sysclk_quickstart_use_case_1_setup_steps Initialization code * Add to the application initialization code: * \code - sysclk_init(); + sysclk_init(); \endcode * * \subsection sysclk_quickstart_use_case_1_setup_steps_workflow Workflow @@ -82,15 +82,15 @@ * Add or uncomment the following in your conf_clock.h header file, commenting out all other * definitions of the same symbol(s): * \code - #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLLACK + #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLLACK - // Fpll0 = (Fclk * PLL_mul) / PLL_div - #define CONFIG_PLL0_SOURCE PLL_SRC_MAINCK_XTAL - #define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL) - #define CONFIG_PLL0_DIV 1 + // Fpll0 = (Fclk * PLL_mul) / PLL_div + #define CONFIG_PLL0_SOURCE PLL_SRC_MAINCK_XTAL + #define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL) + #define CONFIG_PLL0_DIV 1 - // Fbus = Fsys / BUS_div - #define CONFIG_SYSCLK_PRES SYSCLK_PRES_1 + // Fbus = Fsys / BUS_div + #define CONFIG_SYSCLK_PRES SYSCLK_PRES_1 \endcode * * \subsection sysclk_quickstart_use_case_1_example_workflow Workflow @@ -100,14 +100,14 @@ * \code #define CONFIG_PLL0_SOURCE PLL_SRC_MAINCK_XTAL \endcode * -# Configure the PLL module to multiply the external fast crystal oscillator frequency up to 84MHz: * \code - #define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL) - #define CONFIG_PLL0_DIV 1 + #define CONFIG_PLL0_MUL (84000000UL / BOARD_FREQ_MAINCK_XTAL) + #define CONFIG_PLL0_DIV 1 \endcode * \note For user boards, \c BOARD_FREQ_MAINCK_XTAL should be defined in the board \c conf_board.h configuration * file as the frequency of the fast crystal attached to the microcontroller. * -# Configure the main clock to run at the full 84MHz, disable scaling of the main system clock speed: * \code - #define CONFIG_SYSCLK_PRES SYSCLK_PRES_1 + #define CONFIG_SYSCLK_PRES SYSCLK_PRES_1 \endcode * \note Some dividers are powers of two, while others are integer division factors. Refer to the * formulas in the conf_clock.h template commented above each division define. @@ -136,7 +136,7 @@ extern "C" { * initialization. */ #ifndef CONFIG_SYSCLK_SOURCE -# define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_MAINCK_4M_RC + #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_MAINCK_4M_RC #endif /** * \def CONFIG_SYSCLK_PRES @@ -149,7 +149,7 @@ extern "C" { * after initialization. */ #ifndef CONFIG_SYSCLK_PRES -# define CONFIG_SYSCLK_PRES 0 + #define CONFIG_SYSCLK_PRES 0 #endif //@} @@ -197,7 +197,7 @@ extern "C" { * USB is not required. */ #ifdef __DOXYGEN__ -# define CONFIG_USBCLK_SOURCE + #define CONFIG_USBCLK_SOURCE #endif /** @@ -209,10 +209,9 @@ extern "C" { * defined. */ #ifdef __DOXYGEN__ -# define CONFIG_USBCLK_DIV + #define CONFIG_USBCLK_DIV #endif - extern void sysclk_enable_usb(void); extern void sysclk_disable_usb(void); diff --git a/Marlin/src/HAL/DUE/usb/udc.c b/Marlin/src/HAL/DUE/usb/udc.c index 60bf0cfff3..f6a4243d1d 100644 --- a/Marlin/src/HAL/DUE/usb/udc.c +++ b/Marlin/src/HAL/DUE/usb/udc.c @@ -83,7 +83,6 @@ static usb_iface_desc_t UDC_DESC_STORAGE *udc_ptr_iface; //! @} - //! \name Internal structure to store the USB device main strings //! @{ diff --git a/Marlin/src/HAL/DUE/usb/udc.h b/Marlin/src/HAL/DUE/usb/udc.h index 8d92eb5c03..aba08d956e 100644 --- a/Marlin/src/HAL/DUE/usb/udc.h +++ b/Marlin/src/HAL/DUE/usb/udc.h @@ -144,15 +144,15 @@ extern "C" { * \code #define USB_DEVICE_ATTACH_AUTO_DISABLE \endcode * User C file contains: * \code - // Authorize VBUS monitoring - if (!udc_include_vbus_monitoring()) { - // Implement custom VBUS monitoring via GPIO or other - } - Event_VBUS_present() // VBUS interrupt or GPIO interrupt or other - { - // Attach USB Device - udc_attach(); - } + // Authorize VBUS monitoring + if (!udc_include_vbus_monitoring()) { + // Implement custom VBUS monitoring via GPIO or other + } + Event_VBUS_present() // VBUS interrupt or GPIO interrupt or other + { + // Attach USB Device + udc_attach(); + } \endcode * * - Case of battery charging. conf_usb.h file contains define @@ -160,21 +160,20 @@ extern "C" { * \code #define USB_DEVICE_ATTACH_AUTO_DISABLE \endcode * User C file contains: * \code - Event VBUS present() // VBUS interrupt or GPIO interrupt or .. - { - // Authorize battery charging, but wait key press to start USB. - } - Event Key press() - { - // Stop batteries charging - // Start USB - udc_attach(); - } + Event VBUS present() // VBUS interrupt or GPIO interrupt or .. + { + // Authorize battery charging, but wait key press to start USB. + } + Event Key press() + { + // Stop batteries charging + // Start USB + udc_attach(); + } \endcode */ -static inline bool udc_include_vbus_monitoring(void) -{ - return udd_include_vbus_monitoring(); +static inline bool udc_include_vbus_monitoring(void) { + return udd_include_vbus_monitoring(); } /*! \brief Start the USB Device stack @@ -192,32 +191,26 @@ void udc_stop(void); * then it will attach device when an acceptable Vbus * level from the host is detected. */ -static inline void udc_attach(void) -{ - udd_attach(); +static inline void udc_attach(void) { + udd_attach(); } - /** * \brief Detaches the device from the bus * * The driver must remove pull-up on USB line D- or D+. */ -static inline void udc_detach(void) -{ - udd_detach(); +static inline void udc_detach(void) { + udd_detach(); } - /*! \brief The USB driver sends a resume signal called \e "Upstream Resume" * This is authorized only when the remote wakeup feature is enabled by host. */ -static inline void udc_remotewakeup(void) -{ - udd_send_remotewakeup(); +static inline void udc_remotewakeup(void) { + udd_send_remotewakeup(); } - /** * \brief Returns a pointer on the current interface descriptor * @@ -296,23 +289,23 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * * for AVR and SAM3/4 devices, add to the initialization code: * \code - sysclk_init(); - irq_initialize_vectors(); - cpu_irq_enable(); - board_init(); - sleepmgr_init(); // Optional + sysclk_init(); + irq_initialize_vectors(); + cpu_irq_enable(); + board_init(); + sleepmgr_init(); // Optional \endcode * * For SAMD devices, add to the initialization code: * \code - system_init(); - irq_initialize_vectors(); - cpu_irq_enable(); - sleepmgr_init(); // Optional + system_init(); + irq_initialize_vectors(); + cpu_irq_enable(); + sleepmgr_init(); // Optional \endcode * Add to the main IDLE loop: * \code - sleepmgr_enter_sleep(); // Optional + sleepmgr_enter_sleep(); // Optional \endcode * */ @@ -324,20 +317,20 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * * Content of conf_usb.h: * \code - #define USB_DEVICE_VENDOR_ID 0x03EB - #define USB_DEVICE_PRODUCT_ID 0xXXXX - #define USB_DEVICE_MAJOR_VERSION 1 - #define USB_DEVICE_MINOR_VERSION 0 - #define USB_DEVICE_POWER 100 - #define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED + #define USB_DEVICE_VENDOR_ID 0x03EB + #define USB_DEVICE_PRODUCT_ID 0xXXXX + #define USB_DEVICE_MAJOR_VERSION 1 + #define USB_DEVICE_MINOR_VERSION 0 + #define USB_DEVICE_POWER 100 + #define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED \endcode * * Add to application C-file: * \code - void usb_init(void) - { - udc_start(); - } + void usb_init(void) + { + udc_start(); + } \endcode */ @@ -349,17 +342,17 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * -# Ensure that conf_usb.h is available and contains the following configuration * which is the main USB device configuration: * - \code // Vendor ID provided by USB org (ATMEL 0x03EB) - #define USB_DEVICE_VENDOR_ID 0x03EB // Type Word - // Product ID (Atmel PID referenced in usb_atmel.h) - #define USB_DEVICE_PRODUCT_ID 0xXXXX // Type Word - // Major version of the device - #define USB_DEVICE_MAJOR_VERSION 1 // Type Byte - // Minor version of the device - #define USB_DEVICE_MINOR_VERSION 0 // Type Byte - // Maximum device power (mA) - #define USB_DEVICE_POWER 100 // Type 9-bits - // USB attributes to enable features - #define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED // Flags \endcode + #define USB_DEVICE_VENDOR_ID 0x03EB // Type Word + // Product ID (Atmel PID referenced in usb_atmel.h) + #define USB_DEVICE_PRODUCT_ID 0xXXXX // Type Word + // Major version of the device + #define USB_DEVICE_MAJOR_VERSION 1 // Type Byte + // Minor version of the device + #define USB_DEVICE_MINOR_VERSION 0 // Type Byte + // Maximum device power (mA) + #define USB_DEVICE_POWER 100 // Type 9-bits + // USB attributes to enable features + #define USB_DEVICE_ATTR USB_CONFIG_ATTR_BUS_POWERED // Flags \endcode * -# Call the USB device stack start function to enable stack and start USB: * - \code udc_start(); \endcode * \note In case of USB dual roles (Device and Host) managed through USB OTG connector @@ -372,90 +365,90 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * * Content of XMEGA conf_clock.h: * \code - // Configuration based on internal RC: - // USB clock need of 48Mhz - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_RCOSC - #define CONFIG_OSC_RC32_CAL 48000000UL - #define CONFIG_OSC_AUTOCAL_RC32MHZ_REF_OSC OSC_ID_USBSOF - // CPU clock need of clock > 12MHz to run with USB (Here 24MHz) - #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_RC32MHZ - #define CONFIG_SYSCLK_PSADIV SYSCLK_PSADIV_2 - #define CONFIG_SYSCLK_PSBCDIV SYSCLK_PSBCDIV_1_1 + // Configuration based on internal RC: + // USB clock need of 48Mhz + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_RCOSC + #define CONFIG_OSC_RC32_CAL 48000000UL + #define CONFIG_OSC_AUTOCAL_RC32MHZ_REF_OSC OSC_ID_USBSOF + // CPU clock need of clock > 12MHz to run with USB (Here 24MHz) + #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_RC32MHZ + #define CONFIG_SYSCLK_PSADIV SYSCLK_PSADIV_2 + #define CONFIG_SYSCLK_PSBCDIV SYSCLK_PSBCDIV_1_1 \endcode * * Content of conf_clock.h for AT32UC3A0, AT32UC3A1, AT32UC3B devices (USBB): * \code - // Configuration based on 12MHz external OSC: - #define CONFIG_PLL1_SOURCE PLL_SRC_OSC0 - #define CONFIG_PLL1_MUL 8 - #define CONFIG_PLL1_DIV 2 - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 - #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) + // Configuration based on 12MHz external OSC: + #define CONFIG_PLL1_SOURCE PLL_SRC_OSC0 + #define CONFIG_PLL1_MUL 8 + #define CONFIG_PLL1_DIV 2 + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 + #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) \endcode * * Content of conf_clock.h for AT32UC3A3, AT32UC3A4 devices (USBB with high speed support): * \code - // Configuration based on 12MHz external OSC: - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_OSC0 - #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) + // Configuration based on 12MHz external OSC: + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_OSC0 + #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) \endcode * * Content of conf_clock.h for AT32UC3C, ATUCXXD, ATUCXXL3U, ATUCXXL4U devices (USBC): * \code - // Configuration based on 12MHz external OSC: - #define CONFIG_PLL1_SOURCE PLL_SRC_OSC0 - #define CONFIG_PLL1_MUL 8 - #define CONFIG_PLL1_DIV 2 - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 - #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) - // CPU clock need of clock > 25MHz to run with USBC - #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLL1 + // Configuration based on 12MHz external OSC: + #define CONFIG_PLL1_SOURCE PLL_SRC_OSC0 + #define CONFIG_PLL1_MUL 8 + #define CONFIG_PLL1_DIV 2 + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 + #define CONFIG_USBCLK_DIV 1 // Fusb = Fsys/(2 ^ USB_div) + // CPU clock need of clock > 25MHz to run with USBC + #define CONFIG_SYSCLK_SOURCE SYSCLK_SRC_PLL1 \endcode * * Content of conf_clock.h for SAM3S, SAM3SD, SAM4S devices (UPD: USB Peripheral Device): * \code - // PLL1 (B) Options (Fpll = (Fclk * PLL_mul) / PLL_div) - #define CONFIG_PLL1_SOURCE PLL_SRC_MAINCK_XTAL - #define CONFIG_PLL1_MUL 16 - #define CONFIG_PLL1_DIV 2 - // USB Clock Source Options (Fusb = FpllX / USB_div) - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 - #define CONFIG_USBCLK_DIV 2 + // PLL1 (B) Options (Fpll = (Fclk * PLL_mul) / PLL_div) + #define CONFIG_PLL1_SOURCE PLL_SRC_MAINCK_XTAL + #define CONFIG_PLL1_MUL 16 + #define CONFIG_PLL1_DIV 2 + // USB Clock Source Options (Fusb = FpllX / USB_div) + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_PLL1 + #define CONFIG_USBCLK_DIV 2 \endcode * * Content of conf_clock.h for SAM3U device (UPDHS: USB Peripheral Device High Speed): * \code - // USB Clock Source fixed at UPLL. + // USB Clock Source fixed at UPLL. \endcode * * Content of conf_clock.h for SAM3X, SAM3A devices (UOTGHS: USB OTG High Speed): * \code - // USB Clock Source fixed at UPLL. - #define CONFIG_USBCLK_SOURCE USBCLK_SRC_UPLL - #define CONFIG_USBCLK_DIV 1 + // USB Clock Source fixed at UPLL. + #define CONFIG_USBCLK_SOURCE USBCLK_SRC_UPLL + #define CONFIG_USBCLK_DIV 1 \endcode * * Content of conf_clocks.h for SAMD devices (USB): * \code - // System clock bus configuration - # define CONF_CLOCK_FLASH_WAIT_STATES 2 + // System clock bus configuration + # define CONF_CLOCK_FLASH_WAIT_STATES 2 - // USB Clock Source fixed at DFLL. - // SYSTEM_CLOCK_SOURCE_DFLL configuration - Digital Frequency Locked Loop - # define CONF_CLOCK_DFLL_ENABLE true - # define CONF_CLOCK_DFLL_LOOP_MODE SYSTEM_CLOCK_DFLL_LOOP_MODE_USB_RECOVERY - # define CONF_CLOCK_DFLL_ON_DEMAND true + // USB Clock Source fixed at DFLL. + // SYSTEM_CLOCK_SOURCE_DFLL configuration - Digital Frequency Locked Loop + # define CONF_CLOCK_DFLL_ENABLE true + # define CONF_CLOCK_DFLL_LOOP_MODE SYSTEM_CLOCK_DFLL_LOOP_MODE_USB_RECOVERY + # define CONF_CLOCK_DFLL_ON_DEMAND true - // Set this to true to configure the GCLK when running clocks_init. - // If set to false, none of the GCLK generators will be configured in clocks_init(). - # define CONF_CLOCK_CONFIGURE_GCLK true + // Set this to true to configure the GCLK when running clocks_init. + // If set to false, none of the GCLK generators will be configured in clocks_init(). + # define CONF_CLOCK_CONFIGURE_GCLK true - // Configure GCLK generator 0 (Main Clock) - # define CONF_CLOCK_GCLK_0_ENABLE true - # define CONF_CLOCK_GCLK_0_RUN_IN_STANDBY true - # define CONF_CLOCK_GCLK_0_CLOCK_SOURCE SYSTEM_CLOCK_SOURCE_DFLL - # define CONF_CLOCK_GCLK_0_PRESCALER 1 - # define CONF_CLOCK_GCLK_0_OUTPUT_ENABLE false + // Configure GCLK generator 0 (Main Clock) + # define CONF_CLOCK_GCLK_0_ENABLE true + # define CONF_CLOCK_GCLK_0_RUN_IN_STANDBY true + # define CONF_CLOCK_GCLK_0_CLOCK_SOURCE SYSTEM_CLOCK_SOURCE_DFLL + # define CONF_CLOCK_GCLK_0_PRESCALER 1 + # define CONF_CLOCK_GCLK_0_OUTPUT_ENABLE false \endcode */ @@ -474,34 +467,34 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_1_usage_code Example code * Content of conf_usb.h: * \code - #if // Low speed - #define USB_DEVICE_LOW_SPEED - // #define USB_DEVICE_HS_SUPPORT + #if // Low speed + #define USB_DEVICE_LOW_SPEED + // #define USB_DEVICE_HS_SUPPORT - #elif // Full speed - // #define USB_DEVICE_LOW_SPEED - // #define USB_DEVICE_HS_SUPPORT + #elif // Full speed + // #define USB_DEVICE_LOW_SPEED + // #define USB_DEVICE_HS_SUPPORT - #elif // High speed - // #define USB_DEVICE_LOW_SPEED - #define USB_DEVICE_HS_SUPPORT + #elif // High speed + // #define USB_DEVICE_LOW_SPEED + #define USB_DEVICE_HS_SUPPORT - #endif + #endif \endcode * * \subsection udc_use_case_1_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required for a USB device low speed (1.5Mbit/s): * - \code #define USB_DEVICE_LOW_SPEED - //#define USB_DEVICE_HS_SUPPORT \endcode + //#define USB_DEVICE_HS_SUPPORT \endcode * -# Ensure that conf_usb.h contains the following parameters * required for a USB device full speed (12Mbit/s): * - \code //#define USB_DEVICE_LOW_SPEED - //#define USB_DEVICE_HS_SUPPORT \endcode + //#define USB_DEVICE_HS_SUPPORT \endcode * -# Ensure that conf_usb.h contains the following parameters * required for a USB device high speed (480Mbit/s): * - \code //#define USB_DEVICE_LOW_SPEED - #define USB_DEVICE_HS_SUPPORT \endcode + #define USB_DEVICE_HS_SUPPORT \endcode */ /** @@ -518,20 +511,20 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_2_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" - #define USB_DEVICE_PRODUCT_NAME "Product name" - #define USB_DEVICE_SERIAL_NAME "12...EF" + #define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" + #define USB_DEVICE_PRODUCT_NAME "Product name" + #define USB_DEVICE_SERIAL_NAME "12...EF" \endcode * * \subsection udc_use_case_2_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required to enable different USB strings: * - \code // Static ASCII name for the manufacture - #define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" \endcode + #define USB_DEVICE_MANUFACTURE_NAME "Manufacture name" \endcode * - \code // Static ASCII name for the product - #define USB_DEVICE_PRODUCT_NAME "Product name" \endcode + #define USB_DEVICE_PRODUCT_NAME "Product name" \endcode * - \code // Static ASCII name to enable and set a serial number - #define USB_DEVICE_SERIAL_NAME "12...EF" \endcode + #define USB_DEVICE_SERIAL_NAME "12...EF" \endcode */ /** @@ -548,42 +541,42 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_3_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_ATTR \ - (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) - #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() - extern void my_callback_remotewakeup_enable(void); - #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() - extern void my_callback_remotewakeup_disable(void); + #define USB_DEVICE_ATTR \ + (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) + #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() + extern void my_callback_remotewakeup_enable(void); + #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() + extern void my_callback_remotewakeup_disable(void); \endcode * * Add to application C-file: * \code - void my_callback_remotewakeup_enable(void) - { - // Enable application wakeup events (e.g. enable GPIO interrupt) - } - void my_callback_remotewakeup_disable(void) - { - // Disable application wakeup events (e.g. disable GPIO interrupt) - } + void my_callback_remotewakeup_enable(void) + { + // Enable application wakeup events (e.g. enable GPIO interrupt) + } + void my_callback_remotewakeup_disable(void) + { + // Disable application wakeup events (e.g. disable GPIO interrupt) + } - void my_interrupt_event(void) - { - udc_remotewakeup(); - } + void my_interrupt_event(void) + { + udc_remotewakeup(); + } \endcode * * \subsection udc_use_case_3_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required to enable remote wakeup feature: * - \code // Authorizes the remote wakeup feature - #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) \endcode + #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_REMOTE_WAKEUP | USB_CONFIG_ATTR_..._POWERED) \endcode * - \code // Define callback called when the host enables the remotewakeup feature - #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() - extern void my_callback_remotewakeup_enable(void); \endcode + #define UDC_REMOTEWAKEUP_ENABLE() my_callback_remotewakeup_enable() + extern void my_callback_remotewakeup_enable(void); \endcode * - \code // Define callback called when the host disables the remotewakeup feature - #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() - extern void my_callback_remotewakeup_disable(void); \endcode + #define UDC_REMOTEWAKEUP_DISABLE() my_callback_remotewakeup_disable() + extern void my_callback_remotewakeup_disable(void); \endcode * -# Send a remote wakeup (USB upstream): * - \code udc_remotewakeup(); \endcode */ @@ -603,40 +596,40 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_5_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) - #define UDC_SUSPEND_EVENT() user_callback_suspend_action() - extern void user_callback_suspend_action(void) - #define UDC_RESUME_EVENT() user_callback_resume_action() - extern void user_callback_resume_action(void) + #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) + #define UDC_SUSPEND_EVENT() user_callback_suspend_action() + extern void user_callback_suspend_action(void) + #define UDC_RESUME_EVENT() user_callback_resume_action() + extern void user_callback_resume_action(void) \endcode * * Add to application C-file: * \code - void user_callback_suspend_action(void) - { - // Disable hardware component to reduce power consumption - } - void user_callback_resume_action(void) - { - // Re-enable hardware component - } + void user_callback_suspend_action(void) + { + // Disable hardware component to reduce power consumption + } + void user_callback_resume_action(void) + { + // Re-enable hardware component + } \endcode * * \subsection udc_use_case_5_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters: * - \code // Authorizes the BUS power feature - #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) \endcode + #define USB_DEVICE_ATTR (USB_CONFIG_ATTR_BUS_POWERED) \endcode * - \code // Define callback called when the host suspend the USB line - #define UDC_SUSPEND_EVENT() user_callback_suspend_action() - extern void user_callback_suspend_action(void); \endcode + #define UDC_SUSPEND_EVENT() user_callback_suspend_action() + extern void user_callback_suspend_action(void); \endcode * - \code // Define callback called when the host or device resume the USB line - #define UDC_RESUME_EVENT() user_callback_resume_action() - extern void user_callback_resume_action(void); \endcode + #define UDC_RESUME_EVENT() user_callback_resume_action() + extern void user_callback_resume_action(void); \endcode * -# Reduce power consumption in suspend mode (max. 2.5mA on Vbus): * - \code void user_callback_suspend_action(void) - { - turn_off_components(); - } \endcode + { + turn_off_components(); + } \endcode */ /** @@ -654,44 +647,42 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); * \subsection udc_use_case_6_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_SERIAL_NAME - #define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number - #define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 - extern uint8_t serial_number[]; + #define USB_DEVICE_SERIAL_NAME + #define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number + #define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 + extern uint8_t serial_number[]; \endcode * * Add to application C-file: * \code - uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; + uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; - void init_build_usb_serial_number(void) - { - serial_number[0] = 'A'; - serial_number[1] = 'B'; - ... - serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C'; - } \endcode + void init_build_usb_serial_number(void) + { + serial_number[0] = 'A'; + serial_number[1] = 'B'; + ... + serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C'; + } \endcode * * \subsection udc_use_case_6_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required to enable a USB serial number strings dynamically: * - \code #define USB_DEVICE_SERIAL_NAME // Define this empty - #define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number // Give serial array pointer - #define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 // Give size of serial array - extern uint8_t serial_number[]; // Declare external serial array \endcode + #define USB_DEVICE_GET_SERIAL_NAME_POINTER serial_number // Give serial array pointer + #define USB_DEVICE_GET_SERIAL_NAME_LENGTH 12 // Give size of serial array + extern uint8_t serial_number[]; // Declare external serial array \endcode * -# Before start USB stack, initialize the serial array * - \code - uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; + uint8_t serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH]; - void init_build_usb_serial_number(void) - { - serial_number[0] = 'A'; - serial_number[1] = 'B'; - ... - serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C'; - } \endcode + void init_build_usb_serial_number(void) + { + serial_number[0] = 'A'; + serial_number[1] = 'B'; + ... + serial_number[USB_DEVICE_GET_SERIAL_NAME_LENGTH-1] = 'C'; + } \endcode */ - - #endif // _UDC_H_ diff --git a/Marlin/src/HAL/DUE/usb/udc_desc.h b/Marlin/src/HAL/DUE/usb/udc_desc.h index 052ca08eca..f1f328d035 100644 --- a/Marlin/src/HAL/DUE/usb/udc_desc.h +++ b/Marlin/src/HAL/DUE/usb/udc_desc.h @@ -78,50 +78,47 @@ extern "C" { * For Mega application used "code". */ #define UDC_DESC_STORAGE - // Descriptor storage in internal RAM + // Descriptor storage in internal RAM #if (defined UDC_DATA_USE_HRAM_SUPPORT) -# if defined(__GNUC__) -# define UDC_DATA(x) COMPILER_WORD_ALIGNED __attribute__((__section__(".data_hram0"))) -# define UDC_BSS(x) COMPILER_ALIGNED(x) __attribute__((__section__(".bss_hram0"))) -# elif defined(__ICCAVR32__) -# define UDC_DATA(x) COMPILER_ALIGNED(x) __data32 -# define UDC_BSS(x) COMPILER_ALIGNED(x) __data32 -# endif -#else -# define UDC_DATA(x) COMPILER_ALIGNED(x) -# define UDC_BSS(x) COMPILER_ALIGNED(x) + #if defined(__GNUC__) + #define UDC_DATA(x) COMPILER_WORD_ALIGNED __attribute__((__section__(".data_hram0"))) + #define UDC_BSS(x) COMPILER_ALIGNED(x) __attribute__((__section__(".bss_hram0"))) +#elif defined(__ICCAVR32__) + #define UDC_DATA(x) COMPILER_ALIGNED(x) __data32 + #define UDC_BSS(x) COMPILER_ALIGNED(x) __data32 +#endif +#else + #define UDC_DATA(x) COMPILER_ALIGNED(x) + #define UDC_BSS(x) COMPILER_ALIGNED(x) #endif - - /** * \brief Configuration descriptor and UDI link for one USB speed */ typedef struct { - //! USB configuration descriptor - usb_conf_desc_t UDC_DESC_STORAGE *desc; - //! Array of UDI API pointer - udi_api_t UDC_DESC_STORAGE *UDC_DESC_STORAGE * udi_apis; + //! USB configuration descriptor + usb_conf_desc_t UDC_DESC_STORAGE *desc; + //! Array of UDI API pointer + udi_api_t UDC_DESC_STORAGE *UDC_DESC_STORAGE * udi_apis; } udc_config_speed_t; - /** * \brief All information about the USB Device */ typedef struct { - //! USB device descriptor for low or full speed - usb_dev_desc_t UDC_DESC_STORAGE *confdev_lsfs; - //! USB configuration descriptor and UDI API pointers for low or full speed - udc_config_speed_t UDC_DESC_STORAGE *conf_lsfs; -#ifdef USB_DEVICE_HS_SUPPORT - //! USB device descriptor for high speed - usb_dev_desc_t UDC_DESC_STORAGE *confdev_hs; - //! USB device qualifier, only use in high speed mode - usb_dev_qual_desc_t UDC_DESC_STORAGE *qualifier; - //! USB configuration descriptor and UDI API pointers for high speed - udc_config_speed_t UDC_DESC_STORAGE *conf_hs; -#endif - usb_dev_bos_desc_t UDC_DESC_STORAGE *conf_bos; + //! USB device descriptor for low or full speed + usb_dev_desc_t UDC_DESC_STORAGE *confdev_lsfs; + //! USB configuration descriptor and UDI API pointers for low or full speed + udc_config_speed_t UDC_DESC_STORAGE *conf_lsfs; + #ifdef USB_DEVICE_HS_SUPPORT + //! USB device descriptor for high speed + usb_dev_desc_t UDC_DESC_STORAGE *confdev_hs; + //! USB device qualifier, only use in high speed mode + usb_dev_qual_desc_t UDC_DESC_STORAGE *qualifier; + //! USB configuration descriptor and UDI API pointers for high speed + udc_config_speed_t UDC_DESC_STORAGE *conf_hs; + #endif + usb_dev_bos_desc_t UDC_DESC_STORAGE *conf_bos; } udc_config_t; //! Global variables of USB Device Descriptor and UDI links diff --git a/Marlin/src/HAL/DUE/usb/udd.h b/Marlin/src/HAL/DUE/usb/udd.h index 319d8842f7..4e482784e1 100644 --- a/Marlin/src/HAL/DUE/usb/udd.h +++ b/Marlin/src/HAL/DUE/usb/udd.h @@ -71,8 +71,8 @@ typedef uint8_t udd_ep_id_t; //! \brief Endpoint transfer status //! Returned in parameters of callback register via udd_ep_run routine. typedef enum { - UDD_EP_TRANSFER_OK = 0, - UDD_EP_TRANSFER_ABORT = 1, + UDD_EP_TRANSFER_OK = 0, + UDD_EP_TRANSFER_ABORT = 1, } udd_ep_status_t; /** @@ -82,41 +82,37 @@ typedef enum { * It can be updated by udc_process_setup() from UDC or *setup() from UDIs. */ typedef struct { - //! Data received in USB SETUP packet - //! Note: The swap of "req.wValues" from uin16_t to le16_t is done by UDD. - usb_setup_req_t req; + //! Data received in USB SETUP packet + //! Note: The swap of "req.wValues" from uin16_t to le16_t is done by UDD. + usb_setup_req_t req; - //! Point to buffer to send or fill with data following SETUP packet - //! This buffer must be word align for DATA IN phase (use prefix COMPILER_WORD_ALIGNED for buffer) - uint8_t *payload; + //! Point to buffer to send or fill with data following SETUP packet + //! This buffer must be word align for DATA IN phase (use prefix COMPILER_WORD_ALIGNED for buffer) + uint8_t *payload; - //! Size of buffer to send or fill, and content the number of byte transferred - uint16_t payload_size; + //! Size of buffer to send or fill, and content the number of byte transferred + uint16_t payload_size; - //! Callback called after reception of ZLP from setup request - void (*callback)(void); + //! Callback called after reception of ZLP from setup request + void (*callback)(void); - //! Callback called when the buffer given (.payload) is full or empty. - //! This one return false to abort data transfer, or true with a new buffer in .payload. - bool (*over_under_run)(void); + //! Callback called when the buffer given (.payload) is full or empty. + //! This one return false to abort data transfer, or true with a new buffer in .payload. + bool (*over_under_run)(void); } udd_ctrl_request_t; extern udd_ctrl_request_t udd_g_ctrlreq; //! Return true if the setup request \a udd_g_ctrlreq indicates IN data transfer -#define Udd_setup_is_in() \ - (USB_REQ_DIR_IN == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK)) +#define Udd_setup_is_in() (USB_REQ_DIR_IN == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK)) //! Return true if the setup request \a udd_g_ctrlreq indicates OUT data transfer -#define Udd_setup_is_out() \ - (USB_REQ_DIR_OUT == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK)) +#define Udd_setup_is_out() (USB_REQ_DIR_OUT == (udd_g_ctrlreq.req.bmRequestType & USB_REQ_DIR_MASK)) //! Return the type of the SETUP request \a udd_g_ctrlreq. \see usb_reqtype. -#define Udd_setup_type() \ - (udd_g_ctrlreq.req.bmRequestType & USB_REQ_TYPE_MASK) +#define Udd_setup_type() (udd_g_ctrlreq.req.bmRequestType & USB_REQ_TYPE_MASK) //! Return the recipient of the SETUP request \a udd_g_ctrlreq. \see usb_recipient -#define Udd_setup_recipient() \ - (udd_g_ctrlreq.req.bmRequestType & USB_REQ_RECIP_MASK) +#define Udd_setup_recipient() (udd_g_ctrlreq.req.bmRequestType & USB_REQ_RECIP_MASK) /** * \brief End of halt callback function type. @@ -134,8 +130,7 @@ typedef void (*udd_callback_halt_cleared_t)(void); * \param status UDD_EP_TRANSFER_ABORT, if transfer is aborted * \param n number of data transferred */ -typedef void (*udd_callback_trans_t) (udd_ep_status_t status, - iram_size_t nb_transferred, udd_ep_id_t ep); +typedef void (*udd_callback_trans_t) (udd_ep_status_t status, iram_size_t nb_transferred, udd_ep_id_t ep); /** * \brief Authorizes the VBUS event @@ -218,7 +213,6 @@ void udd_send_remotewakeup(void); */ void udd_set_setup_payload( uint8_t *payload, uint16_t payload_size ); - /** * \name Endpoint Management * @@ -239,8 +233,7 @@ void udd_set_setup_payload( uint8_t *payload, uint16_t payload_size ); * * \return \c 1 if the endpoint is enabled, otherwise \c 0. */ -bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes, - uint16_t MaxEndpointSize); +bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes, uint16_t MaxEndpointSize); /** * \brief Disables an endpoint @@ -294,8 +287,7 @@ bool udd_ep_clear_halt(udd_ep_id_t ep); * * \return \c 1 if the register is accepted, otherwise \c 0. */ -bool udd_ep_wait_stall_clear(udd_ep_id_t ep, - udd_callback_halt_cleared_t callback); +bool udd_ep_wait_stall_clear(udd_ep_id_t ep, udd_callback_halt_cleared_t callback); /** * \brief Allows to receive or send data on an endpoint @@ -321,9 +313,8 @@ bool udd_ep_wait_stall_clear(udd_ep_id_t ep, * * \return \c 1 if function was successfully done, otherwise \c 0. */ -bool udd_ep_run(udd_ep_id_t ep, bool b_shortpacket, - uint8_t * buf, iram_size_t buf_size, - udd_callback_trans_t callback); +bool udd_ep_run(udd_ep_id_t ep, bool b_shortpacket, uint8_t * buf, iram_size_t buf_size, udd_callback_trans_t callback); + /** * \brief Aborts transfer on going on endpoint * @@ -339,7 +330,6 @@ void udd_ep_abort(udd_ep_id_t ep); //@} - /** * \name High speed test mode management * @@ -352,7 +342,6 @@ void udd_test_mode_se0_nak(void); void udd_test_mode_packet(void); //@} - /** * \name UDC callbacks to provide for UDD * diff --git a/Marlin/src/HAL/DUE/usb/udi.h b/Marlin/src/HAL/DUE/usb/udi.h index febf03b718..bc5de086f3 100644 --- a/Marlin/src/HAL/DUE/usb/udi.h +++ b/Marlin/src/HAL/DUE/usb/udi.h @@ -72,57 +72,57 @@ extern "C" { * selected by UDC. */ typedef struct { - /** - * \brief Enable the interface. - * - * This function is called when the host selects a configuration - * to which this interface belongs through a Set Configuration - * request, and when the host selects an alternate setting of - * this interface through a Set Interface request. - * - * \return \c 1 if function was successfully done, otherwise \c 0. - */ - bool (*enable)(void); + /** + * \brief Enable the interface. + * + * This function is called when the host selects a configuration + * to which this interface belongs through a Set Configuration + * request, and when the host selects an alternate setting of + * this interface through a Set Interface request. + * + * \return \c 1 if function was successfully done, otherwise \c 0. + */ + bool (*enable)(void); - /** - * \brief Disable the interface. - * - * This function is called when this interface is currently - * active, and - * - the host selects any configuration through a Set - * Configuration request, or - * - the host issues a USB reset, or - * - the device is detached from the host (i.e. Vbus is no - * longer present) - */ - void (*disable)(void); + /** + * \brief Disable the interface. + * + * This function is called when this interface is currently + * active, and + * - the host selects any configuration through a Set + * Configuration request, or + * - the host issues a USB reset, or + * - the device is detached from the host (i.e. Vbus is no + * longer present) + */ + void (*disable)(void); - /** - * \brief Handle a control request directed at an interface. - * - * This function is called when this interface is currently - * active and the host sends a SETUP request - * with this interface as the recipient. - * - * Use udd_g_ctrlreq to decode and response to SETUP request. - * - * \return \c 1 if this interface supports the SETUP request, otherwise \c 0. - */ - bool (*setup)(void); + /** + * \brief Handle a control request directed at an interface. + * + * This function is called when this interface is currently + * active and the host sends a SETUP request + * with this interface as the recipient. + * + * Use udd_g_ctrlreq to decode and response to SETUP request. + * + * \return \c 1 if this interface supports the SETUP request, otherwise \c 0. + */ + bool (*setup)(void); - /** - * \brief Returns the current setting of the selected interface. - * - * This function is called when UDC when know alternate setting of selected interface. - * - * \return alternate setting of selected interface - */ - uint8_t (*getsetting)(void); + /** + * \brief Returns the current setting of the selected interface. + * + * This function is called when UDC when know alternate setting of selected interface. + * + * \return alternate setting of selected interface + */ + uint8_t (*getsetting)(void); - /** - * \brief To signal that a SOF is occurred - */ - void (*sof_notify)(void); + /** + * \brief To signal that a SOF is occurred + */ + void (*sof_notify)(void); } udi_api_t; //@} diff --git a/Marlin/src/HAL/DUE/usb/udi_cdc.c b/Marlin/src/HAL/DUE/usb/udi_cdc.c index 89debe57f1..26788570c6 100644 --- a/Marlin/src/HAL/DUE/usb/udi_cdc.c +++ b/Marlin/src/HAL/DUE/usb/udi_cdc.c @@ -457,7 +457,6 @@ void udi_cdc_data_sof_notify(void) #endif } - // ------------------------ //------- Internal routines to control serial line @@ -520,7 +519,6 @@ static void udi_cdc_ctrl_state_change(uint8_t port, bool b_set, le16_t bit_mask) udi_cdc_ctrl_state_notify(port, ep_comm); } - static void udi_cdc_ctrl_state_notify(uint8_t port, udd_ep_id_t ep) { #if UDI_CDC_PORT_NB == 1 // To optimize code @@ -542,7 +540,6 @@ static void udi_cdc_ctrl_state_notify(uint8_t port, udd_ep_id_t ep) } } - static void udi_cdc_serial_state_msg_sent(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep) { uint8_t port; @@ -578,11 +575,9 @@ static void udi_cdc_serial_state_msg_sent(udd_ep_status_t status, iram_size_t n, udi_cdc_ctrl_state_notify(port, ep); } - // ------------------------ //------- Internal routines to process data transfer - static bool udi_cdc_rx_start(uint8_t port) { irqflags_t flags; @@ -632,7 +627,6 @@ static bool udi_cdc_rx_start(uint8_t port) udi_cdc_data_received); } - static void udi_cdc_data_received(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep) { uint8_t buf_sel_trans; @@ -668,7 +662,6 @@ static void udi_cdc_data_received(udd_ep_status_t status, iram_size_t n, udd_ep_ udi_cdc_rx_start(port); } - static void udi_cdc_data_sent(udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep) { uint8_t port; @@ -700,7 +693,6 @@ static void udi_cdc_data_sent(udd_ep_status_t status, iram_size_t n, udd_ep_id_t udi_cdc_tx_send(port); } - static void udi_cdc_tx_send(uint8_t port) { irqflags_t flags; @@ -780,11 +772,9 @@ static void udi_cdc_tx_send(uint8_t port) udi_cdc_data_sent); } - // ------------------------ //------- Application interface - //------- Application interface void udi_cdc_ctrl_signal_dcd(bool b_set) diff --git a/Marlin/src/HAL/DUE/usb/udi_cdc.h b/Marlin/src/HAL/DUE/usb/udi_cdc.h index b61845011a..e9c6abbbb2 100644 --- a/Marlin/src/HAL/DUE/usb/udi_cdc.h +++ b/Marlin/src/HAL/DUE/usb/udi_cdc.h @@ -92,21 +92,20 @@ extern UDC_DESC_STORAGE udi_api_t udi_api_cdc_data; * descriptors for the CDC Communication Class interface. */ typedef struct { - //! Standard interface descriptor - usb_iface_desc_t iface; - //! CDC Header functional descriptor - usb_cdc_hdr_desc_t header; - //! CDC Abstract Control Model functional descriptor - usb_cdc_acm_desc_t acm; - //! CDC Union functional descriptor - usb_cdc_union_desc_t union_desc; - //! CDC Call Management functional descriptor - usb_cdc_call_mgmt_desc_t call_mgmt; - //! Notification endpoint descriptor - usb_ep_desc_t ep_notify; + //! Standard interface descriptor + usb_iface_desc_t iface; + //! CDC Header functional descriptor + usb_cdc_hdr_desc_t header; + //! CDC Abstract Control Model functional descriptor + usb_cdc_acm_desc_t acm; + //! CDC Union functional descriptor + usb_cdc_union_desc_t union_desc; + //! CDC Call Management functional descriptor + usb_cdc_call_mgmt_desc_t call_mgmt; + //! Notification endpoint descriptor + usb_ep_desc_t ep_notify; } udi_cdc_comm_desc_t; - /** * \brief Data Class interface descriptor * @@ -114,14 +113,13 @@ typedef struct { * CDC Data Class interface. */ typedef struct { - //! Standard interface descriptor - usb_iface_desc_t iface; - //! Data IN/OUT endpoint descriptors - usb_ep_desc_t ep_in; - usb_ep_desc_t ep_out; + //! Standard interface descriptor + usb_iface_desc_t iface; + //! Data IN/OUT endpoint descriptors + usb_ep_desc_t ep_in; + usb_ep_desc_t ep_out; } udi_cdc_data_desc_t; - //! CDC communication endpoints size for all speeds #define UDI_CDC_COMM_EP_SIZE 64 //! CDC data endpoints size for FS speed (8B, 16B, 32B, 64B) @@ -136,13 +134,13 @@ typedef struct { //@{ //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_0 -#define UDI_CDC_IAD_STRING_ID_0 0 + #define UDI_CDC_IAD_STRING_ID_0 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_0 -#define UDI_CDC_COMM_STRING_ID_0 0 + #define UDI_CDC_COMM_STRING_ID_0 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_0 -#define UDI_CDC_DATA_STRING_ID_0 0 + #define UDI_CDC_DATA_STRING_ID_0 0 #endif #define UDI_CDC_IAD_DESC_0 UDI_CDC_IAD_DESC(0) #define UDI_CDC_COMM_DESC_0 UDI_CDC_COMM_DESC(0) @@ -151,13 +149,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_1 -#define UDI_CDC_IAD_STRING_ID_1 0 + #define UDI_CDC_IAD_STRING_ID_1 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_1 -#define UDI_CDC_COMM_STRING_ID_1 0 + #define UDI_CDC_COMM_STRING_ID_1 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_1 -#define UDI_CDC_DATA_STRING_ID_1 0 + #define UDI_CDC_DATA_STRING_ID_1 0 #endif #define UDI_CDC_IAD_DESC_1 UDI_CDC_IAD_DESC(1) #define UDI_CDC_COMM_DESC_1 UDI_CDC_COMM_DESC(1) @@ -166,13 +164,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_2 -#define UDI_CDC_IAD_STRING_ID_2 0 + #define UDI_CDC_IAD_STRING_ID_2 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_2 -#define UDI_CDC_COMM_STRING_ID_2 0 + #define UDI_CDC_COMM_STRING_ID_2 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_2 -#define UDI_CDC_DATA_STRING_ID_2 0 + #define UDI_CDC_DATA_STRING_ID_2 0 #endif #define UDI_CDC_IAD_DESC_2 UDI_CDC_IAD_DESC(2) #define UDI_CDC_COMM_DESC_2 UDI_CDC_COMM_DESC(2) @@ -181,13 +179,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_3 -#define UDI_CDC_IAD_STRING_ID_3 0 + #define UDI_CDC_IAD_STRING_ID_3 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_3 -#define UDI_CDC_COMM_STRING_ID_3 0 + #define UDI_CDC_COMM_STRING_ID_3 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_3 -#define UDI_CDC_DATA_STRING_ID_3 0 + #define UDI_CDC_DATA_STRING_ID_3 0 #endif #define UDI_CDC_IAD_DESC_3 UDI_CDC_IAD_DESC(3) #define UDI_CDC_COMM_DESC_3 UDI_CDC_COMM_DESC(3) @@ -196,13 +194,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_4 -#define UDI_CDC_IAD_STRING_ID_4 0 + #define UDI_CDC_IAD_STRING_ID_4 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_4 -#define UDI_CDC_COMM_STRING_ID_4 0 + #define UDI_CDC_COMM_STRING_ID_4 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_4 -#define UDI_CDC_DATA_STRING_ID_4 0 + #define UDI_CDC_DATA_STRING_ID_4 0 #endif #define UDI_CDC_IAD_DESC_4 UDI_CDC_IAD_DESC(4) #define UDI_CDC_COMM_DESC_4 UDI_CDC_COMM_DESC(4) @@ -211,13 +209,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_5 -#define UDI_CDC_IAD_STRING_ID_5 0 + #define UDI_CDC_IAD_STRING_ID_5 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_5 -#define UDI_CDC_COMM_STRING_ID_5 0 + #define UDI_CDC_COMM_STRING_ID_5 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_5 -#define UDI_CDC_DATA_STRING_ID_5 0 + #define UDI_CDC_DATA_STRING_ID_5 0 #endif #define UDI_CDC_IAD_DESC_5 UDI_CDC_IAD_DESC(5) #define UDI_CDC_COMM_DESC_5 UDI_CDC_COMM_DESC(5) @@ -226,13 +224,13 @@ typedef struct { //! By default no string associated to these interfaces #ifndef UDI_CDC_IAD_STRING_ID_6 -#define UDI_CDC_IAD_STRING_ID_6 0 + #define UDI_CDC_IAD_STRING_ID_6 0 #endif #ifndef UDI_CDC_COMM_STRING_ID_6 -#define UDI_CDC_COMM_STRING_ID_6 0 + #define UDI_CDC_COMM_STRING_ID_6 0 #endif #ifndef UDI_CDC_DATA_STRING_ID_6 -#define UDI_CDC_DATA_STRING_ID_6 0 + #define UDI_CDC_DATA_STRING_ID_6 0 #endif #define UDI_CDC_IAD_DESC_6 UDI_CDC_IAD_DESC(6) #define UDI_CDC_COMM_DESC_6 UDI_CDC_COMM_DESC(6) @@ -240,7 +238,6 @@ typedef struct { #define UDI_CDC_DATA_DESC_6_HS UDI_CDC_DATA_DESC_HS(6) //@} - //! Content of CDC IAD interface descriptor for all speeds #define UDI_CDC_IAD_DESC(port) { \ .bLength = sizeof(usb_iad_desc_t),\ @@ -270,7 +267,7 @@ typedef struct { .call_mgmt.bDescriptorType = CDC_CS_INTERFACE,\ .call_mgmt.bDescriptorSubtype = CDC_SCS_CALL_MGMT,\ .call_mgmt.bmCapabilities = \ - CDC_CALL_MGMT_SUPPORTED | CDC_CALL_MGMT_OVER_DCI,\ + CDC_CALL_MGMT_SUPPORTED | CDC_CALL_MGMT_OVER_DCI,\ .acm.bFunctionLength = sizeof(usb_cdc_acm_desc_t),\ .acm.bDescriptorType = CDC_CS_INTERFACE,\ .acm.bDescriptorSubtype = CDC_SCS_ACM,\ @@ -610,40 +607,37 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * \subsection udi_cdc_basic_use_case_usage_code Example code * Content of conf_usb.h: * \code - #define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable() - extern bool my_callback_cdc_enable(void); - #define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable() - extern void my_callback_cdc_disable(void); - #define UDI_CDC_LOW_RATE + #define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable() + extern bool my_callback_cdc_enable(void); + #define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable() + extern void my_callback_cdc_disable(void); + #define UDI_CDC_LOW_RATE - #define UDI_CDC_DEFAULT_RATE 115200 - #define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1 - #define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE - #define UDI_CDC_DEFAULT_DATABITS 8 + #define UDI_CDC_DEFAULT_RATE 115200 + #define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1 + #define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE + #define UDI_CDC_DEFAULT_DATABITS 8 - #include "udi_cdc_conf.h" // At the end of conf_usb.h file + #include "udi_cdc_conf.h" // At the end of conf_usb.h file \endcode * * Add to application C-file: * \code - static bool my_flag_autorize_cdc_transfert = false; - bool my_callback_cdc_enable(void) - { - my_flag_autorize_cdc_transfert = true; - return true; - } - void my_callback_cdc_disable(void) - { - my_flag_autorize_cdc_transfert = false; - } + static bool my_flag_autorize_cdc_transfert = false; + bool my_callback_cdc_enable(void) { + my_flag_autorize_cdc_transfert = true; + return true; + } + void my_callback_cdc_disable(void) { + my_flag_autorize_cdc_transfert = false; + } - void task(void) - { - if (my_flag_autorize_cdc_transfert) { - udi_cdc_putc('A'); - udi_cdc_getc(); - } - } + void task(void) { + if (my_flag_autorize_cdc_transfert) { + udi_cdc_putc('A'); + udi_cdc_getc(); + } + } \endcode * * \subsection udi_cdc_basic_use_case_setup_flow Workflow @@ -652,14 +646,14 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * - \code #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for CDC \endcode * \note The USB serial number is mandatory when a CDC interface is used. * - \code #define UDI_CDC_ENABLE_EXT(port) my_callback_cdc_enable() - extern bool my_callback_cdc_enable(void); \endcode + extern bool my_callback_cdc_enable(void); \endcode * \note After the device enumeration (detecting and identifying USB devices), * the USB host starts the device configuration. When the USB CDC interface * from the device is accepted by the host, the USB host enables this interface and the * UDI_CDC_ENABLE_EXT() callback function is called and return true. * Thus, when this event is received, the data transfer on CDC interface are authorized. * - \code #define UDI_CDC_DISABLE_EXT(port) my_callback_cdc_disable() - extern void my_callback_cdc_disable(void); \endcode + extern void my_callback_cdc_disable(void); \endcode * \note When the USB device is unplugged or is reset by the USB host, the USB * interface is disabled and the UDI_CDC_DISABLE_EXT() callback function * is called. Thus, the data transfer must be stopped on CDC interface. @@ -667,19 +661,19 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * \note Define it when the transfer CDC Device to Host is a low rate * (<512000 bauds) to reduce CDC buffers size. * - \code #define UDI_CDC_DEFAULT_RATE 115200 - #define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1 - #define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE - #define UDI_CDC_DEFAULT_DATABITS 8 \endcode + #define UDI_CDC_DEFAULT_STOPBITS CDC_STOP_BITS_1 + #define UDI_CDC_DEFAULT_PARITY CDC_PAR_NONE + #define UDI_CDC_DEFAULT_DATABITS 8 \endcode * \note Default configuration of communication port at startup. * -# Send or wait data on CDC line: * - \code // Waits and gets a value on CDC line - int udi_cdc_getc(void); - // Reads a RAM buffer on CDC line - iram_size_t udi_cdc_read_buf(int *buf, iram_size_t size); - // Puts a byte on CDC line - int udi_cdc_putc(int value); - // Writes a RAM buffer on CDC line - iram_size_t udi_cdc_write_buf(const int *buf, iram_size_t size); \endcode + int udi_cdc_getc(void); + // Reads a RAM buffer on CDC line + iram_size_t udi_cdc_read_buf(int *buf, iram_size_t size); + // Puts a byte on CDC line + int udi_cdc_putc(int value); + // Writes a RAM buffer on CDC line + iram_size_t udi_cdc_write_buf(const int *buf, iram_size_t size); \endcode * * \section udi_cdc_use_cases Advanced use cases * For more advanced use of the UDI CDC module, see the following use cases: @@ -713,90 +707,90 @@ iram_size_t udi_cdc_multi_write_buf(uint8_t port, const void* buf, iram_size_t s * \subsection udi_cdc_use_case_composite_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_EP_CTRL_SIZE 64 - #define USB_DEVICE_NB_INTERFACE (X+2) - #define USB_DEVICE_MAX_EP (X+3) + #define USB_DEVICE_EP_CTRL_SIZE 64 + #define USB_DEVICE_NB_INTERFACE (X+2) + #define USB_DEVICE_MAX_EP (X+3) - #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX - #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX - #define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint - #define UDI_CDC_COMM_IFACE_NUMBER_0 X+0 - #define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 + #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX + #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX + #define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint + #define UDI_CDC_COMM_IFACE_NUMBER_0 X+0 + #define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 - #define UDI_COMPOSITE_DESC_T \ - usb_iad_desc_t udi_cdc_iad; \ - udi_cdc_comm_desc_t udi_cdc_comm; \ - udi_cdc_data_desc_t udi_cdc_data; \ - ... - #define UDI_COMPOSITE_DESC_FS \ - .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ - .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ - .udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \ - ... - #define UDI_COMPOSITE_DESC_HS \ - .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ - .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ - .udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \ - ... - #define UDI_COMPOSITE_API \ - &udi_api_cdc_comm, \ - &udi_api_cdc_data, \ - ... + #define UDI_COMPOSITE_DESC_T \ + usb_iad_desc_t udi_cdc_iad; \ + udi_cdc_comm_desc_t udi_cdc_comm; \ + udi_cdc_data_desc_t udi_cdc_data; \ + ... + #define UDI_COMPOSITE_DESC_FS \ + .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ + .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ + .udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \ + ... + #define UDI_COMPOSITE_DESC_HS \ + .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ + .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ + .udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \ + ... + #define UDI_COMPOSITE_API \ + &udi_api_cdc_comm, \ + &udi_api_cdc_data, \ + ... \endcode * * \subsection udi_cdc_use_case_composite_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required for a USB composite device configuration: * - \code // Endpoint control size, This must be: - // - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM) - // - 64 for a high speed device - #define USB_DEVICE_EP_CTRL_SIZE 64 - // Total Number of interfaces on this USB device. - // Add 2 for CDC. - #define USB_DEVICE_NB_INTERFACE (X+2) - // Total number of endpoints on this USB device. - // This must include each endpoint for each interface. - // Add 3 for CDC. - #define USB_DEVICE_MAX_EP (X+3) \endcode + // - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM) + // - 64 for a high speed device + #define USB_DEVICE_EP_CTRL_SIZE 64 + // Total Number of interfaces on this USB device. + // Add 2 for CDC. + #define USB_DEVICE_NB_INTERFACE (X+2) + // Total number of endpoints on this USB device. + // This must include each endpoint for each interface. + // Add 3 for CDC. + #define USB_DEVICE_MAX_EP (X+3) \endcode * -# Ensure that conf_usb.h contains the description of * composite device: * - \code // The endpoint numbers chosen by you for the CDC. - // The endpoint numbers starting from 1. - #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX - #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX - #define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint - // The interface index of an interface starting from 0 - #define UDI_CDC_COMM_IFACE_NUMBER_0 X+0 - #define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 \endcode + // The endpoint numbers starting from 1. + #define UDI_CDC_DATA_EP_IN_0 (1 | USB_EP_DIR_IN) // TX + #define UDI_CDC_DATA_EP_OUT_0 (2 | USB_EP_DIR_OUT) // RX + #define UDI_CDC_COMM_EP_0 (3 | USB_EP_DIR_IN) // Notify endpoint + // The interface index of an interface starting from 0 + #define UDI_CDC_COMM_IFACE_NUMBER_0 X+0 + #define UDI_CDC_DATA_IFACE_NUMBER_0 X+1 \endcode * -# Ensure that conf_usb.h contains the following parameters * required for a USB composite device configuration: * - \code // USB Interfaces descriptor structure - #define UDI_COMPOSITE_DESC_T \ - ... - usb_iad_desc_t udi_cdc_iad; \ - udi_cdc_comm_desc_t udi_cdc_comm; \ - udi_cdc_data_desc_t udi_cdc_data; \ - ... - // USB Interfaces descriptor value for Full Speed - #define UDI_COMPOSITE_DESC_FS \ - ... - .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ - .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ - .udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \ - ... - // USB Interfaces descriptor value for High Speed - #define UDI_COMPOSITE_DESC_HS \ - ... - .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ - .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ - .udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \ - ... - // USB Interface APIs - #define UDI_COMPOSITE_API \ - ... - &udi_api_cdc_comm, \ - &udi_api_cdc_data, \ - ... \endcode + #define UDI_COMPOSITE_DESC_T \ + ... + usb_iad_desc_t udi_cdc_iad; \ + udi_cdc_comm_desc_t udi_cdc_comm; \ + udi_cdc_data_desc_t udi_cdc_data; \ + ... + // USB Interfaces descriptor value for Full Speed + #define UDI_COMPOSITE_DESC_FS \ + ... + .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ + .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ + .udi_cdc_data = UDI_CDC_DATA_DESC_0_FS, \ + ... + // USB Interfaces descriptor value for High Speed + #define UDI_COMPOSITE_DESC_HS \ + ... + .udi_cdc_iad = UDI_CDC_IAD_DESC_0, \ + .udi_cdc_comm = UDI_CDC_COMM_DESC_0, \ + .udi_cdc_data = UDI_CDC_DATA_DESC_0_HS, \ + ... + // USB Interface APIs + #define UDI_COMPOSITE_API \ + ... + &udi_api_cdc_comm, \ + &udi_api_cdc_data, \ + ... \endcode * - \note The descriptors order given in the four lists above must be the * same as the order defined by all interface indexes. The interface index * orders are defined through UDI_X_IFACE_NUMBER defines.\n diff --git a/Marlin/src/HAL/DUE/usb/udi_cdc_desc.c b/Marlin/src/HAL/DUE/usb/udi_cdc_desc.c index 4c79e8df13..bcae362cef 100644 --- a/Marlin/src/HAL/DUE/usb/udi_cdc_desc.c +++ b/Marlin/src/HAL/DUE/usb/udi_cdc_desc.c @@ -109,7 +109,6 @@ UDC_DESC_STORAGE usb_dev_desc_t udc_device_desc = { .bNumConfigurations = 1 }; - #ifdef USB_DEVICE_HS_SUPPORT //! USB Device Qualifier Descriptor for HS COMPILER_WORD_ALIGNED diff --git a/Marlin/src/HAL/DUE/usb/udi_composite_desc.c b/Marlin/src/HAL/DUE/usb/udi_composite_desc.c index b10d043b9f..8fa5acbb3f 100644 --- a/Marlin/src/HAL/DUE/usb/udi_composite_desc.c +++ b/Marlin/src/HAL/DUE/usb/udi_composite_desc.c @@ -93,7 +93,6 @@ UDC_DESC_STORAGE usb_dev_desc_t udc_device_desc = { .bNumConfigurations = 1 }; - #ifdef USB_DEVICE_HS_SUPPORT //! USB Device Qualifier Descriptor for HS COMPILER_WORD_ALIGNED @@ -147,7 +146,6 @@ UDC_DESC_STORAGE udc_desc_t udc_desc_hs = { }; #endif - /** * \name UDC structures which contains all USB Device definitions */ diff --git a/Marlin/src/HAL/DUE/usb/udi_msc.c b/Marlin/src/HAL/DUE/usb/udi_msc.c index a75b5936b3..56664f4bf7 100644 --- a/Marlin/src/HAL/DUE/usb/udi_msc.c +++ b/Marlin/src/HAL/DUE/usb/udi_msc.c @@ -86,7 +86,6 @@ UDC_DESC_STORAGE udi_api_t udi_api_msc = { }; //@} - /** * \ingroup udi_msc_group * \defgroup udi_msc_group_internal Implementation of UDI MSC @@ -137,7 +136,6 @@ volatile bool udi_msc_b_reset_trans = true; //@} - /** * \name Internal routines */ @@ -190,7 +188,6 @@ static void udi_msc_cbw_received(udd_ep_status_t status, static bool udi_msc_cbw_validate(uint32_t alloc_len, uint8_t dir_flag); //@} - /** * \name Routines to process small data packet */ @@ -217,7 +214,6 @@ static void udi_msc_data_sent(udd_ep_status_t status, iram_size_t nb_sent, udd_ep_id_t ep); //@} - /** * \name Routines to process CSW packet */ @@ -250,7 +246,6 @@ static void udi_msc_csw_sent(udd_ep_status_t status, iram_size_t nb_sent, udd_ep_id_t ep); //@} - /** * \name Routines manage sense data */ @@ -307,7 +302,6 @@ static void udi_msc_sense_fail_cdb_invalid(void); static void udi_msc_sense_command_invalid(void); //@} - /** * \name Routines manage SCSI Commands */ @@ -372,9 +366,7 @@ static void udi_msc_sbc_trans(bool b_read); //@} - -bool udi_msc_enable(void) -{ +bool udi_msc_enable(void) { uint8_t lun; udi_msc_b_trans_req = false; udi_msc_b_cbw_invalid = false; @@ -397,18 +389,14 @@ bool udi_msc_enable(void) return true; } - -void udi_msc_disable(void) -{ +void udi_msc_disable(void) { udi_msc_b_trans_req = false; udi_msc_b_ack_trans = true; udi_msc_b_reset_trans = true; UDI_MSC_DISABLE_EXT(); } - -bool udi_msc_setup(void) -{ +bool udi_msc_setup(void) { if (Udd_setup_is_in()) { // Requests Interface GET if (Udd_setup_type() == USB_REQ_TYPE_CLASS) { @@ -451,17 +439,14 @@ bool udi_msc_setup(void) return false; // Not supported request } -uint8_t udi_msc_getsetting(void) -{ +uint8_t udi_msc_getsetting(void) { return 0; // MSC don't have multiple alternate setting } - // ------------------------ //------- Routines to process CBW packet -static void udi_msc_cbw_invalid(void) -{ +static void udi_msc_cbw_invalid(void) { if (!udi_msc_b_cbw_invalid) return; // Don't re-stall endpoint if error reset by setup udd_ep_set_halt(UDI_MSC_EP_OUT); @@ -469,8 +454,7 @@ static void udi_msc_cbw_invalid(void) udd_ep_wait_stall_clear(UDI_MSC_EP_OUT, udi_msc_cbw_invalid); } -static void udi_msc_csw_invalid(void) -{ +static void udi_msc_csw_invalid(void) { if (!udi_msc_b_cbw_invalid) return; // Don't re-stall endpoint if error reset by setup udd_ep_set_halt(UDI_MSC_EP_IN); @@ -478,8 +462,7 @@ static void udi_msc_csw_invalid(void) udd_ep_wait_stall_clear(UDI_MSC_EP_IN, udi_msc_csw_invalid); } -static void udi_msc_cbw_wait(void) -{ +static void udi_msc_cbw_wait(void) { // Register buffer and callback on OUT endpoint if (!udd_ep_run(UDI_MSC_EP_OUT, true, (uint8_t *) & udi_msc_cbw, @@ -490,10 +473,8 @@ static void udi_msc_cbw_wait(void) } } - static void udi_msc_cbw_received(udd_ep_status_t status, - iram_size_t nb_received, udd_ep_id_t ep) -{ + iram_size_t nb_received, udd_ep_id_t ep) { UNUSED(ep); // Check status of transfer if (UDD_EP_TRANSFER_OK != status) { @@ -582,9 +563,7 @@ static void udi_msc_cbw_received(udd_ep_status_t status, } } - -static bool udi_msc_cbw_validate(uint32_t alloc_len, uint8_t dir_flag) -{ +static bool udi_msc_cbw_validate(uint32_t alloc_len, uint8_t dir_flag) { /* * The following cases should result in a phase error: * - Case 2: Hn < Di @@ -612,12 +591,10 @@ static bool udi_msc_cbw_validate(uint32_t alloc_len, uint8_t dir_flag) return true; } - // ------------------------ //------- Routines to process small data packet -static void udi_msc_data_send(uint8_t * buffer, uint8_t buf_size) -{ +static void udi_msc_data_send(uint8_t * buffer, uint8_t buf_size) { // Sends data on IN endpoint if (!udd_ep_run(UDI_MSC_EP_IN, true, buffer, buf_size, udi_msc_data_sent)) { @@ -627,10 +604,8 @@ static void udi_msc_data_send(uint8_t * buffer, uint8_t buf_size) } } - static void udi_msc_data_sent(udd_ep_status_t status, iram_size_t nb_sent, - udd_ep_id_t ep) -{ + udd_ep_id_t ep) { UNUSED(ep); if (UDD_EP_TRANSFER_OK != status) { // Error protocol @@ -644,12 +619,10 @@ static void udi_msc_data_sent(udd_ep_status_t status, iram_size_t nb_sent, udi_msc_csw_process(); } - // ------------------------ //------- Routines to process CSW packet -static void udi_msc_csw_process(void) -{ +static void udi_msc_csw_process(void) { if (0 != udi_msc_csw.dCSWDataResidue) { // Residue not NULL // then STALL next request from USB host on corresponding endpoint @@ -664,9 +637,7 @@ static void udi_msc_csw_process(void) udi_msc_csw_send(); } - -void udi_msc_csw_send(void) -{ +void udi_msc_csw_send(void) { // Sends CSW on IN endpoint if (!udd_ep_run(UDI_MSC_EP_IN, false, (uint8_t *) & udi_msc_csw, @@ -678,10 +649,8 @@ void udi_msc_csw_send(void) } } - static void udi_msc_csw_sent(udd_ep_status_t status, iram_size_t nb_sent, - udd_ep_id_t ep) -{ + udd_ep_id_t ep) { UNUSED(ep); UNUSED(status); UNUSED(nb_sent); @@ -690,20 +659,17 @@ static void udi_msc_csw_sent(udd_ep_status_t status, iram_size_t nb_sent, udi_msc_cbw_wait(); } - // ------------------------ //------- Routines manage sense data -static void udi_msc_clear_sense(void) -{ +static void udi_msc_clear_sense(void) { memset((uint8_t*)&udi_msc_sense, 0, sizeof(struct scsi_request_sense_data)); udi_msc_sense.valid_reponse_code = SCSI_SENSE_VALID | SCSI_SENSE_CURRENT; udi_msc_sense.AddSenseLen = SCSI_SENSE_ADDL_LEN(sizeof(udi_msc_sense)); } static void udi_msc_sense_fail(uint8_t sense_key, uint16_t add_sense, - uint32_t lba) -{ + uint32_t lba) { udi_msc_clear_sense(); udi_msc_csw.bCSWStatus = USB_CSW_STATUS_FAIL; udi_msc_sense.sense_flag_key = sense_key; @@ -715,53 +681,39 @@ static void udi_msc_sense_fail(uint8_t sense_key, uint16_t add_sense, udi_msc_sense.AddSnsCodeQlfr = add_sense; } -static void udi_msc_sense_pass(void) -{ +static void udi_msc_sense_pass(void) { udi_msc_clear_sense(); udi_msc_csw.bCSWStatus = USB_CSW_STATUS_PASS; } - -static void udi_msc_sense_fail_not_present(void) -{ +static void udi_msc_sense_fail_not_present(void) { udi_msc_sense_fail(SCSI_SK_NOT_READY, SCSI_ASC_MEDIUM_NOT_PRESENT, 0); } -static void udi_msc_sense_fail_busy_or_change(void) -{ - udi_msc_sense_fail(SCSI_SK_UNIT_ATTENTION, - SCSI_ASC_NOT_READY_TO_READY_CHANGE, 0); +static void udi_msc_sense_fail_busy_or_change(void) { + udi_msc_sense_fail(SCSI_SK_UNIT_ATTENTION, SCSI_ASC_NOT_READY_TO_READY_CHANGE, 0); } -static void udi_msc_sense_fail_hardware(void) -{ - udi_msc_sense_fail(SCSI_SK_HARDWARE_ERROR, - SCSI_ASC_NO_ADDITIONAL_SENSE_INFO, 0); +static void udi_msc_sense_fail_hardware(void) { + udi_msc_sense_fail(SCSI_SK_HARDWARE_ERROR, SCSI_ASC_NO_ADDITIONAL_SENSE_INFO, 0); } -static void udi_msc_sense_fail_protected(void) -{ +static void udi_msc_sense_fail_protected(void) { udi_msc_sense_fail(SCSI_SK_DATA_PROTECT, SCSI_ASC_WRITE_PROTECTED, 0); } -static void udi_msc_sense_fail_cdb_invalid(void) -{ - udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, - SCSI_ASC_INVALID_FIELD_IN_CDB, 0); +static void udi_msc_sense_fail_cdb_invalid(void) { + udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, SCSI_ASC_INVALID_FIELD_IN_CDB, 0); } -static void udi_msc_sense_command_invalid(void) -{ - udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, - SCSI_ASC_INVALID_COMMAND_OPERATION_CODE, 0); +static void udi_msc_sense_command_invalid(void) { + udi_msc_sense_fail(SCSI_SK_ILLEGAL_REQUEST, SCSI_ASC_INVALID_COMMAND_OPERATION_CODE, 0); } - // ------------------------ //------- Routines manage SCSI Commands -static void udi_msc_spc_requestsense(void) -{ +static void udi_msc_spc_requestsense(void) { uint8_t length = udi_msc_cbw.CDB[4]; // Can't send more than sense data length @@ -774,9 +726,7 @@ static void udi_msc_spc_requestsense(void) udi_msc_data_send((uint8_t*)&udi_msc_sense, length); } - -static void udi_msc_spc_inquiry(void) -{ +static void udi_msc_spc_inquiry(void) { uint8_t length, i; UDC_DATA(4) // Constant inquiry data for all LUNs @@ -835,9 +785,7 @@ static void udi_msc_spc_inquiry(void) udi_msc_data_send((uint8_t *) & udi_msc_inquiry_data, length); } - -static bool udi_msc_spc_testunitready_global(void) -{ +static bool udi_msc_spc_testunitready_global(void) { switch (mem_test_unit_ready(udi_msc_cbw.bCBWLUN)) { case CTRL_GOOD: return true; // Don't change sense data @@ -855,9 +803,7 @@ static bool udi_msc_spc_testunitready_global(void) return false; } - -static void udi_msc_spc_testunitready(void) -{ +static void udi_msc_spc_testunitready(void) { if (udi_msc_spc_testunitready_global()) { // LUN ready, then update sense data with status pass udi_msc_sense_pass(); @@ -866,9 +812,7 @@ static void udi_msc_spc_testunitready(void) udi_msc_csw_process(); } - -static void udi_msc_spc_mode_sense(bool b_sense10) -{ +static void udi_msc_spc_mode_sense(bool b_sense10) { // Union of all mode sense structures union sense_6_10 { struct { @@ -943,9 +887,7 @@ static void udi_msc_spc_mode_sense(bool b_sense10) udi_msc_data_send((uint8_t *) & sense, request_lgt); } - -static void udi_msc_spc_prevent_allow_medium_removal(void) -{ +static void udi_msc_spc_prevent_allow_medium_removal(void) { uint8_t prevent = udi_msc_cbw.CDB[4]; if (0 == prevent) { udi_msc_sense_pass(); @@ -955,9 +897,7 @@ static void udi_msc_spc_prevent_allow_medium_removal(void) udi_msc_csw_process(); } - -static void udi_msc_sbc_start_stop(void) -{ +static void udi_msc_sbc_start_stop(void) { bool start = 0x1 & udi_msc_cbw.CDB[4]; bool loej = 0x2 & udi_msc_cbw.CDB[4]; if (loej) { @@ -967,9 +907,7 @@ static void udi_msc_sbc_start_stop(void) udi_msc_csw_process(); } - -static void udi_msc_sbc_read_capacity(void) -{ +static void udi_msc_sbc_read_capacity(void) { UDC_BSS(4) static struct sbc_read_capacity10_data udi_msc_capacity; if (!udi_msc_cbw_validate(sizeof(udi_msc_capacity), @@ -1003,9 +941,7 @@ static void udi_msc_sbc_read_capacity(void) sizeof(udi_msc_capacity)); } - -static void udi_msc_sbc_trans(bool b_read) -{ +static void udi_msc_sbc_trans(bool b_read) { uint32_t trans_size; if (!b_read) { @@ -1038,9 +974,7 @@ static void udi_msc_sbc_trans(bool b_read) UDI_MSC_NOTIFY_TRANS_EXT(); } - -bool udi_msc_process_trans(void) -{ +bool udi_msc_process_trans(void) { Ctrl_status status; if (!udi_msc_b_trans_req) @@ -1084,10 +1018,8 @@ bool udi_msc_process_trans(void) return true; } - static void udi_msc_trans_ack(udd_ep_status_t status, iram_size_t n, - udd_ep_id_t ep) -{ + udd_ep_id_t ep) { UNUSED(ep); UNUSED(n); // Update variable to signal the end of transfer @@ -1095,10 +1027,8 @@ static void udi_msc_trans_ack(udd_ep_status_t status, iram_size_t n, udi_msc_b_ack_trans = true; } - bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, - void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)) -{ + void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)) { if (!udi_msc_b_ack_trans) return false; // No possible, transfer on going diff --git a/Marlin/src/HAL/DUE/usb/udi_msc.h b/Marlin/src/HAL/DUE/usb/udi_msc.h index 730dbc8eec..0ede4d6a83 100644 --- a/Marlin/src/HAL/DUE/usb/udi_msc.h +++ b/Marlin/src/HAL/DUE/usb/udi_msc.h @@ -77,9 +77,9 @@ extern UDC_DESC_STORAGE udi_api_t udi_api_msc; //! Interface descriptor structure for MSC typedef struct { - usb_iface_desc_t iface; - usb_ep_desc_t ep_in; - usb_ep_desc_t ep_out; + usb_iface_desc_t iface; + usb_ep_desc_t ep_in; + usb_ep_desc_t ep_out; } udi_msc_desc_t; //! By default no string associated to this interface @@ -94,32 +94,32 @@ typedef struct { //! Content of MSC interface descriptor for all speeds #define UDI_MSC_DESC \ - .iface.bLength = sizeof(usb_iface_desc_t),\ - .iface.bDescriptorType = USB_DT_INTERFACE,\ - .iface.bInterfaceNumber = UDI_MSC_IFACE_NUMBER,\ - .iface.bAlternateSetting = 0,\ - .iface.bNumEndpoints = 2,\ - .iface.bInterfaceClass = MSC_CLASS,\ - .iface.bInterfaceSubClass = MSC_SUBCLASS_TRANSPARENT,\ - .iface.bInterfaceProtocol = MSC_PROTOCOL_BULK,\ - .iface.iInterface = UDI_MSC_STRING_ID,\ - .ep_in.bLength = sizeof(usb_ep_desc_t),\ - .ep_in.bDescriptorType = USB_DT_ENDPOINT,\ - .ep_in.bEndpointAddress = UDI_MSC_EP_IN,\ - .ep_in.bmAttributes = USB_EP_TYPE_BULK,\ - .ep_in.bInterval = 0,\ - .ep_out.bLength = sizeof(usb_ep_desc_t),\ - .ep_out.bDescriptorType = USB_DT_ENDPOINT,\ - .ep_out.bEndpointAddress = UDI_MSC_EP_OUT,\ - .ep_out.bmAttributes = USB_EP_TYPE_BULK,\ - .ep_out.bInterval = 0, + .iface.bLength = sizeof(usb_iface_desc_t),\ + .iface.bDescriptorType = USB_DT_INTERFACE,\ + .iface.bInterfaceNumber = UDI_MSC_IFACE_NUMBER,\ + .iface.bAlternateSetting = 0,\ + .iface.bNumEndpoints = 2,\ + .iface.bInterfaceClass = MSC_CLASS,\ + .iface.bInterfaceSubClass = MSC_SUBCLASS_TRANSPARENT,\ + .iface.bInterfaceProtocol = MSC_PROTOCOL_BULK,\ + .iface.iInterface = UDI_MSC_STRING_ID,\ + .ep_in.bLength = sizeof(usb_ep_desc_t),\ + .ep_in.bDescriptorType = USB_DT_ENDPOINT,\ + .ep_in.bEndpointAddress = UDI_MSC_EP_IN,\ + .ep_in.bmAttributes = USB_EP_TYPE_BULK,\ + .ep_in.bInterval = 0,\ + .ep_out.bLength = sizeof(usb_ep_desc_t),\ + .ep_out.bDescriptorType = USB_DT_ENDPOINT,\ + .ep_out.bEndpointAddress = UDI_MSC_EP_OUT,\ + .ep_out.bmAttributes = USB_EP_TYPE_BULK,\ + .ep_out.bInterval = 0, //! Content of MSC interface descriptor for full speed only #define UDI_MSC_DESC_FS {\ - UDI_MSC_DESC \ - .ep_in.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\ - .ep_out.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\ - } + UDI_MSC_DESC \ + .ep_in.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\ + .ep_out.wMaxPacketSize = LE16(UDI_MSC_EPS_SIZE_FS),\ + } //! Content of MSC interface descriptor for high speed only #define UDI_MSC_DESC_HS {\ @@ -129,7 +129,6 @@ typedef struct { } //@} - /** * \ingroup udi_group * \defgroup udi_msc_group USB Device Interface (UDI) for Mass Storage Class (MSC) @@ -163,14 +162,13 @@ bool udi_msc_process_trans(void); * \return \c 1 if function was successfully done, otherwise \c 0. */ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, - void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)); + void (*callback) (udd_ep_status_t status, iram_size_t n, udd_ep_id_t ep)); //@} #ifdef __cplusplus } #endif - /** * \page udi_msc_quickstart Quick start guide for USB device Mass Storage module (UDI MSC) * @@ -200,35 +198,32 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * \subsection udi_msc_basic_use_case_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for MSC - #define UDI_MSC_GLOBAL_VENDOR_ID \ - 'A', 'T', 'M', 'E', 'L', ' ', ' ', ' ' - #define UDI_MSC_GLOBAL_PRODUCT_VERSION \ - '1', '.', '0', '0' - #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable() - extern bool my_callback_msc_enable(void); - #define UDI_MSC_DISABLE_EXT() my_callback_msc_disable() - extern void my_callback_msc_disable(void); - #include "udi_msc_conf.h" // At the end of conf_usb.h file + #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for MSC + #define UDI_MSC_GLOBAL_VENDOR_ID \ + 'A', 'T', 'M', 'E', 'L', ' ', ' ', ' ' + #define UDI_MSC_GLOBAL_PRODUCT_VERSION \ + '1', '.', '0', '0' + #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable() + extern bool my_callback_msc_enable(void); + #define UDI_MSC_DISABLE_EXT() my_callback_msc_disable() + extern void my_callback_msc_disable(void); + #include "udi_msc_conf.h" // At the end of conf_usb.h file \endcode * * Add to application C-file: * \code - static bool my_flag_autorize_msc_transfert = false; - bool my_callback_msc_enable(void) - { - my_flag_autorize_msc_transfert = true; - return true; - } - void my_callback_msc_disable(void) - { - my_flag_autorize_msc_transfert = false; - } + static bool my_flag_autorize_msc_transfert = false; + bool my_callback_msc_enable(void) { + my_flag_autorize_msc_transfert = true; + return true; + } + void my_callback_msc_disable(void) { + my_flag_autorize_msc_transfert = false; + } - void task(void) - { - udi_msc_process_trans(); - } + void task(void) { + udi_msc_process_trans(); + } \endcode * * \subsection udi_msc_basic_use_case_setup_flow Workflow @@ -237,14 +232,14 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * - \code #define USB_DEVICE_SERIAL_NAME "12...EF" // Disk SN for MSC \endcode * \note The USB serial number is mandatory when a MSC interface is used. * - \code //! Vendor name and Product version of MSC interface - #define UDI_MSC_GLOBAL_VENDOR_ID \ - 'A', 'T', 'M', 'E', 'L', ' ', ' ', ' ' - #define UDI_MSC_GLOBAL_PRODUCT_VERSION \ - '1', '.', '0', '0' \endcode + #define UDI_MSC_GLOBAL_VENDOR_ID \ + 'A', 'T', 'M', 'E', 'L', ' ', ' ', ' ' + #define UDI_MSC_GLOBAL_PRODUCT_VERSION \ + '1', '.', '0', '0' \endcode * \note The USB MSC interface requires a vendor ID (8 ASCII characters) * and a product version (4 ASCII characters). * - \code #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable() - extern bool my_callback_msc_enable(void); \endcode + extern bool my_callback_msc_enable(void); \endcode * \note After the device enumeration (detecting and identifying USB devices), * the USB host starts the device configuration. When the USB MSC interface * from the device is accepted by the host, the USB host enables this interface and the @@ -252,7 +247,7 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * Thus, when this event is received, the tasks which call * udi_msc_process_trans() must be enabled. * - \code #define UDI_MSC_DISABLE_EXT() my_callback_msc_disable() - extern void my_callback_msc_disable(void); \endcode + extern void my_callback_msc_disable(void); \endcode * \note When the USB device is unplugged or is reset by the USB host, the USB * interface is disabled and the UDI_MSC_DISABLE_EXT() callback function * is called. Thus, it is recommended to disable the task which is called udi_msc_process_trans(). @@ -261,15 +256,15 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * must be done outside USB interrupt routine. This is done in the MSC process * ("udi_msc_process_trans()") called by main loop: * - \code * void task(void) { - udi_msc_process_trans(); - } \endcode + udi_msc_process_trans(); + } \endcode * -# The MSC speed depends on task periodicity. To get the best speed * the notification callback "UDI_MSC_NOTIFY_TRANS_EXT" can be used to wakeup * this task (Example, through a mutex): * - \code #define UDI_MSC_NOTIFY_TRANS_EXT() msc_notify_trans() - void msc_notify_trans(void) { - wakeup_my_task(); - } \endcode + void msc_notify_trans(void) { + wakeup_my_task(); + } \endcode * * \section udi_msc_use_cases Advanced use cases * For more advanced use of the UDI MSC module, see the following use cases: @@ -302,72 +297,72 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * \subsection udi_msc_use_case_composite_usage_code Example code * Content of conf_usb.h: * \code - #define USB_DEVICE_EP_CTRL_SIZE 64 - #define USB_DEVICE_NB_INTERFACE (X+1) - #define USB_DEVICE_MAX_EP (X+2) + #define USB_DEVICE_EP_CTRL_SIZE 64 + #define USB_DEVICE_NB_INTERFACE (X+1) + #define USB_DEVICE_MAX_EP (X+2) - #define UDI_MSC_EP_IN (X | USB_EP_DIR_IN) - #define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT) - #define UDI_MSC_IFACE_NUMBER X + #define UDI_MSC_EP_IN (X | USB_EP_DIR_IN) + #define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT) + #define UDI_MSC_IFACE_NUMBER X - #define UDI_COMPOSITE_DESC_T \ - udi_msc_desc_t udi_msc; \ - ... - #define UDI_COMPOSITE_DESC_FS \ - .udi_msc = UDI_MSC_DESC, \ - ... - #define UDI_COMPOSITE_DESC_HS \ - .udi_msc = UDI_MSC_DESC, \ - ... - #define UDI_COMPOSITE_API \ - &udi_api_msc, \ - ... + #define UDI_COMPOSITE_DESC_T \ + udi_msc_desc_t udi_msc; \ + ... + #define UDI_COMPOSITE_DESC_FS \ + .udi_msc = UDI_MSC_DESC, \ + ... + #define UDI_COMPOSITE_DESC_HS \ + .udi_msc = UDI_MSC_DESC, \ + ... + #define UDI_COMPOSITE_API \ + &udi_api_msc, \ + ... \endcode * * \subsection udi_msc_use_case_composite_usage_flow Workflow * -# Ensure that conf_usb.h is available and contains the following parameters * required for a USB composite device configuration: * - \code // Endpoint control size, This must be: - // - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM) - // - 64 for a high speed device - #define USB_DEVICE_EP_CTRL_SIZE 64 - // Total Number of interfaces on this USB device. - // Add 1 for MSC. - #define USB_DEVICE_NB_INTERFACE (X+1) - // Total number of endpoints on this USB device. - // This must include each endpoint for each interface. - // Add 2 for MSC. - #define USB_DEVICE_MAX_EP (X+2) \endcode + // - 8, 16, 32 or 64 for full speed device (8 is recommended to save RAM) + // - 64 for a high speed device + #define USB_DEVICE_EP_CTRL_SIZE 64 + // Total Number of interfaces on this USB device. + // Add 1 for MSC. + #define USB_DEVICE_NB_INTERFACE (X+1) + // Total number of endpoints on this USB device. + // This must include each endpoint for each interface. + // Add 2 for MSC. + #define USB_DEVICE_MAX_EP (X+2) \endcode * -# Ensure that conf_usb.h contains the description of * composite device: * - \code // The endpoint numbers chosen by you for the MSC. - // The endpoint numbers starting from 1. - #define UDI_MSC_EP_IN (X | USB_EP_DIR_IN) - #define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT) - // The interface index of an interface starting from 0 - #define UDI_MSC_IFACE_NUMBER X \endcode + // The endpoint numbers starting from 1. + #define UDI_MSC_EP_IN (X | USB_EP_DIR_IN) + #define UDI_MSC_EP_OUT (Y | USB_EP_DIR_OUT) + // The interface index of an interface starting from 0 + #define UDI_MSC_IFACE_NUMBER X \endcode * -# Ensure that conf_usb.h contains the following parameters * required for a USB composite device configuration: * - \code // USB Interfaces descriptor structure - #define UDI_COMPOSITE_DESC_T \ - ... - udi_msc_desc_t udi_msc; \ - ... - // USB Interfaces descriptor value for Full Speed - #define UDI_COMPOSITE_DESC_FS \ - ... - .udi_msc = UDI_MSC_DESC_FS, \ - ... - // USB Interfaces descriptor value for High Speed - #define UDI_COMPOSITE_DESC_HS \ - ... - .udi_msc = UDI_MSC_DESC_HS, \ - ... - // USB Interface APIs - #define UDI_COMPOSITE_API \ - ... - &udi_api_msc, \ - ... \endcode + #define UDI_COMPOSITE_DESC_T \ + ... + udi_msc_desc_t udi_msc; \ + ... + // USB Interfaces descriptor value for Full Speed + #define UDI_COMPOSITE_DESC_FS \ + ... + .udi_msc = UDI_MSC_DESC_FS, \ + ... + // USB Interfaces descriptor value for High Speed + #define UDI_COMPOSITE_DESC_HS \ + ... + .udi_msc = UDI_MSC_DESC_HS, \ + ... + // USB Interface APIs + #define UDI_COMPOSITE_API \ + ... + &udi_api_msc, \ + ... \endcode * - \note The descriptors order given in the four lists above must be the * same as the order defined by all interface indexes. The interface index * orders are defined through UDI_X_IFACE_NUMBER defines. diff --git a/Marlin/src/HAL/DUE/usb/uotghs_device_due.c b/Marlin/src/HAL/DUE/usb/uotghs_device_due.c index c7e8f8d991..6c0b133e01 100644 --- a/Marlin/src/HAL/DUE/usb/uotghs_device_due.c +++ b/Marlin/src/HAL/DUE/usb/uotghs_device_due.c @@ -276,7 +276,6 @@ # endif #endif - /** * \name Power management routine. */ @@ -293,7 +292,6 @@ static bool udd_b_idle; //! State of sleep manager static bool udd_b_sleep_initialized = false; - /*! \brief Authorize or not the CPU powerdown mode * * \param b_enable true to authorize idle mode @@ -321,7 +319,6 @@ static void udd_sleep_mode(bool b_idle) //@} - /** * \name Control endpoint low level management routine. * @@ -393,7 +390,6 @@ static void udd_ctrl_send_zlp_out(void); //! \brief Call callback associated to setup request static void udd_ctrl_endofrequest(void); - /** * \brief Main interrupt routine for control endpoint * @@ -405,7 +401,6 @@ static bool udd_ctrl_interrupt(void); //@} - /** * \name Management of bulk/interrupt/isochronous endpoints * @@ -443,7 +438,6 @@ typedef struct { uint8_t stall_requested:1; } udd_ep_job_t; - //! Array to register a job on bulk/interrupt/isochronous endpoint static udd_ep_job_t udd_ep_job[USB_DEVICE_MAX_EP]; @@ -505,7 +499,6 @@ static bool udd_ep_interrupt(void); #endif // (0!=USB_DEVICE_MAX_EP) //@} - // ------------------------ //--- INTERNAL ROUTINES TO MANAGED GLOBAL EVENTS @@ -642,13 +635,11 @@ udd_interrupt_sof_end: return; } - bool udd_include_vbus_monitoring(void) { return true; } - void udd_enable(void) { irqflags_t flags; @@ -735,7 +726,6 @@ void udd_enable(void) cpu_irq_restore(flags); } - void udd_disable(void) { irqflags_t flags; @@ -776,7 +766,6 @@ void udd_disable(void) cpu_irq_restore(flags); } - void udd_attach(void) { irqflags_t flags; @@ -817,7 +806,6 @@ void udd_attach(void) cpu_irq_restore(flags); } - void udd_detach(void) { otg_unfreeze_clock(); @@ -828,7 +816,6 @@ void udd_detach(void) udd_sleep_mode(false); } - bool udd_is_high_speed(void) { #ifdef USB_DEVICE_HS_SUPPORT @@ -838,7 +825,6 @@ bool udd_is_high_speed(void) #endif } - void udd_set_address(uint8_t address) { udd_disable_address(); @@ -846,13 +832,11 @@ void udd_set_address(uint8_t address) udd_enable_address(); } - uint8_t udd_getaddress(void) { return udd_get_configured_address(); } - uint16_t udd_get_frame_number(void) { return udd_frame_number(); @@ -875,14 +859,12 @@ void udd_send_remotewakeup(void) } } - void udd_set_setup_payload(uint8_t *payload, uint16_t payload_size) { udd_g_ctrlreq.payload = payload; udd_g_ctrlreq.payload_size = payload_size; } - #if (0 != USB_DEVICE_MAX_EP) bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes, uint16_t MaxEndpointSize) @@ -1006,7 +988,6 @@ bool udd_ep_alloc(udd_ep_id_t ep, uint8_t bmAttributes, return true; } - void udd_ep_free(udd_ep_id_t ep) { uint8_t ep_index = ep & USB_EP_ADDR_MASK; @@ -1019,14 +1000,12 @@ void udd_ep_free(udd_ep_id_t ep) udd_ep_job[ep_index - 1].stall_requested = false; } - bool udd_ep_is_halted(udd_ep_id_t ep) { uint8_t ep_index = ep & USB_EP_ADDR_MASK; return Is_udd_endpoint_stall_requested(ep_index); } - bool udd_ep_set_halt(udd_ep_id_t ep) { uint8_t ep_index = ep & USB_EP_ADDR_MASK; @@ -1067,7 +1046,6 @@ bool udd_ep_set_halt(udd_ep_id_t ep) return true; } - bool udd_ep_clear_halt(udd_ep_id_t ep) { uint8_t ep_index = ep & USB_EP_ADDR_MASK; @@ -1108,7 +1086,6 @@ bool udd_ep_clear_halt(udd_ep_id_t ep) return true; } - bool udd_ep_run(udd_ep_id_t ep, bool b_shortpacket, uint8_t * buf, iram_size_t buf_size, udd_callback_trans_t callback) @@ -1175,7 +1152,6 @@ bool udd_ep_run(udd_ep_id_t ep, bool b_shortpacket, #endif } - void udd_ep_abort(udd_ep_id_t ep) { uint8_t ep_index = ep & USB_EP_ADDR_MASK; @@ -1204,7 +1180,6 @@ void udd_ep_abort(udd_ep_id_t ep) udd_ep_abort_job(ep); } - bool udd_ep_wait_stall_clear(udd_ep_id_t ep, udd_callback_halt_cleared_t callback) { @@ -1239,7 +1214,6 @@ bool udd_ep_wait_stall_clear(udd_ep_id_t ep, } #endif // (0 != USB_DEVICE_MAX_EP) - #ifdef USB_DEVICE_HS_SUPPORT void udd_test_mode_j(void) @@ -1248,20 +1222,17 @@ void udd_test_mode_j(void) udd_enable_hs_test_mode_j(); } - void udd_test_mode_k(void) { udd_enable_hs_test_mode(); udd_enable_hs_test_mode_k(); } - void udd_test_mode_se0_nak(void) { udd_enable_hs_test_mode(); } - void udd_test_mode_packet(void) { uint8_t i; @@ -1305,8 +1276,6 @@ void udd_test_mode_packet(void) } #endif // USB_DEVICE_HS_SUPPORT - - // ------------------------ //--- INTERNAL ROUTINES TO MANAGED THE CONTROL ENDPOINT @@ -1356,7 +1325,6 @@ static void udd_ctrl_init(void) udd_ep_control_state = UDD_EPCTRL_SETUP; } - static void udd_ctrl_setup_received(void) { irqflags_t flags; @@ -1418,7 +1386,6 @@ static void udd_ctrl_setup_received(void) } } - static void udd_ctrl_in_sent(void) { static bool b_shortpacket = false; @@ -1502,7 +1469,6 @@ static void udd_ctrl_in_sent(void) cpu_irq_restore(flags); } - static void udd_ctrl_out_received(void) { irqflags_t flags; @@ -1593,7 +1559,6 @@ static void udd_ctrl_out_received(void) cpu_irq_restore(flags); } - static void udd_ctrl_underflow(void) { if (Is_udd_out_received(0)) @@ -1610,7 +1575,6 @@ static void udd_ctrl_underflow(void) } } - static void udd_ctrl_overflow(void) { if (Is_udd_in_send(0)) @@ -1626,7 +1590,6 @@ static void udd_ctrl_overflow(void) } } - static void udd_ctrl_stall_data(void) { // Stall all packets on IN & OUT control endpoint @@ -1634,7 +1597,6 @@ static void udd_ctrl_stall_data(void) udd_enable_stall_handshake(0); } - static void udd_ctrl_send_zlp_in(void) { irqflags_t flags; @@ -1652,7 +1614,6 @@ static void udd_ctrl_send_zlp_in(void) cpu_irq_restore(flags); } - static void udd_ctrl_send_zlp_out(void) { irqflags_t flags; @@ -1668,7 +1629,6 @@ static void udd_ctrl_send_zlp_out(void) cpu_irq_restore(flags); } - static void udd_ctrl_endofrequest(void) { // If a callback is registered then call it @@ -1677,7 +1637,6 @@ static void udd_ctrl_endofrequest(void) } } - static bool udd_ctrl_interrupt(void) { @@ -1728,7 +1687,6 @@ static bool udd_ctrl_interrupt(void) return false; } - // ------------------------ //--- INTERNAL ROUTINES TO MANAGED THE BULK/INTERRUPT/ISOCHRONOUS ENDPOINTS @@ -1743,7 +1701,6 @@ static void udd_ep_job_table_reset(void) } } - static void udd_ep_job_table_kill(void) { uint8_t i; @@ -1754,7 +1711,6 @@ static void udd_ep_job_table_kill(void) } } - static void udd_ep_abort_job(udd_ep_id_t ep) { ep &= USB_EP_ADDR_MASK; @@ -1763,7 +1719,6 @@ static void udd_ep_abort_job(udd_ep_id_t ep) udd_ep_finish_job(&udd_ep_job[ep - 1], true, ep); } - static void udd_ep_finish_job(udd_ep_job_t * ptr_job, bool b_abort, uint8_t ep_num) { if (ptr_job->busy == false) { @@ -1834,7 +1789,6 @@ static void udd_ep_trans_done(udd_ep_id_t ep) udd_dma_ctrl |= UOTGHS_DEVDMACONTROL_END_BUFFIT | UOTGHS_DEVDMACONTROL_CHANN_ENB; - // Disable IRQs to have a short sequence // between read of EOT_STA and DMA enable flags = cpu_irq_save(); diff --git a/Marlin/src/HAL/DUE/usb/uotghs_device_due.h b/Marlin/src/HAL/DUE/usb/uotghs_device_due.h index 6df26d63df..99ad492c1f 100644 --- a/Marlin/src/HAL/DUE/usb/uotghs_device_due.h +++ b/Marlin/src/HAL/DUE/usb/uotghs_device_due.h @@ -129,7 +129,6 @@ extern "C" { #define Is_udd_vbus_transition() (Tst_bits(UOTGHS->UOTGHS_SR, UOTGHS_SR_VBUSTI)) //! @} - //! @name UOTGHS device attach control //! These macros manage the UOTGHS Device attach. //! @{ @@ -141,7 +140,6 @@ extern "C" { #define Is_udd_detached() (Tst_bits(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_DETACH)) //! @} - //! @name UOTGHS device bus events control //! These macros manage the UOTGHS Device bus events. //! @{ @@ -246,7 +244,6 @@ extern "C" { #define udd_get_configured_address() (Rd_bitfield(UOTGHS->UOTGHS_DEVCTRL, UOTGHS_DEVCTRL_UADD_Msk)) //! @} - //! @name UOTGHS Device endpoint drivers //! These macros manage the common features of the endpoints. //! @{ @@ -330,7 +327,6 @@ extern "C" { #define udd_data_toggle(ep) (Rd_bitfield(UOTGHS_ARRAY(UOTGHS_DEVEPTISR[0], ep), UOTGHS_DEVEPTISR_DTSEQ_Msk)) //! @} - //! @name UOTGHS Device control endpoint //! These macros control the endpoints. //! @{ @@ -530,7 +526,6 @@ extern "C" { //! Tests if IN sending interrupt is enabled #define Is_udd_in_send_interrupt_enabled(ep) (Tst_bits(UOTGHS_ARRAY(UOTGHS_DEVEPTIMR[0], ep), UOTGHS_DEVEPTIMR_TXINE)) - //! Get 64-, 32-, 16- or 8-bit access to FIFO data register of selected endpoint. //! @param ep Endpoint of which to access FIFO data register //! @param scale Data scale in bits: 64, 32, 16 or 8 @@ -652,7 +647,6 @@ typedef struct { //! @} //! @} - /// @cond 0 /**INDENT-OFF**/ #ifdef __cplusplus diff --git a/Marlin/src/HAL/DUE/usb/uotghs_otg.h b/Marlin/src/HAL/DUE/usb/uotghs_otg.h index eca5e938bb..8c12a3e291 100644 --- a/Marlin/src/HAL/DUE/usb/uotghs_otg.h +++ b/Marlin/src/HAL/DUE/usb/uotghs_otg.h @@ -53,7 +53,6 @@ extern "C" { #endif - //! \ingroup usb_group //! \defgroup otg_group UOTGHS OTG Driver //! UOTGHS low-level driver for OTG features @@ -74,7 +73,6 @@ bool otg_dual_enable(void); */ void otg_dual_disable(void); - //! @name UOTGHS OTG ID pin management //! The ID pin come from the USB OTG connector (A and B receptable) and //! allows to select the USB mode host or device. @@ -127,13 +125,13 @@ void otg_dual_disable(void); //! These macros allows to enable/disable pad and UOTGHS hardware //! @{ //! Reset USB macro -#define otg_reset() \ - do { \ - UOTGHS->UOTGHS_CTRL = 0; \ - while( UOTGHS->UOTGHS_SR & 0x3FFF) {\ - UOTGHS->UOTGHS_SCR = 0xFFFFFFFF;\ - } \ - } while (0) +#define otg_reset() \ + do { \ + UOTGHS->UOTGHS_CTRL = 0; \ + while( UOTGHS->UOTGHS_SR & 0x3FFF) { \ + UOTGHS->UOTGHS_SCR = 0xFFFFFFFF; \ + } \ + } while (0) //! Enable USB macro #define otg_enable() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_USBE)) //! Disable USB macro @@ -157,15 +155,14 @@ void otg_dual_disable(void); //! Configure time-out of specified OTG timer #define otg_configure_timeout(timer, timeout) (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\ - Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\ - Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk, timeout),\ - Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK)) + Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\ + Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk, timeout),\ + Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK)) //! Get configured time-out of specified OTG timer #define otg_get_timeout(timer) (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\ - Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\ - Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\ - Rd_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk)) - + Wr_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMPAGE_Msk, timer),\ + Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_UNLOCK),\ + Rd_bitfield(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_TIMVALUE_Msk)) //! Get the dual-role device state of the internal USB finite state machine of the UOTGHS controller #define otg_get_fsm_drd_state() (Rd_bitfield(UOTGHS->UOTGHS_FSM, UOTGHS_FSM_DRDSTATE_Msk)) diff --git a/Marlin/src/HAL/DUE/usb/usb_protocol.h b/Marlin/src/HAL/DUE/usb/usb_protocol.h index ea51a86896..9bf0a1ba60 100644 --- a/Marlin/src/HAL/DUE/usb/usb_protocol.h +++ b/Marlin/src/HAL/DUE/usb/usb_protocol.h @@ -108,17 +108,17 @@ * \brief Standard USB requests (bRequest) */ enum usb_reqid { - USB_REQ_GET_STATUS = 0, - USB_REQ_CLEAR_FEATURE = 1, - USB_REQ_SET_FEATURE = 3, - USB_REQ_SET_ADDRESS = 5, - USB_REQ_GET_DESCRIPTOR = 6, - USB_REQ_SET_DESCRIPTOR = 7, - USB_REQ_GET_CONFIGURATION = 8, - USB_REQ_SET_CONFIGURATION = 9, - USB_REQ_GET_INTERFACE = 10, - USB_REQ_SET_INTERFACE = 11, - USB_REQ_SYNCH_FRAME = 12, + USB_REQ_GET_STATUS = 0, + USB_REQ_CLEAR_FEATURE = 1, + USB_REQ_SET_FEATURE = 3, + USB_REQ_SET_ADDRESS = 5, + USB_REQ_GET_DESCRIPTOR = 6, + USB_REQ_SET_DESCRIPTOR = 7, + USB_REQ_GET_CONFIGURATION = 8, + USB_REQ_SET_CONFIGURATION = 9, + USB_REQ_GET_INTERFACE = 10, + USB_REQ_SET_INTERFACE = 11, + USB_REQ_SYNCH_FRAME = 12, }; /** @@ -126,9 +126,9 @@ enum usb_reqid { * */ enum usb_device_status { - USB_DEV_STATUS_BUS_POWERED = 0, - USB_DEV_STATUS_SELF_POWERED = 1, - USB_DEV_STATUS_REMOTEWAKEUP = 2 + USB_DEV_STATUS_BUS_POWERED = 0, + USB_DEV_STATUS_SELF_POWERED = 1, + USB_DEV_STATUS_REMOTEWAKEUP = 2 }; /** @@ -136,7 +136,7 @@ enum usb_device_status { * */ enum usb_interface_status { - USB_IFACE_STATUS_RESERVED = 0 + USB_IFACE_STATUS_RESERVED = 0 }; /** @@ -144,7 +144,7 @@ enum usb_interface_status { * */ enum usb_endpoint_status { - USB_EP_STATUS_HALTED = 1, + USB_EP_STATUS_HALTED = 1, }; /** @@ -153,11 +153,11 @@ enum usb_endpoint_status { * \note valid for SetFeature request. */ enum usb_device_feature { - USB_DEV_FEATURE_REMOTE_WAKEUP = 1, //!< Remote wakeup enabled - USB_DEV_FEATURE_TEST_MODE = 2, //!< USB test mode - USB_DEV_FEATURE_OTG_B_HNP_ENABLE = 3, - USB_DEV_FEATURE_OTG_A_HNP_SUPPORT = 4, - USB_DEV_FEATURE_OTG_A_ALT_HNP_SUPPORT = 5 + USB_DEV_FEATURE_REMOTE_WAKEUP = 1, //!< Remote wakeup enabled + USB_DEV_FEATURE_TEST_MODE = 2, //!< USB test mode + USB_DEV_FEATURE_OTG_B_HNP_ENABLE = 3, + USB_DEV_FEATURE_OTG_A_HNP_SUPPORT = 4, + USB_DEV_FEATURE_OTG_A_ALT_HNP_SUPPORT = 5 }; /** @@ -166,54 +166,54 @@ enum usb_device_feature { * \note valid for USB_DEV_FEATURE_TEST_MODE request. */ enum usb_device_hs_test_mode { - USB_DEV_TEST_MODE_J = 1, - USB_DEV_TEST_MODE_K = 2, - USB_DEV_TEST_MODE_SE0_NAK = 3, - USB_DEV_TEST_MODE_PACKET = 4, - USB_DEV_TEST_MODE_FORCE_ENABLE = 5, + USB_DEV_TEST_MODE_J = 1, + USB_DEV_TEST_MODE_K = 2, + USB_DEV_TEST_MODE_SE0_NAK = 3, + USB_DEV_TEST_MODE_PACKET = 4, + USB_DEV_TEST_MODE_FORCE_ENABLE = 5, }; /** * \brief Standard USB endpoint feature/status flags */ enum usb_endpoint_feature { - USB_EP_FEATURE_HALT = 0, + USB_EP_FEATURE_HALT = 0, }; /** * \brief Standard USB Test Mode Selectors */ enum usb_test_mode_selector { - USB_TEST_J = 0x01, - USB_TEST_K = 0x02, - USB_TEST_SE0_NAK = 0x03, - USB_TEST_PACKET = 0x04, - USB_TEST_FORCE_ENABLE = 0x05, + USB_TEST_J = 0x01, + USB_TEST_K = 0x02, + USB_TEST_SE0_NAK = 0x03, + USB_TEST_PACKET = 0x04, + USB_TEST_FORCE_ENABLE = 0x05, }; /** * \brief Standard USB descriptor types */ enum usb_descriptor_type { - USB_DT_DEVICE = 1, - USB_DT_CONFIGURATION = 2, - USB_DT_STRING = 3, - USB_DT_INTERFACE = 4, - USB_DT_ENDPOINT = 5, - USB_DT_DEVICE_QUALIFIER = 6, - USB_DT_OTHER_SPEED_CONFIGURATION = 7, - USB_DT_INTERFACE_POWER = 8, - USB_DT_OTG = 9, - USB_DT_IAD = 0x0B, - USB_DT_BOS = 0x0F, - USB_DT_DEVICE_CAPABILITY = 0x10, + USB_DT_DEVICE = 1, + USB_DT_CONFIGURATION = 2, + USB_DT_STRING = 3, + USB_DT_INTERFACE = 4, + USB_DT_ENDPOINT = 5, + USB_DT_DEVICE_QUALIFIER = 6, + USB_DT_OTHER_SPEED_CONFIGURATION = 7, + USB_DT_INTERFACE_POWER = 8, + USB_DT_OTG = 9, + USB_DT_IAD = 0x0B, + USB_DT_BOS = 0x0F, + USB_DT_DEVICE_CAPABILITY = 0x10, }; /** * \brief USB Device Capability types */ enum usb_capability_type { - USB_DC_USB20_EXTENSION = 0x02, + USB_DC_USB20_EXTENSION = 0x02, }; /** @@ -221,7 +221,7 @@ enum usb_capability_type { * To fill bmAttributes field of usb_capa_ext_desc_t structure. */ enum usb_capability_extension_attr { - USB_DC_EXT_LPM = 0x00000002, + USB_DC_EXT_LPM = 0x00000002, }; #define HIRD_50_US 0 @@ -254,18 +254,18 @@ enum usb_capability_extension_attr { * \brief Standard USB endpoint transfer types */ enum usb_ep_type { - USB_EP_TYPE_CONTROL = 0x00, - USB_EP_TYPE_ISOCHRONOUS = 0x01, - USB_EP_TYPE_BULK = 0x02, - USB_EP_TYPE_INTERRUPT = 0x03, - USB_EP_TYPE_MASK = 0x03, + USB_EP_TYPE_CONTROL = 0x00, + USB_EP_TYPE_ISOCHRONOUS = 0x01, + USB_EP_TYPE_BULK = 0x02, + USB_EP_TYPE_INTERRUPT = 0x03, + USB_EP_TYPE_MASK = 0x03, }; /** * \brief Standard USB language IDs for string descriptors */ enum usb_langid { - USB_LANGID_EN_US = 0x0409, //!< English (United States) + USB_LANGID_EN_US = 0x0409, //!< English (United States) }; /** @@ -308,31 +308,31 @@ COMPILER_PACK_SET(1) * The data payload of SETUP packets always follows this structure. */ typedef struct { - uint8_t bmRequestType; - uint8_t bRequest; - le16_t wValue; - le16_t wIndex; - le16_t wLength; + uint8_t bmRequestType; + uint8_t bRequest; + le16_t wValue; + le16_t wIndex; + le16_t wLength; } usb_setup_req_t; /** * \brief Standard USB device descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - le16_t bcdUSB; - uint8_t bDeviceClass; - uint8_t bDeviceSubClass; - uint8_t bDeviceProtocol; - uint8_t bMaxPacketSize0; - le16_t idVendor; - le16_t idProduct; - le16_t bcdDevice; - uint8_t iManufacturer; - uint8_t iProduct; - uint8_t iSerialNumber; - uint8_t bNumConfigurations; + uint8_t bLength; + uint8_t bDescriptorType; + le16_t bcdUSB; + uint8_t bDeviceClass; + uint8_t bDeviceSubClass; + uint8_t bDeviceProtocol; + uint8_t bMaxPacketSize0; + le16_t idVendor; + le16_t idProduct; + le16_t bcdDevice; + uint8_t iManufacturer; + uint8_t iProduct; + uint8_t iSerialNumber; + uint8_t bNumConfigurations; } usb_dev_desc_t; /** @@ -344,15 +344,15 @@ typedef struct { * the device was operating at full speed.) */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - le16_t bcdUSB; - uint8_t bDeviceClass; - uint8_t bDeviceSubClass; - uint8_t bDeviceProtocol; - uint8_t bMaxPacketSize0; - uint8_t bNumConfigurations; - uint8_t bReserved; + uint8_t bLength; + uint8_t bDescriptorType; + le16_t bcdUSB; + uint8_t bDeviceClass; + uint8_t bDeviceSubClass; + uint8_t bDeviceProtocol; + uint8_t bMaxPacketSize0; + uint8_t bNumConfigurations; + uint8_t bReserved; } usb_dev_qual_desc_t; /** @@ -368,23 +368,22 @@ typedef struct { * The descriptor type in the GetDescriptor() request is set to BOS. */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - le16_t wTotalLength; - uint8_t bNumDeviceCaps; + uint8_t bLength; + uint8_t bDescriptorType; + le16_t wTotalLength; + uint8_t bNumDeviceCaps; } usb_dev_bos_desc_t; - /** * \brief USB Device Capabilities - USB 2.0 Extension Descriptor structure * * Defines the set of USB 1.1-specific device level capabilities. */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - uint8_t bDevCapabilityType; - le32_t bmAttributes; + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bDevCapabilityType; + le32_t bmAttributes; } usb_dev_capa_ext_desc_t; /** @@ -393,40 +392,38 @@ typedef struct { * The BOS descriptor and capabilities descriptors for LPM. */ typedef struct { - usb_dev_bos_desc_t bos; - usb_dev_capa_ext_desc_t capa_ext; + usb_dev_bos_desc_t bos; + usb_dev_capa_ext_desc_t capa_ext; } usb_dev_lpm_desc_t; /** * \brief Standard USB Interface Association Descriptor structure */ typedef struct { - uint8_t bLength; //!< size of this descriptor in bytes - uint8_t bDescriptorType; //!< INTERFACE descriptor type - uint8_t bFirstInterface; //!< Number of interface - uint8_t bInterfaceCount; //!< value to select alternate setting - uint8_t bFunctionClass; //!< Class code assigned by the USB - uint8_t bFunctionSubClass;//!< Sub-class code assigned by the USB - uint8_t bFunctionProtocol;//!< Protocol code assigned by the USB - uint8_t iFunction; //!< Index of string descriptor + uint8_t bLength; //!< size of this descriptor in bytes + uint8_t bDescriptorType; //!< INTERFACE descriptor type + uint8_t bFirstInterface; //!< Number of interface + uint8_t bInterfaceCount; //!< value to select alternate setting + uint8_t bFunctionClass; //!< Class code assigned by the USB + uint8_t bFunctionSubClass;//!< Sub-class code assigned by the USB + uint8_t bFunctionProtocol;//!< Protocol code assigned by the USB + uint8_t iFunction; //!< Index of string descriptor } usb_association_desc_t; - /** * \brief Standard USB configuration descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - le16_t wTotalLength; - uint8_t bNumInterfaces; - uint8_t bConfigurationValue; - uint8_t iConfiguration; - uint8_t bmAttributes; - uint8_t bMaxPower; + uint8_t bLength; + uint8_t bDescriptorType; + le16_t wTotalLength; + uint8_t bNumInterfaces; + uint8_t bConfigurationValue; + uint8_t iConfiguration; + uint8_t bmAttributes; + uint8_t bMaxPower; } usb_conf_desc_t; - #define USB_CONFIG_ATTR_MUST_SET (1 << 7) //!< Must always be set #define USB_CONFIG_ATTR_BUS_POWERED (0 << 6) //!< Bus-powered #define USB_CONFIG_ATTR_SELF_POWERED (1 << 6) //!< Self-powered @@ -438,55 +435,54 @@ typedef struct { * \brief Standard USB association descriptor structure */ typedef struct { - uint8_t bLength; //!< Size of this descriptor in bytes - uint8_t bDescriptorType; //!< Interface descriptor type - uint8_t bFirstInterface; //!< Number of interface - uint8_t bInterfaceCount; //!< value to select alternate setting - uint8_t bFunctionClass; //!< Class code assigned by the USB - uint8_t bFunctionSubClass; //!< Sub-class code assigned by the USB - uint8_t bFunctionProtocol; //!< Protocol code assigned by the USB - uint8_t iFunction; //!< Index of string descriptor + uint8_t bLength; //!< Size of this descriptor in bytes + uint8_t bDescriptorType; //!< Interface descriptor type + uint8_t bFirstInterface; //!< Number of interface + uint8_t bInterfaceCount; //!< value to select alternate setting + uint8_t bFunctionClass; //!< Class code assigned by the USB + uint8_t bFunctionSubClass; //!< Sub-class code assigned by the USB + uint8_t bFunctionProtocol; //!< Protocol code assigned by the USB + uint8_t iFunction; //!< Index of string descriptor } usb_iad_desc_t; /** * \brief Standard USB interface descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - uint8_t bInterfaceNumber; - uint8_t bAlternateSetting; - uint8_t bNumEndpoints; - uint8_t bInterfaceClass; - uint8_t bInterfaceSubClass; - uint8_t bInterfaceProtocol; - uint8_t iInterface; + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bInterfaceNumber; + uint8_t bAlternateSetting; + uint8_t bNumEndpoints; + uint8_t bInterfaceClass; + uint8_t bInterfaceSubClass; + uint8_t bInterfaceProtocol; + uint8_t iInterface; } usb_iface_desc_t; /** * \brief Standard USB endpoint descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; - uint8_t bEndpointAddress; - uint8_t bmAttributes; - le16_t wMaxPacketSize; - uint8_t bInterval; + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bEndpointAddress; + uint8_t bmAttributes; + le16_t wMaxPacketSize; + uint8_t bInterval; } usb_ep_desc_t; - /** * \brief A standard USB string descriptor structure */ typedef struct { - uint8_t bLength; - uint8_t bDescriptorType; + uint8_t bLength; + uint8_t bDescriptorType; } usb_str_desc_t; typedef struct { - usb_str_desc_t desc; - le16_t string[1]; + usb_str_desc_t desc; + le16_t string[1]; } usb_str_lgid_desc_t; COMPILER_PACK_RESET() diff --git a/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h b/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h index d594db52e3..769e7589bc 100644 --- a/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h +++ b/Marlin/src/HAL/DUE/usb/usb_protocol_cdc.h @@ -58,42 +58,42 @@ * \name Possible values of class */ //@{ -#define CDC_CLASS_DEVICE 0x02 //!< USB Communication Device Class -#define CDC_CLASS_COMM 0x02 //!< CDC Communication Class Interface -#define CDC_CLASS_DATA 0x0A //!< CDC Data Class Interface +#define CDC_CLASS_DEVICE 0x02 //!< USB Communication Device Class +#define CDC_CLASS_COMM 0x02 //!< CDC Communication Class Interface +#define CDC_CLASS_DATA 0x0A //!< CDC Data Class Interface #define CDC_CLASS_MULTI 0xEF //!< CDC Multi-interface Function //@} //! \name USB CDC Subclass IDs //@{ -#define CDC_SUBCLASS_DLCM 0x01 //!< Direct Line Control Model -#define CDC_SUBCLASS_ACM 0x02 //!< Abstract Control Model -#define CDC_SUBCLASS_TCM 0x03 //!< Telephone Control Model -#define CDC_SUBCLASS_MCCM 0x04 //!< Multi-Channel Control Model -#define CDC_SUBCLASS_CCM 0x05 //!< CAPI Control Model -#define CDC_SUBCLASS_ETH 0x06 //!< Ethernet Networking Control Model -#define CDC_SUBCLASS_ATM 0x07 //!< ATM Networking Control Model +#define CDC_SUBCLASS_DLCM 0x01 //!< Direct Line Control Model +#define CDC_SUBCLASS_ACM 0x02 //!< Abstract Control Model +#define CDC_SUBCLASS_TCM 0x03 //!< Telephone Control Model +#define CDC_SUBCLASS_MCCM 0x04 //!< Multi-Channel Control Model +#define CDC_SUBCLASS_CCM 0x05 //!< CAPI Control Model +#define CDC_SUBCLASS_ETH 0x06 //!< Ethernet Networking Control Model +#define CDC_SUBCLASS_ATM 0x07 //!< ATM Networking Control Model //@} //! \name USB CDC Communication Interface Protocol IDs //@{ -#define CDC_PROTOCOL_V25TER 0x01 //!< Common AT commands +#define CDC_PROTOCOL_V25TER 0x01 //!< Common AT commands //@} //! \name USB CDC Data Interface Protocol IDs //@{ -#define CDC_PROTOCOL_I430 0x30 //!< ISDN BRI -#define CDC_PROTOCOL_HDLC 0x31 //!< HDLC -#define CDC_PROTOCOL_TRANS 0x32 //!< Transparent -#define CDC_PROTOCOL_Q921M 0x50 //!< Q.921 management protocol -#define CDC_PROTOCOL_Q921 0x51 //!< Q.931 [sic] Data link protocol -#define CDC_PROTOCOL_Q921TM 0x52 //!< Q.921 TEI-multiplexor -#define CDC_PROTOCOL_V42BIS 0x90 //!< Data compression procedures -#define CDC_PROTOCOL_Q931 0x91 //!< Euro-ISDN protocol control -#define CDC_PROTOCOL_V120 0x92 //!< V.24 rate adaption to ISDN -#define CDC_PROTOCOL_CAPI20 0x93 //!< CAPI Commands -#define CDC_PROTOCOL_HOST 0xFD //!< Host based driver +#define CDC_PROTOCOL_I430 0x30 //!< ISDN BRI +#define CDC_PROTOCOL_HDLC 0x31 //!< HDLC +#define CDC_PROTOCOL_TRANS 0x32 //!< Transparent +#define CDC_PROTOCOL_Q921M 0x50 //!< Q.921 management protocol +#define CDC_PROTOCOL_Q921 0x51 //!< Q.931 [sic] Data link protocol +#define CDC_PROTOCOL_Q921TM 0x52 //!< Q.921 TEI-multiplexor +#define CDC_PROTOCOL_V42BIS 0x90 //!< Data compression procedures +#define CDC_PROTOCOL_Q931 0x91 //!< Euro-ISDN protocol control +#define CDC_PROTOCOL_V120 0x92 //!< V.24 rate adaption to ISDN +#define CDC_PROTOCOL_CAPI20 0x93 //!< CAPI Commands +#define CDC_PROTOCOL_HOST 0xFD //!< Host based driver /** * \brief Describes the Protocol Unit Functional Descriptors [sic] * on Communication Class Interface @@ -103,16 +103,16 @@ //! \name USB CDC Functional Descriptor Types //@{ -#define CDC_CS_INTERFACE 0x24 //!< Interface Functional Descriptor -#define CDC_CS_ENDPOINT 0x25 //!< Endpoint Functional Descriptor +#define CDC_CS_INTERFACE 0x24 //!< Interface Functional Descriptor +#define CDC_CS_ENDPOINT 0x25 //!< Endpoint Functional Descriptor //@} //! \name USB CDC Functional Descriptor Subtypes //@{ -#define CDC_SCS_HEADER 0x00 //!< Header Functional Descriptor -#define CDC_SCS_CALL_MGMT 0x01 //!< Call Management -#define CDC_SCS_ACM 0x02 //!< Abstract Control Management -#define CDC_SCS_UNION 0x06 //!< Union Functional Descriptor +#define CDC_SCS_HEADER 0x00 //!< Header Functional Descriptor +#define CDC_SCS_CALL_MGMT 0x01 //!< Call Management +#define CDC_SCS_ACM 0x02 //!< Abstract Control Management +#define CDC_SCS_UNION 0x06 //!< Union Functional Descriptor //@} //! \name USB CDC Request IDs @@ -168,42 +168,40 @@ COMPILER_PACK_SET(1) //! \name USB CDC Descriptors //@{ - //! CDC Header Functional Descriptor typedef struct { - uint8_t bFunctionLength; - uint8_t bDescriptorType; - uint8_t bDescriptorSubtype; - le16_t bcdCDC; + uint8_t bFunctionLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubtype; + le16_t bcdCDC; } usb_cdc_hdr_desc_t; //! CDC Call Management Functional Descriptor typedef struct { - uint8_t bFunctionLength; - uint8_t bDescriptorType; - uint8_t bDescriptorSubtype; - uint8_t bmCapabilities; - uint8_t bDataInterface; + uint8_t bFunctionLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubtype; + uint8_t bmCapabilities; + uint8_t bDataInterface; } usb_cdc_call_mgmt_desc_t; //! CDC ACM Functional Descriptor typedef struct { - uint8_t bFunctionLength; - uint8_t bDescriptorType; - uint8_t bDescriptorSubtype; - uint8_t bmCapabilities; + uint8_t bFunctionLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubtype; + uint8_t bmCapabilities; } usb_cdc_acm_desc_t; //! CDC Union Functional Descriptor typedef struct { - uint8_t bFunctionLength; - uint8_t bDescriptorType; - uint8_t bDescriptorSubtype; - uint8_t bMasterInterface; - uint8_t bSlaveInterface0; + uint8_t bFunctionLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubtype; + uint8_t bMasterInterface; + uint8_t bSlaveInterface0; } usb_cdc_union_desc_t; - //! \name USB CDC Call Management Capabilities //@{ //! Device handles call management itself @@ -235,24 +233,24 @@ typedef struct { //@{ //! Line Coding structure typedef struct { - le32_t dwDTERate; - uint8_t bCharFormat; - uint8_t bParityType; - uint8_t bDataBits; + le32_t dwDTERate; + uint8_t bCharFormat; + uint8_t bParityType; + uint8_t bDataBits; } usb_cdc_line_coding_t; //! Possible values of bCharFormat enum cdc_char_format { - CDC_STOP_BITS_1 = 0, //!< 1 stop bit - CDC_STOP_BITS_1_5 = 1, //!< 1.5 stop bits - CDC_STOP_BITS_2 = 2, //!< 2 stop bits + CDC_STOP_BITS_1 = 0, //!< 1 stop bit + CDC_STOP_BITS_1_5 = 1, //!< 1.5 stop bits + CDC_STOP_BITS_2 = 2, //!< 2 stop bits }; //! Possible values of bParityType enum cdc_parity { - CDC_PAR_NONE = 0, //!< No parity - CDC_PAR_ODD = 1, //!< Odd parity - CDC_PAR_EVEN = 2, //!< Even parity - CDC_PAR_MARK = 3, //!< Parity forced to 0 (space) - CDC_PAR_SPACE = 4, //!< Parity forced to 1 (mark) + CDC_PAR_NONE = 0, //!< No parity + CDC_PAR_ODD = 1, //!< Odd parity + CDC_PAR_EVEN = 2, //!< Even parity + CDC_PAR_MARK = 3, //!< Parity forced to 0 (space) + CDC_PAR_SPACE = 4, //!< Parity forced to 1 (mark) }; //@} @@ -262,7 +260,7 @@ enum cdc_parity { //! Control signal structure typedef struct { - uint16_t value; + uint16_t value; } usb_cdc_control_signal_t; //! \name Possible values in usb_cdc_control_signal_t @@ -278,16 +276,15 @@ typedef struct { //@} //@} - //! \name USB CDC notification message //@{ typedef struct { - uint8_t bmRequestType; - uint8_t bNotification; - le16_t wValue; - le16_t wIndex; - le16_t wLength; + uint8_t bmRequestType; + uint8_t bNotification; + le16_t wValue; + le16_t wIndex; + le16_t wLength; } usb_cdc_notify_msg_t; //! \name USB CDC serial state @@ -295,8 +292,8 @@ typedef struct { //! Hardware handshake support (cdc spec 1.1 chapter 6.3.5) typedef struct { - usb_cdc_notify_msg_t header; - le16_t value; + usb_cdc_notify_msg_t header; + le16_t value; } usb_cdc_notify_serial_state_t; //! \name Possible values in usb_cdc_notify_serial_state_t diff --git a/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h b/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h index e1e59237d8..227a13dc53 100644 --- a/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h +++ b/Marlin/src/HAL/DUE/usb/usb_protocol_msc.h @@ -47,7 +47,6 @@ #ifndef _USB_PROTOCOL_MSC_H_ #define _USB_PROTOCOL_MSC_H_ - /** * \ingroup usb_protocol_group * \defgroup usb_msc_protocol USB Mass Storage Class (MSC) protocol definitions @@ -59,7 +58,7 @@ * \name Possible Class value */ //@{ -#define MSC_CLASS 0x08 +#define MSC_CLASS 0x08 //@} /** @@ -71,12 +70,12 @@ * operating systems like Windows XP. */ //@{ -#define MSC_SUBCLASS_RBC 0x01 //!< Reduced Block Commands -#define MSC_SUBCLASS_ATAPI 0x02 //!< CD/DVD devices -#define MSC_SUBCLASS_QIC_157 0x03 //!< Tape devices -#define MSC_SUBCLASS_UFI 0x04 //!< Floppy disk drives -#define MSC_SUBCLASS_SFF_8070I 0x05 //!< Floppy disk drives -#define MSC_SUBCLASS_TRANSPARENT 0x06 //!< Determined by INQUIRY +#define MSC_SUBCLASS_RBC 0x01 //!< Reduced Block Commands +#define MSC_SUBCLASS_ATAPI 0x02 //!< CD/DVD devices +#define MSC_SUBCLASS_QIC_157 0x03 //!< Tape devices +#define MSC_SUBCLASS_UFI 0x04 //!< Floppy disk drives +#define MSC_SUBCLASS_SFF_8070I 0x05 //!< Floppy disk drives +#define MSC_SUBCLASS_TRANSPARENT 0x06 //!< Determined by INQUIRY //@} /** @@ -84,21 +83,19 @@ * \note Only the BULK protocol should be used in new designs. */ //@{ -#define MSC_PROTOCOL_CBI 0x00 //!< Command/Bulk/Interrupt -#define MSC_PROTOCOL_CBI_ALT 0x01 //!< W/o command completion -#define MSC_PROTOCOL_BULK 0x50 //!< Bulk-only +#define MSC_PROTOCOL_CBI 0x00 //!< Command/Bulk/Interrupt +#define MSC_PROTOCOL_CBI_ALT 0x01 //!< W/o command completion +#define MSC_PROTOCOL_BULK 0x50 //!< Bulk-only //@} - /** * \brief MSC USB requests (bRequest) */ enum usb_reqid_msc { - USB_REQ_MSC_BULK_RESET = 0xFF, //!< Mass Storage Reset - USB_REQ_MSC_GET_MAX_LUN = 0xFE //!< Get Max LUN + USB_REQ_MSC_BULK_RESET = 0xFF, //!< Mass Storage Reset + USB_REQ_MSC_GET_MAX_LUN = 0xFE //!< Get Max LUN }; - COMPILER_PACK_SET(1) /** @@ -106,38 +103,37 @@ COMPILER_PACK_SET(1) */ //@{ struct usb_msc_cbw { - le32_t dCBWSignature; //!< Must contain 'USBC' - le32_t dCBWTag; //!< Unique command ID - le32_t dCBWDataTransferLength; //!< Number of bytes to transfer - uint8_t bmCBWFlags; //!< Direction in bit 7 - uint8_t bCBWLUN; //!< Logical Unit Number - uint8_t bCBWCBLength; //!< Number of valid CDB bytes - uint8_t CDB[16]; //!< SCSI Command Descriptor Block + le32_t dCBWSignature; //!< Must contain 'USBC' + le32_t dCBWTag; //!< Unique command ID + le32_t dCBWDataTransferLength; //!< Number of bytes to transfer + uint8_t bmCBWFlags; //!< Direction in bit 7 + uint8_t bCBWLUN; //!< Logical Unit Number + uint8_t bCBWCBLength; //!< Number of valid CDB bytes + uint8_t CDB[16]; //!< SCSI Command Descriptor Block }; -#define USB_CBW_SIGNATURE 0x55534243 //!< dCBWSignature value -#define USB_CBW_DIRECTION_IN (1<<7) //!< Data from device to host -#define USB_CBW_DIRECTION_OUT (0<<7) //!< Data from host to device -#define USB_CBW_LUN_MASK 0x0F //!< Valid bits in bCBWLUN -#define USB_CBW_LEN_MASK 0x1F //!< Valid bits in bCBWCBLength +#define USB_CBW_SIGNATURE 0x55534243 //!< dCBWSignature value +#define USB_CBW_DIRECTION_IN (1<<7) //!< Data from device to host +#define USB_CBW_DIRECTION_OUT (0<<7) //!< Data from host to device +#define USB_CBW_LUN_MASK 0x0F //!< Valid bits in bCBWLUN +#define USB_CBW_LEN_MASK 0x1F //!< Valid bits in bCBWCBLength //@} - /** * \name A Command Status Wrapper (CSW). */ //@{ struct usb_msc_csw { - le32_t dCSWSignature; //!< Must contain 'USBS' - le32_t dCSWTag; //!< Same as dCBWTag - le32_t dCSWDataResidue; //!< Number of bytes not transferred - uint8_t bCSWStatus; //!< Status code + le32_t dCSWSignature; //!< Must contain 'USBS' + le32_t dCSWTag; //!< Same as dCBWTag + le32_t dCSWDataResidue; //!< Number of bytes not transferred + uint8_t bCSWStatus; //!< Status code }; -#define USB_CSW_SIGNATURE 0x55534253 //!< dCSWSignature value -#define USB_CSW_STATUS_PASS 0x00 //!< Command Passed -#define USB_CSW_STATUS_FAIL 0x01 //!< Command Failed -#define USB_CSW_STATUS_PE 0x02 //!< Phase Error +#define USB_CSW_SIGNATURE 0x55534253 //!< dCSWSignature value +#define USB_CSW_STATUS_PASS 0x00 //!< Command Passed +#define USB_CSW_STATUS_FAIL 0x01 //!< Command Failed +#define USB_CSW_STATUS_PE 0x02 //!< Phase Error //@} COMPILER_PACK_RESET() diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index 5dc9b2cfe2..5ec47322c6 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 diff --git a/Marlin/src/HAL/ESP32/HAL_SPI.cpp b/Marlin/src/HAL/ESP32/HAL_SPI.cpp index 6dc540864e..e5302bb905 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/ESP32/ota.cpp b/Marlin/src/HAL/ESP32/ota.cpp index 99516bfc6e..d70611f189 100644 --- a/Marlin/src/HAL/ESP32/ota.cpp +++ b/Marlin/src/HAL/ESP32/ota.cpp @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 diff --git a/Marlin/src/HAL/ESP32/ota.h b/Marlin/src/HAL/ESP32/ota.h index 546ace82db..a91d04dbb7 100644 --- a/Marlin/src/HAL/ESP32/ota.h +++ b/Marlin/src/HAL/ESP32/ota.h @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 diff --git a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp index 7dbfa81262..d264555720 100644 --- a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp +++ b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp @@ -41,7 +41,6 @@ static SPISettings spiConfig; - #ifndef LCD_SPI_SPEED #ifdef SD_SPI_SPEED #define LCD_SPI_SPEED SD_SPI_SPEED // Assume SPI speed shared with SD @@ -101,6 +100,6 @@ uint8_t u8g_eps_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt return 1; } -#endif // ANY(MKS_MINI_12864, FYSETC_MINI_12864_2_1) +#endif // MKS_MINI_12864 || FYSETC_MINI_12864_2_1 #endif // ARDUINO_ARCH_ESP32 diff --git a/Marlin/src/HAL/LINUX/HAL.cpp b/Marlin/src/HAL/LINUX/HAL.cpp index db43f42eaa..b7a89e3c5f 100644 --- a/Marlin/src/HAL/LINUX/HAL.cpp +++ b/Marlin/src/HAL/LINUX/HAL.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ + #ifdef __PLAT_LINUX__ #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index 22c3e521f0..d928a2f597 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/LINUX/servo_private.h b/Marlin/src/HAL/LINUX/servo_private.h index bcc8d2037f..11e1c2b93c 100644 --- a/Marlin/src/HAL/LINUX/servo_private.h +++ b/Marlin/src/HAL/LINUX/servo_private.h @@ -60,7 +60,6 @@ #define INVALID_SERVO 255 // flag indicating an invalid servo index - // Types typedef struct { diff --git a/Marlin/src/HAL/LINUX/timers.cpp b/Marlin/src/HAL/LINUX/timers.cpp index 66d80f2518..a8ab403197 100644 --- a/Marlin/src/HAL/LINUX/timers.cpp +++ b/Marlin/src/HAL/LINUX/timers.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h index 2d2a95774c..2b29edce0b 100644 --- a/Marlin/src/HAL/LINUX/timers.h +++ b/Marlin/src/HAL/LINUX/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index b0eeb983b4..869b77c6bc 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp index 4d6cb55cff..6ce7f75552 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp @@ -318,7 +318,7 @@ void SPIClass::dmaSend(void *buf, uint16_t length, bool minc) { // Enable DMA GPDMA_ChannelCmd(0, ENABLE); - /* + /** * Observed behaviour on normal data transfer completion (SKR 1.3 board / LPC1768 MCU) * GPDMA_STAT_INTTC flag is SET * GPDMA_STAT_INTERR flag is NOT SET diff --git a/Marlin/src/HAL/LPC1768/MinSerial.cpp b/Marlin/src/HAL/LPC1768/MinSerial.cpp index 7a1c038c0b..368bcb5259 100644 --- a/Marlin/src/HAL/LPC1768/MinSerial.cpp +++ b/Marlin/src/HAL/LPC1768/MinSerial.cpp @@ -33,18 +33,18 @@ static void TX(char c) { _DBC(c); } void install_min_serial() { HAL_min_serial_out = &TX; } #if DISABLED(DYNAMIC_VECTORTABLE) -extern "C" { - __attribute__((naked)) void JumpHandler_ASM() { - __asm__ __volatile__ ( - "b CommonHandler_ASM\n" - ); + extern "C" { + __attribute__((naked)) void JumpHandler_ASM() { + __asm__ __volatile__ ( + "b CommonHandler_ASM\n" + ); + } + void __attribute__((naked, alias("JumpHandler_ASM"))) HardFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) BusFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) UsageFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) MemManage_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"))) NMI_Handler(); } - void __attribute__((naked, alias("JumpHandler_ASM"))) HardFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) BusFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) UsageFault_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) MemManage_Handler(); - void __attribute__((naked, alias("JumpHandler_ASM"))) NMI_Handler(); -} #endif #endif // POSTMORTEM_DEBUGGING diff --git a/Marlin/src/HAL/LPC1768/timers.cpp b/Marlin/src/HAL/LPC1768/timers.cpp index bbb13f81da..b541ab6e6a 100644 --- a/Marlin/src/HAL/LPC1768/timers.cpp +++ b/Marlin/src/HAL/LPC1768/timers.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index c6d7bc632e..bae01703ed 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 diff --git a/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h b/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h index d2260037b6..fb7fdcb869 100644 --- a/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h +++ b/Marlin/src/HAL/LPC1768/u8g/LCD_defines.h @@ -34,7 +34,6 @@ uint8_t u8g_com_HAL_LPC1768_ST7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t ar uint8_t u8g_com_HAL_LPC1768_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); uint8_t u8g_com_HAL_LPC1768_ssd_hw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); - // connect U8g com generic com names to the desired driver #define U8G_COM_HW_SPI u8g_com_HAL_LPC1768_hw_spi_fn // use LPC1768 specific hardware SPI routine #define U8G_COM_SW_SPI u8g_com_HAL_LPC1768_sw_spi_fn // use LPC1768 specific software SPI routine diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp index 0118f92847..406fc4840c 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp @@ -125,5 +125,4 @@ uint8_t u8g_com_HAL_LPC1768_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, } #endif // HAS_MARLINUI_U8GLIB - #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp index bf76eaf0f4..3dea365ac7 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_ssd_hw_i2c.cpp @@ -194,5 +194,4 @@ uint8_t u8g_com_HAL_LPC1768_ssd_hw_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_v } #endif // HAS_MARLINUI_U8GLIB - #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp index ce7b338019..c029dc0680 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp @@ -134,5 +134,4 @@ uint8_t u8g_com_HAL_LPC1768_ST7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t ar } #endif // HAS_MARLINUI_U8GLIB - #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp index c56533bb7e..f6ed7b0e7e 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp @@ -160,10 +160,10 @@ uint8_t u8g_com_HAL_LPC1768_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, break; case U8G_COM_MSG_CHIP_SELECT: - #if ANY(FYSETC_MINI_12864, MKS_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 - if (arg_val) { // SCK idle state needs to be set to the proper idle state before - // the next chip select goes active - u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active + #if ANY(FYSETC_MINI_12864, MKS_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 + if (arg_val) { // SCK idle state needs to be set to the proper idle state before + // the next chip select goes active + u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active u8g_SetPILevel(u8g, U8G_PI_CS, LOW); } else { diff --git a/Marlin/src/HAL/LPC1768/win_usb_driver/lpc176x_usb_driver.inf b/Marlin/src/HAL/LPC1768/win_usb_driver/lpc176x_usb_driver.inf index 4732eb8552..37d9a617db 100644 --- a/Marlin/src/HAL/LPC1768/win_usb_driver/lpc176x_usb_driver.inf +++ b/Marlin/src/HAL/LPC1768/win_usb_driver/lpc176x_usb_driver.inf @@ -8,14 +8,12 @@ DriverVer =04/14/2008, 5.1.2600.5512 [Manufacturer] %PROVIDER%=DeviceList,ntamd64 - [DeviceList] %DESCRIPTION%=LPC1768USB, USB\VID_1D50&PID_6029&MI_00 [DeviceList.ntamd64] %DESCRIPTION%=LPC1768USB, USB\VID_1D50&PID_6029&MI_00 - [LPC1768USB] include=mdmcpq.inf CopyFiles=FakeModemCopyFileSection @@ -28,9 +26,8 @@ AddService=usbser, 0x00000002, LowerFilter_Service_Inst [SerialPropPageAddReg] HKR,,EnumPropPages32,,"MsPorts.dll,SerialPortPropPageProvider" - [Strings] PROVIDER = "marlinfw.org" DRIVER.SVC = "Marlin USB Driver" DESCRIPTION= "Marlin USB Serial" -COMPOSITE = "Marlin USB VCOM" \ No newline at end of file +COMPOSITE = "Marlin USB VCOM" diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index 52e5eb4f39..b57bfa363c 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h b/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h index b5cc6f02a4..0c447ba4cb 100644 --- a/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h +++ b/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h index af9a651c79..24aec63758 100644 --- a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h +++ b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/NATIVE_SIM/servo_private.h b/Marlin/src/HAL/NATIVE_SIM/servo_private.h index 06be1893f6..e0eb30ab28 100644 --- a/Marlin/src/HAL/NATIVE_SIM/servo_private.h +++ b/Marlin/src/HAL/NATIVE_SIM/servo_private.h @@ -61,7 +61,6 @@ #define INVALID_SERVO 255 // flag indicating an invalid servo index - // Types typedef struct { diff --git a/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h b/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h index b3e622f19a..2ae443c386 100644 --- a/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h +++ b/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h @@ -31,10 +31,10 @@ #endif #define DATASIZE_8BIT 8 -#define DATASIZE_16BIT 16 -#define TFT_IO_DRIVER TFT_SPI +#define DATASIZE_16BIT 16 +#define TFT_IO_DRIVER TFT_SPI -#define DMA_MINC_ENABLE 1 +#define DMA_MINC_ENABLE 1 #define DMA_MINC_DISABLE 0 class TFT_SPI { diff --git a/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h b/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h index 4e999f88ff..8bf059f59c 100644 --- a/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h +++ b/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h index be38d583b6..d46e8e7b94 100644 --- a/Marlin/src/HAL/NATIVE_SIM/timers.h +++ b/Marlin/src/HAL/NATIVE_SIM/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * + * 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 diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h index 2a50eddcd4..05d5526b63 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_defines.h @@ -21,6 +21,10 @@ */ #pragma once +/** + * Native/Simulator LCD-specific defines + */ + void usleep(uint64_t microsec); // The following are optional depending on the platform. diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h index c27c84e8c3..39af4d7e68 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/LCD_pin_routines.h @@ -31,7 +31,6 @@ * resulted in using about about 25% of the CPU's time. */ - #ifdef __cplusplus extern "C" { #endif diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp index a3254774bf..46f2798afa 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_st7920_sw_spi.cpp @@ -100,6 +100,7 @@ static void u8g_com_st7920_write_byte_sw_spi(uint8_t rs, uint8_t val) { swSpiTransfer(val & 0x0F0, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL); swSpiTransfer(val << 4, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL); } + #ifdef __cplusplus extern "C" { #endif @@ -128,7 +129,7 @@ uint8_t u8g_com_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void break; case U8G_COM_MSG_RESET: - if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val); + if (U8G_PIN_NONE != u8g->pin_list[U8G_PI_RESET]) u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val); break; case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ @@ -163,6 +164,7 @@ uint8_t u8g_com_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void } return 1; } + #ifdef __cplusplus } #endif diff --git a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp index 505ccd7d9c..9184e2f618 100644 --- a/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp +++ b/Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp @@ -159,10 +159,10 @@ uint8_t u8g_com_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt break; case U8G_COM_MSG_CHIP_SELECT: - #if ANY(FYSETC_MINI_12864, MKS_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 - if (arg_val) { // SCK idle state needs to be set to the proper idle state before - // the next chip select goes active - u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active + #if ANY(FYSETC_MINI_12864, MKS_MINI_12864) // LCD SPI is running mode 3 while SD card is running mode 0 + if (arg_val) { // SCK idle state needs to be set to the proper idle state before + // the next chip select goes active + u8g_SetPILevel(u8g, U8G_PI_SCK, 1); // Set SCK to mode 3 idle state before CS goes active u8g_SetPILevel(u8g, U8G_PI_CS, LOW); } else { diff --git a/Marlin/src/HAL/SAMD21/HAL.cpp b/Marlin/src/HAL/SAMD21/HAL.cpp index 1bc0406ab3..3656d97190 100644 --- a/Marlin/src/HAL/SAMD21/HAL.cpp +++ b/Marlin/src/HAL/SAMD21/HAL.cpp @@ -40,8 +40,6 @@ DefaultSerial3 MSerial2(false, Serial2); #endif - - #define WDT_CONFIG_PER_7_Val 0x9u #define WDT_CONFIG_PER_Pos 0 #define WDT_CONFIG_PER_7 (WDT_CONFIG_PER_7_Val << WDT_CONFIG_PER_Pos) @@ -165,7 +163,6 @@ void MarlinHAL::adc_init() { ADC->REFCTRL.reg = ADC_REFCTRL_REFSEL_INTVCC1; ADC->AVGCTRL.reg = ADC_AVGCTRL_SAMPLENUM_32| ADC_AVGCTRL_ADJRES(4);; - ADC->CTRLB.reg = ADC_CTRLB_PRESCALER_DIV128 | ADC_CTRLB_RESSEL_16BIT | ADC_CTRLB_FREERUN; diff --git a/Marlin/src/HAL/SAMD21/HAL.h b/Marlin/src/HAL/SAMD21/HAL.h index 1854e523ed..40be6c2420 100644 --- a/Marlin/src/HAL/SAMD21/HAL.h +++ b/Marlin/src/HAL/SAMD21/HAL.h @@ -47,7 +47,6 @@ typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3; extern DefaultSerial2 MSerial0; extern DefaultSerial3 MSerial1; - #define __MSERIAL(X) MSerial##X #define _MSERIAL(X) __MSERIAL(X) #define MSERIAL(X) _MSERIAL(INCREMENT(X)) diff --git a/Marlin/src/HAL/SAMD21/SAMD21.h b/Marlin/src/HAL/SAMD21/SAMD21.h index 8e9d17fc50..b64c5ce725 100644 --- a/Marlin/src/HAL/SAMD21/SAMD21.h +++ b/Marlin/src/HAL/SAMD21/SAMD21.h @@ -57,8 +57,6 @@ : (P == 3 && WITHIN(B, 20, 21)) ? 10 + (B) - 20 \ : -1) - - #define A2_AIN 3 #define A3_AIN 4 #define A4_AIN 5 diff --git a/Marlin/src/HAL/SAMD21/Servo.cpp b/Marlin/src/HAL/SAMD21/Servo.cpp index 38b995fc9a..704d0a2904 100644 --- a/Marlin/src/HAL/SAMD21/Servo.cpp +++ b/Marlin/src/HAL/SAMD21/Servo.cpp @@ -55,7 +55,6 @@ #define TIMER_TCCHANNEL(t) ((t) & 1) #define TC_COUNTER_START_VAL 0xFFFF - static volatile int8_t currentServoIndex[_Nbr_16timers]; // index for the servo being pulsed for each timer (or -1 if refresh interval) FORCE_INLINE static uint16_t getTimerCount() { diff --git a/Marlin/src/HAL/SAMD21/eeprom_flash.cpp b/Marlin/src/HAL/SAMD21/eeprom_flash.cpp index 4a4e328d1a..8d8d8a00c3 100644 --- a/Marlin/src/HAL/SAMD21/eeprom_flash.cpp +++ b/Marlin/src/HAL/SAMD21/eeprom_flash.cpp @@ -99,8 +99,7 @@ bool PersistentStore::access_finish() { volatile uint32_t *dst_addr = (volatile uint32_t *) &flashdata; uint32_t *pointer = (uint32_t *) buffer; - for (uint32_t i = 0; i < TOTAL_FLASH_SIZE; i+=4) { - + for (uint32_t i = 0; i < TOTAL_FLASH_SIZE; i += 4) { *dst_addr = (uint32_t) *pointer; pointer++; dst_addr ++; @@ -120,7 +119,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui if (!hasWritten) { // init temp buffer buffer = (uint8_t *) malloc(MARLIN_EEPROM_SIZE); - hasWritten=true; + hasWritten = true; } memcpy(buffer+pos,value,size); @@ -132,7 +131,7 @@ bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t volatile uint8_t *dst_addr = (volatile uint8_t *) &flashdata; dst_addr += pos; - memcpy(value,(const void *) dst_addr,size); + memcpy(value, (const void *)dst_addr, size); pos += size; return false; } diff --git a/Marlin/src/HAL/SAMD21/fastio.h b/Marlin/src/HAL/SAMD21/fastio.h index df907ff7ec..471e8b62ab 100644 --- a/Marlin/src/HAL/SAMD21/fastio.h +++ b/Marlin/src/HAL/SAMD21/fastio.h @@ -129,7 +129,7 @@ * Added as necessary or if I feel like it- not a comprehensive list! */ -/* +/** * Some of these share the same source and so can't be used in the same time */ #define PWM_PIN(P) (WITHIN(P, 2, 13) || WITHIN(P, 22, 23) || WITHIN(P, 44, 45) || P == 48) diff --git a/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h b/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h index 9d58e45432..570baf7e95 100644 --- a/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h @@ -19,5 +19,4 @@ * along with this program. If not, see . * */ - #pragma once diff --git a/Marlin/src/HAL/SAMD21/timers.cpp b/Marlin/src/HAL/SAMD21/timers.cpp index 982eebc549..b5f1d4f7bd 100644 --- a/Marlin/src/HAL/SAMD21/timers.cpp +++ b/Marlin/src/HAL/SAMD21/timers.cpp @@ -135,7 +135,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { } else if (timer_config[timer_num].type==TimerType::tcc) { - + Tcc * const tc = timer_config[timer_num].pTcc; PM->APBCMASK.reg |= PM_APBCMASK_TCC0; diff --git a/Marlin/src/HAL/SAMD51/Servo.cpp b/Marlin/src/HAL/SAMD51/Servo.cpp index e533eee301..059955e11a 100644 --- a/Marlin/src/HAL/SAMD51/Servo.cpp +++ b/Marlin/src/HAL/SAMD51/Servo.cpp @@ -54,7 +54,6 @@ #define TIMER_TCCHANNEL(t) ((t) & 1) #define TC_COUNTER_START_VAL 0xFFFF - static volatile int8_t currentServoIndex[_Nbr_16timers]; // index for the servo being pulsed for each timer (or -1 if refresh interval) FORCE_INLINE static uint16_t getTimerCount() { diff --git a/Marlin/src/HAL/SAMD51/fastio.h b/Marlin/src/HAL/SAMD51/fastio.h index 0acf481317..3d43bdb24d 100644 --- a/Marlin/src/HAL/SAMD51/fastio.h +++ b/Marlin/src/HAL/SAMD51/fastio.h @@ -130,7 +130,7 @@ #ifdef ADAFRUIT_GRAND_CENTRAL_M4 - /* + /** * Adafruit Grand Central M4 has a lot of PWMs the availables are listed here. * Some of these share the same source and so can't be used in the same time */ @@ -176,7 +176,7 @@ #define digitalPinToAnalogInput(P) (WITHIN(P, 67, 74) ? (P) - 67 : WITHIN(P, 54, 61) ? 8 + (P) - 54 : WITHIN(P, 12, 13) ? 16 + (P) - 12 : P == 9 ? 18 : -1) - /* + /** * pins */ diff --git a/Marlin/src/HAL/SAMD51/spi_pins.h b/Marlin/src/HAL/SAMD51/spi_pins.h index f1e4fd4302..2c7cbeb994 100644 --- a/Marlin/src/HAL/SAMD51/spi_pins.h +++ b/Marlin/src/HAL/SAMD51/spi_pins.h @@ -27,7 +27,7 @@ #ifdef ADAFRUIT_GRAND_CENTRAL_M4 - /* + /** * AGCM4 Default SPI Pins * * SS SCK MISO MOSI diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index d8a12aad7e..5b12c7a90d 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2017 Victor Perez + * + * 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 diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index 61569c7937..bf07b4e6db 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2017 Victor Perez + * + * 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 diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index 278d209c47..cc035ecffa 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32/MinSerial.cpp b/Marlin/src/HAL/STM32/MinSerial.cpp index b0fcff20c1..cda91a331e 100644 --- a/Marlin/src/HAL/STM32/MinSerial.cpp +++ b/Marlin/src/HAL/STM32/MinSerial.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32/Servo.cpp b/Marlin/src/HAL/STM32/Servo.cpp index a00186e0e7..4f026ffc6d 100644 --- a/Marlin/src/HAL/STM32/Servo.cpp +++ b/Marlin/src/HAL/STM32/Servo.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32/Servo.h b/Marlin/src/HAL/STM32/Servo.h index 1527e753b6..95ecb5d977 100644 --- a/Marlin/src/HAL/STM32/Servo.h +++ b/Marlin/src/HAL/STM32/Servo.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 6bd519877d..69511c6de4 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/STM32/eeprom_sram.cpp b/Marlin/src/HAL/STM32/eeprom_sram.cpp index 687e7f55c2..9bd84ff4fe 100644 --- a/Marlin/src/HAL/STM32/eeprom_sram.cpp +++ b/Marlin/src/HAL/STM32/eeprom_sram.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/STM32/eeprom_wired.cpp b/Marlin/src/HAL/STM32/eeprom_wired.cpp index cf0468151e..6fb9d9b51b 100644 --- a/Marlin/src/HAL/STM32/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32/eeprom_wired.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/STM32/endstop_interrupts.h b/Marlin/src/HAL/STM32/endstop_interrupts.h index d2f20ba1c7..b2693db1dd 100644 --- a/Marlin/src/HAL/STM32/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32/endstop_interrupts.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32/fastio.cpp b/Marlin/src/HAL/STM32/fastio.cpp index a4b3ba70c9..f8501545a0 100644 --- a/Marlin/src/HAL/STM32/fastio.cpp +++ b/Marlin/src/HAL/STM32/fastio.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32/fastio.h b/Marlin/src/HAL/STM32/fastio.h index 4a48954471..af2941c49c 100644 --- a/Marlin/src/HAL/STM32/fastio.h +++ b/Marlin/src/HAL/STM32/fastio.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32/inc/SanityCheck.h b/Marlin/src/HAL/STM32/inc/SanityCheck.h index 9b0c232bdf..deb16ef71e 100644 --- a/Marlin/src/HAL/STM32/inc/SanityCheck.h +++ b/Marlin/src/HAL/STM32/inc/SanityCheck.h @@ -28,7 +28,6 @@ // #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector" //#endif - #if ENABLED(SDCARD_EEPROM_EMULATION) && !HAS_MEDIA #undef SDCARD_EEPROM_EMULATION // Avoid additional error noise #if USE_FALLBACK_EEPROM diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp index a40bec9d64..be889d4fd3 100644 --- a/Marlin/src/HAL/STM32/msc_sd.cpp +++ b/Marlin/src/HAL/STM32/msc_sd.cpp @@ -1,14 +1,21 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * + * 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 . * diff --git a/Marlin/src/HAL/STM32/msc_sd.h b/Marlin/src/HAL/STM32/msc_sd.h index a8e5349f7c..20e738223c 100644 --- a/Marlin/src/HAL/STM32/msc_sd.h +++ b/Marlin/src/HAL/STM32/msc_sd.h @@ -1,14 +1,21 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * + * 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 . * diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp index 5e79f156d2..b0eb8d7288 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_spi.cpp @@ -245,7 +245,6 @@ void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Coun TERN_(TFT_SHARED_SPI, while (isBusy())); } - void TFT_SPI::Transmit(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { DMAtx.Init.MemInc = MemoryIncrease; HAL_DMA_Init(&DMAtx); diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index f176c7d8e3..10e0dc43a4 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 @@ -292,9 +292,9 @@ static constexpr int get_timer_num_from_base_address(uintptr_t base_address) { // constexpr doesn't like using the base address pointers that timers evaluate to. // We can get away with casting them to uintptr_t, if we do so inside an array. // GCC will not currently do it directly to a uintptr_t. -IF_ENABLED(HAS_TMC_SW_SERIAL, static constexpr uintptr_t timer_serial[] = {uintptr_t(TIMER_SERIAL)}); -IF_ENABLED(SPEAKER, static constexpr uintptr_t timer_tone[] = {uintptr_t(TIMER_TONE)}); -IF_ENABLED(HAS_SERVOS, static constexpr uintptr_t timer_servo[] = {uintptr_t(TIMER_SERVO)}); +TERN_(HAS_TMC_SW_SERIAL, static constexpr uintptr_t timer_serial[] = {uintptr_t(TIMER_SERIAL)}); +TERN_(SPEAKER, static constexpr uintptr_t timer_tone[] = {uintptr_t(TIMER_TONE)}); +TERN_(HAS_SERVOS, static constexpr uintptr_t timer_servo[] = {uintptr_t(TIMER_SERVO)}); enum TimerPurpose { TP_SERIAL, TP_TONE, TP_SERVO, TP_STEP, TP_TEMP }; diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 6828998198..180e240314 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2017 Victor Perez + * + * 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 diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index e8e958478f..be2c933413 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2017 Victor Perez + * + * 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 diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 80002e8807..0865bc34cf 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2017 Victor Perez + * + * 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 diff --git a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp index abb348d743..b5b57536f3 100644 --- a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp index 9e1e07c724..7186ffcb12 100644 --- a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp +++ b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp @@ -75,7 +75,7 @@ static inline __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb } // Not every MarlinSerial port should handle emergency parsing. -// It would not make sense to parse GCode from TMC responses, for example. +// It would not make sense to parse G-Code from TMC responses, for example. constexpr bool serial_handles_emergency(int port) { return false #ifdef SERIAL_PORT diff --git a/Marlin/src/HAL/STM32F1/MinSerial.cpp b/Marlin/src/HAL/STM32F1/MinSerial.cpp index 6cf68d8d8f..8fb9133254 100644 --- a/Marlin/src/HAL/STM32F1/MinSerial.cpp +++ b/Marlin/src/HAL/STM32F1/MinSerial.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32F1/SPI.cpp b/Marlin/src/HAL/STM32F1/SPI.cpp index a180684757..ab111ddbf0 100644 --- a/Marlin/src/HAL/STM32F1/SPI.cpp +++ b/Marlin/src/HAL/STM32F1/SPI.cpp @@ -517,7 +517,6 @@ uint8_t SPIClass::dmaSendAsync(const void * transmitBuf, uint16_t length, bool m return b; } - /** * New functions added to manage callbacks. * Victor Perez 2017 diff --git a/Marlin/src/HAL/STM32F1/SPI.h b/Marlin/src/HAL/STM32F1/SPI.h index 0941fa55b7..27bf684388 100644 --- a/Marlin/src/HAL/STM32F1/SPI.h +++ b/Marlin/src/HAL/STM32F1/SPI.h @@ -58,7 +58,7 @@ #define SPI_CLOCK_DIV128 SPI_BAUD_PCLK_DIV_128 #define SPI_CLOCK_DIV256 SPI_BAUD_PCLK_DIV_256 -/* +/** * Roger Clark. 20150106 * Commented out redundant AVR defined * @@ -153,7 +153,7 @@ private: friend class SPIClass; }; -/* +/** * Kept for compat. */ static const uint8_t ff = 0xFF; @@ -233,7 +233,7 @@ public: void onReceive(void(*)()); void onTransmit(void(*)()); - /* + /** * I/O */ @@ -314,7 +314,7 @@ public: uint8_t dmaSendRepeat(uint16_t length); uint8_t dmaSendAsync(const void * transmitBuf, uint16_t length, bool minc = 1); - /* + /** * Pin accessors */ @@ -398,7 +398,7 @@ private: void updateSettings(); - /* + /** * Functions added for DMA transfers with Callback. * Experimental. */ diff --git a/Marlin/src/HAL/STM32F1/Servo.cpp b/Marlin/src/HAL/STM32F1/Servo.cpp index 47ffb631cf..7aa8fe3d00 100644 --- a/Marlin/src/HAL/STM32F1/Servo.cpp +++ b/Marlin/src/HAL/STM32F1/Servo.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32F1/Servo.h b/Marlin/src/HAL/STM32F1/Servo.h index 745a1c93f0..ffafc23833 100644 --- a/Marlin/src/HAL/STM32F1/Servo.h +++ b/Marlin/src/HAL/STM32F1/Servo.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32F1/eeprom_flash.cpp b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp index e7d9dd29e2..48fb2d286c 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/STM32F1/endstop_interrupts.h b/Marlin/src/HAL/STM32F1/endstop_interrupts.h index a1ef8a8c3a..3703ddd82b 100644 --- a/Marlin/src/HAL/STM32F1/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32F1/endstop_interrupts.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32F1/fastio.h b/Marlin/src/HAL/STM32F1/fastio.h index e75254d692..5b3ebaa52c 100644 --- a/Marlin/src/HAL/STM32F1/fastio.h +++ b/Marlin/src/HAL/STM32F1/fastio.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32F1/maple_win_usb_driver/maple_serial.inf b/Marlin/src/HAL/STM32F1/maple_win_usb_driver/maple_serial.inf index c39f4ce0ed..0df30d2c42 100644 --- a/Marlin/src/HAL/STM32F1/maple_win_usb_driver/maple_serial.inf +++ b/Marlin/src/HAL/STM32F1/maple_win_usb_driver/maple_serial.inf @@ -48,7 +48,6 @@ ServiceBinary=%12%\usbser.sys ; String Definitions ;------------------------------------------------------------------------------ - [Strings] STM = "LeafLabs" MFGNAME = "LeafLabs" diff --git a/Marlin/src/HAL/STM32F1/msc_sd.cpp b/Marlin/src/HAL/STM32F1/msc_sd.cpp index f490c83ed8..067b46eb8b 100644 --- a/Marlin/src/HAL/STM32F1/msc_sd.cpp +++ b/Marlin/src/HAL/STM32F1/msc_sd.cpp @@ -1,14 +1,21 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * + * 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 . * diff --git a/Marlin/src/HAL/STM32F1/msc_sd.h b/Marlin/src/HAL/STM32F1/msc_sd.h index f4636bdff7..371211efc6 100644 --- a/Marlin/src/HAL/STM32F1/msc_sd.h +++ b/Marlin/src/HAL/STM32F1/msc_sd.h @@ -1,14 +1,21 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * + * 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 . * diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.h b/Marlin/src/HAL/STM32F1/onboard_sd.h index f8846e95bc..be1d1d0a6b 100644 --- a/Marlin/src/HAL/STM32F1/onboard_sd.h +++ b/Marlin/src/HAL/STM32F1/onboard_sd.h @@ -47,7 +47,6 @@ typedef enum { RES_PARERR /* 4: Invalid Parameter */ } DRESULT; - #if _DISKIO_ISDIO /* Command structure for iSDIO ioctl command */ typedef struct { diff --git a/Marlin/src/HAL/STM32F1/sdio.cpp b/Marlin/src/HAL/STM32F1/sdio.cpp index 95184c3935..a805995941 100644 --- a/Marlin/src/HAL/STM32F1/sdio.cpp +++ b/Marlin/src/HAL/STM32F1/sdio.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32F1/sdio.h b/Marlin/src/HAL/STM32F1/sdio.h index 8777299f01..08c884666d 100644 --- a/Marlin/src/HAL/STM32F1/sdio.h +++ b/Marlin/src/HAL/STM32F1/sdio.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2017 Victor Perez + * + * 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 @@ -60,7 +60,6 @@ #define ACMD41_SD_APP_OP_COND (uint16_t)(SDMMC_ACMD_SD_APP_OP_COND | SDIO_CMD_WAIT_SHORT_RESP) #define ACMD42_SD_APP_SET_CLR_CARD_DETECT (uint16_t)(SDMMC_ACMD_SD_APP_SET_CLR_CARD_DETECT | SDIO_CMD_WAIT_SHORT_RESP) - #define SDMMC_ALLZERO 0x00000000U #define SDMMC_OCR_ERRORBITS 0xFDFFE008U diff --git a/Marlin/src/HAL/STM32F1/timers.cpp b/Marlin/src/HAL/STM32F1/timers.cpp index 112c730b9a..12477a4583 100644 --- a/Marlin/src/HAL/STM32F1/timers.cpp +++ b/Marlin/src/HAL/STM32F1/timers.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index 557522f336..f92c32c2a3 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2017 Victor Perez + * + * 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 diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index a7aa9f0da2..c6f97fe5f2 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp index 415c692229..cda7e7d16c 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp @@ -120,7 +120,6 @@ void spiSendBlock(uint8_t token, const uint8_t *buf) { SPI.endTransaction(); } - // Begin SPI transaction, set clock, bit order, data mode void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { spiConfig = SPISettings(spiClock, bitOrder, dataMode); diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 2a192e4718..bc1d31745f 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp index b80e93b536..a2afa45343 100644 --- a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 8af79d7392..3536b62265 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index c54a2e8a0b..f5fef26099 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/TEENSY40_41/eeprom.cpp b/Marlin/src/HAL/TEENSY40_41/eeprom.cpp index 3cd376edce..87f7dd3cfc 100644 --- a/Marlin/src/HAL/TEENSY40_41/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY40_41/eeprom.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/TEENSY40_41/fastio.h b/Marlin/src/HAL/TEENSY40_41/fastio.h index 52f991dfb8..179f044c9b 100644 --- a/Marlin/src/HAL/TEENSY40_41/fastio.h +++ b/Marlin/src/HAL/TEENSY40_41/fastio.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index 77fe0953d3..3c7cda0b4e 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/HAL/shared/Delay.cpp b/Marlin/src/HAL/shared/Delay.cpp index c64376d25d..8856fe134d 100644 --- a/Marlin/src/HAL/shared/Delay.cpp +++ b/Marlin/src/HAL/shared/Delay.cpp @@ -167,7 +167,6 @@ } #endif // MARLIN_DEV_MODE - #else void calibrate_delay_loop() {} diff --git a/Marlin/src/HAL/shared/backtrace/unwarm.cpp b/Marlin/src/HAL/shared/backtrace/unwarm.cpp index e72a02e487..823f54c157 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarm.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwarm.cpp @@ -50,7 +50,6 @@ void UnwInvalidateRegisterFile(RegData *regFile) { } while (t < 13); } - /** * Initialize the data used for unwinding. */ @@ -129,7 +128,6 @@ bool UnwReportRetAddr(UnwState * const state, uint32_t addr) { return state->cb->report((void *)state->reportData, &entry); } - /** * Write some register to memory. * This will store some register and meta data onto the virtual stack. diff --git a/Marlin/src/HAL/shared/backtrace/unwarm.h b/Marlin/src/HAL/shared/backtrace/unwarm.h index edae90650e..72ea0b0627 100644 --- a/Marlin/src/HAL/shared/backtrace/unwarm.h +++ b/Marlin/src/HAL/shared/backtrace/unwarm.h @@ -41,7 +41,6 @@ typedef enum { REG_VAL_ARITHMETIC = 0x80 } RegValOrigin; - /** Type for tracking information about a register. * This stores the register value, as well as other data that helps unwinding. */ @@ -56,7 +55,6 @@ typedef struct { int o; /* (RegValOrigin) */ } RegData; - /** Structure used to track reads and writes to memory. * This structure is used as a hash to store a small number of writes * to memory. @@ -81,7 +79,6 @@ typedef struct { uint8_t tracked[(MEM_HASH_SIZE + 7) / 8]; } MemData; - /** Structure that is used to keep track of unwinding meta-data. * This data is passed between all the unwinding functions. */ diff --git a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp index a4151b38c2..da1cff4fcc 100644 --- a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp @@ -135,7 +135,7 @@ // Generic ARM code, that's testing if an access to the given address would cause a fault or not // It can't guarantee an address is in RAM or Flash only, but we usually don't care - #define NVIC_FAULT_STAT 0xE000ED28 // Configurable Fault Status Reg. + #define NVIC_FAULT_STAT 0xE000ED28 // Configurable Fault Status reg. #define NVIC_CFG_CTRL 0xE000ED14 // Configuration Control Register #define NVIC_FAULT_STAT_BFARV 0x00008000 // BFAR is valid #define NVIC_CFG_CTRL_BFHFNMIGN 0x00000100 // Ignore bus fault in NMI/fault diff --git a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp index e54661c770..6c7a3fe7d9 100644 --- a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp +++ b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2020 Cyril Russo * * 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 @@ -27,7 +26,6 @@ #if defined(__arm__) || defined(__thumb__) - /* On ARM CPUs exception handling is quite powerful. diff --git a/Marlin/src/HAL/shared/eeprom_api.cpp b/Marlin/src/HAL/shared/eeprom_api.cpp index 083ccc70d7..62a8f2afbc 100644 --- a/Marlin/src/HAL/shared/eeprom_api.cpp +++ b/Marlin/src/HAL/shared/eeprom_api.cpp @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/shared/eeprom_api.h b/Marlin/src/HAL/shared/eeprom_api.h index cd744f82dc..7be1e72f7a 100644 --- a/Marlin/src/HAL/shared/eeprom_api.h +++ b/Marlin/src/HAL/shared/eeprom_api.h @@ -1,10 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com + * + * 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 diff --git a/Marlin/src/HAL/shared/eeprom_if.h b/Marlin/src/HAL/shared/eeprom_if.h index e496de2a03..8b9791e1f8 100644 --- a/Marlin/src/HAL/shared/eeprom_if.h +++ b/Marlin/src/HAL/shared/eeprom_if.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com + * + * 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 diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index e4e72f3bdb..e21c89be21 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -351,9 +351,7 @@ void startOrResumeJob() { TERN_(GCODE_REPEAT_MARKERS, repeat.reset()); TERN_(CANCEL_OBJECTS, cancelable.reset()); TERN_(LCD_SHOW_E_TOTAL, e_move_accumulator = 0); - #if ENABLED(SET_REMAINING_TIME) - ui.reset_remaining_time(); - #endif + TERN_(SET_REMAINING_TIME, ui.reset_remaining_time()); } print_job_timer.start(); } @@ -1079,7 +1077,7 @@ inline void tmc_standby_setup() { * - Init the buzzer, possibly a custom timer * - Init more optional hardware: * • Color LED illumination - * • Neopixel illumination + * • NeoPixel illumination * • Controller Fan * • Creality DWIN LCD (show boot image) * • Tare the Probe if possible diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 9419a43fa3..ed5b649f24 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -308,7 +308,7 @@ // #define BOARD_BTT_EBB42_V1_1 4000 // BigTreeTech EBB42 V1.1 (STM32G0B1CB) -#define BOARD_BTT_SKR_MINI_E3_V3_0 4001 // BigTreeTech SKR Mini E3 V3.0 (STM32G0B1RE) +#define BOARD_BTT_SKR_MINI_E3_V3_0 4001 // BigTreeTech SKR Mini E3 V3.0 (STM32G0B0RE / STM32G0B1RE) #define BOARD_BTT_MANTA_E3_EZ_V1_0 4002 // BigTreeTech Manta E3 EZ V1.0 (STM32G0B1RE) #define BOARD_BTT_MANTA_M4P_V2_1 4003 // BigTreeTech Manta M4P V2.1 (STM32G0B0RE) #define BOARD_BTT_MANTA_M5P_V1_0 4004 // BigTreeTech Manta M5P V1.0 (STM32G0B1RE) @@ -386,7 +386,7 @@ #define BOARD_ZONESTAR_ZM3E4V2 5064 // Zonestar ZM3E4 V2 (STM32F103VC) #define BOARD_ERYONE_ERY32_MINI 5065 // Eryone Ery32 mini (STM32F103VE) #define BOARD_PANDA_PI_V29 5066 // Panda Pi V2.9 - Standalone (STM32F103RC) -#define BOARD_SOVOL_V131 5067 // Sovol V1.3.1 (GD32F103RET6) +#define BOARD_SOVOL_V131 5067 // Sovol V1.3.1 (GD32F103RE) // // ARM Cortex-M4F @@ -455,9 +455,9 @@ #define BOARD_NUCLEO_F767ZI 6003 // ST NUCLEO-F767ZI Dev Board #define BOARD_BTT_SKR_SE_BX_V2 6004 // BigTreeTech SKR SE BX V2.0 (STM32H743II) #define BOARD_BTT_SKR_SE_BX_V3 6005 // BigTreeTech SKR SE BX V3.0 (STM32H743II) -#define BOARD_BTT_SKR_V3_0 6006 // BigTreeTech SKR V3.0 (STM32H743VG) -#define BOARD_BTT_SKR_V3_0_EZ 6007 // BigTreeTech SKR V3.0 EZ (STM32H743VG) -#define BOARD_BTT_OCTOPUS_MAX_EZ_V1_0 6008 // BigTreeTech Octopus Max EZ V1.0 (STM32H723VE / STM32H723ZE) +#define BOARD_BTT_SKR_V3_0 6006 // BigTreeTech SKR V3.0 (STM32H743VI / STM32H723VG) +#define BOARD_BTT_SKR_V3_0_EZ 6007 // BigTreeTech SKR V3.0 EZ (STM32H743VI / STM32H723VG) +#define BOARD_BTT_OCTOPUS_MAX_EZ_V1_0 6008 // BigTreeTech Octopus Max EZ V1.0 (STM32H723ZE) // // Espressif ESP32 WiFi diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 3a44299e87..3d69474d48 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -153,7 +153,7 @@ #define STR_ERR_ARC_ARGS "G2/G3 bad parameters" #define STR_ERR_PROTECTED_PIN "Protected Pin" #define STR_ERR_M420_FAILED "Failed to enable Bed Leveling" -#define STR_ERR_M428_TOO_FAR "Too far from reference point" +#define STR_ERR_M428_TOO_FAR "Too far from MIN/MAX" #define STR_ERR_M303_DISABLED "PIDTEMP disabled" #define STR_M119_REPORT "Reporting endstop status" #define STR_ON "ON" diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 5ca68b95d5..6dc7a7bcce 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -82,11 +82,12 @@ #define FORCE_INLINE __attribute__((always_inline)) inline #define NO_INLINE __attribute__((noinline)) #define _UNUSED __attribute__((unused)) -#define __O0 __attribute__((optimize("O0"))) -#define __Os __attribute__((optimize("Os"))) -#define __O1 __attribute__((optimize("O1"))) -#define __O2 __attribute__((optimize("O2"))) -#define __O3 __attribute__((optimize("O3"))) +#define __O0 __attribute__((optimize("O0"))) // No optimization and less debug info +#define __Og __attribute__((optimize("Og"))) // Optimize the debugging experience +#define __Os __attribute__((optimize("Os"))) // Optimize for size +#define __O1 __attribute__((optimize("O1"))) // Try to reduce size and cycles; nothing that takes a lot of time to compile +#define __O2 __attribute__((optimize("O2"))) // Optimize even more +#define __O3 __attribute__((optimize("O3"))) // Optimize yet more #define IS_CONSTEXPR(...) __builtin_constant_p(__VA_ARGS__) // Only valid solution with C++14. Should use std::is_constant_evaluated() in C++20 instead @@ -223,22 +224,25 @@ #define _DO_N(W,C,N,V...) __DO_N(W,C,N,V) #define DO(W,C,V...) (_DO_N(W,C,NUM_ARGS(V),V)) -// Macros to support option testing +// Concatenate symbol names, without or with pre-expansion #define _CAT(a,V...) a##V #define CAT(a,V...) _CAT(a,V) +// Recognize "true" values: blank, 1, 0x1, true #define _ISENA_ ~,1 #define _ISENA_1 ~,1 #define _ISENA_0x1 ~,1 #define _ISENA_true ~,1 #define _ISENA(V...) IS_PROBE(V) +// Macros to evaluate simple option switches #define _ENA_1(O) _ISENA(CAT(_IS,CAT(ENA_, O))) #define _DIS_1(O) NOT(_ENA_1(O)) #define ENABLED(V...) DO(ENA,&&,V) #define DISABLED(V...) DO(DIS,&&,V) #define COUNT_ENABLED(V...) DO(ENA,+,V) +// Ternary pre-compiler macros conceal non-emitted content from the compiler #define TERN(O,A,B) _TERN(_ENA_1(O),B,A) // OPTION ? 'A' : 'B' #define TERN0(O,A) _TERN(_ENA_1(O),0,A) // OPTION ? 'A' : '0' #define TERN1(O,A) _TERN(_ENA_1(O),1,A) // OPTION ? 'A' : '1' @@ -247,6 +251,7 @@ #define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1' #define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B. +// Macros to conditionally emit array items and function arguments #define _OPTITEM(A...) A, #define OPTITEM(O,A...) TERN_(O,DEFER4(_OPTITEM)(A)) #define _OPTARG(A...) , A @@ -254,7 +259,7 @@ #define _OPTCODE(A) A; #define OPTCODE(O,A) TERN_(O,DEFER4(_OPTCODE)(A)) -// Macros to avoid 'f + 0.0' which is not always optimized away. Minus included for symmetry. +// Macros to avoid operations that aren't always optimized away (e.g., 'f + 0.0' and 'f * 1.0'). // Compiler flags -fno-signed-zeros -ffinite-math-only also cover 'f * 1.0', 'f - f', etc. #define PLUS_TERN0(O,A) _TERN(_ENA_1(O),,+ (A)) // OPTION ? '+ (A)' : '' #define MINUS_TERN0(O,A) _TERN(_ENA_1(O),,- (A)) // OPTION ? '- (A)' : '' @@ -282,6 +287,7 @@ #define BUTTONS_EXIST(V...) DO(BTNEX,&&,V) #define ANY_BUTTON(V...) DO(BTNEX,||,V) +// Value helper macros #define WITHIN(N,L,H) ((N) >= (L) && (N) <= (H)) #define ISEOL(C) ((C) == '\n' || (C) == '\r') #define NUMERIC(a) WITHIN(a, '0', '9') @@ -289,6 +295,8 @@ #define HEXCHR(a) (NUMERIC(a) ? (a) - '0' : WITHIN(a, 'a', 'f') ? ((a) - 'a' + 10) : WITHIN(a, 'A', 'F') ? ((a) - 'A' + 10) : -1) #define NUMERIC_SIGNED(a) (NUMERIC(a) || (a) == '-' || (a) == '+') #define DECIMAL_SIGNED(a) (DECIMAL(a) || (a) == '-' || (a) == '+') + +// Array shorthand #define COUNT(a) (sizeof(a)/sizeof(*a)) #define ZERO(a) memset((void*)a,0,sizeof(a)) #define COPY(a,b) do{ \ @@ -296,6 +304,7 @@ memcpy(&a[0],&b[0],_MIN(sizeof(a),sizeof(b))); \ }while(0) +// Expansion of some code #define CODE_16( A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,...) A; B; C; D; E; F; G; H; I; J; K; L; M; N; O; P #define CODE_15( A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,...) A; B; C; D; E; F; G; H; I; J; K; L; M; N; O #define CODE_14( A,B,C,D,E,F,G,H,I,J,K,L,M,N,...) A; B; C; D; E; F; G; H; I; J; K; L; M; N @@ -316,6 +325,7 @@ #define _CODE_N(N,V...) CODE_##N(V) #define CODE_N(N,V...) _CODE_N(N,V) +// Expansion of some non-delimited content #define GANG_16(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,...) A B C D E F G H I J K L M N O P #define GANG_15(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,...) A B C D E F G H I J K L M N O #define GANG_14(A,B,C,D,E,F,G,H,I,J,K,L,M,N,...) A B C D E F G H I J K L M N @@ -337,7 +347,7 @@ #define GANG_N(N,V...) _GANG_N(N,V) #define GANG_N_1(N,K) _GANG_N(N,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K) -// Macros for initializing arrays +// Expansion of some list items #define LIST_26(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z #define LIST_25(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y #define LIST_24(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X @@ -458,6 +468,7 @@ template struct first_type_of { typedef T type; }; template struct first_type_of { typedef T type; }; } + // C++11 solution using SFINAE to detect the existence of a member in a class at compile time. // It creates a HasMember structure containing 'value' set to true if the member exists #define HAS_MEMBER_IMPL(Member) \ diff --git a/Marlin/src/core/serial_base.h b/Marlin/src/core/serial_base.h index d1b6237989..0ff99b766b 100644 --- a/Marlin/src/core/serial_base.h +++ b/Marlin/src/core/serial_base.h @@ -77,7 +77,7 @@ struct EnsureDouble { operator double() { return a; } // If the compiler breaks on ambiguity here, it's likely because print(X, base) is called with X not a double/float, and // a base that's not a PrintBase value. This code is made to detect the error. You MUST set a base explicitly like this: - // SERIAL_PRINT(v, PrintBase::Hex) + //SERIAL_PRINT(v, PrintBase::Hex) EnsureDouble(double a) : a(a) {} EnsureDouble(float a) : a(a) {} }; @@ -167,7 +167,6 @@ struct SerialBase { FORCE_INLINE void print(unsigned int c, PrintBase base) { printNumber_unsigned(c, base); } FORCE_INLINE void print(unsigned long c, PrintBase base) { printNumber_unsigned(c, base); } - void print(EnsureDouble c, int digits) { printFloat(c, digits); } // Forward the call to the former's method @@ -178,7 +177,7 @@ struct SerialBase { void print(T c) { print(c, PrintBase::Dec); } void print(float c) { print(c, 2); } - void print(double c) { print(c, 2); } + void print(double c) { print(c, 2); } void println(char *s) { print(s); println(); } void println(const char *s) { print(s); println(); } diff --git a/Marlin/src/core/serial_hook.h b/Marlin/src/core/serial_hook.h index 65c553c702..06efce1dc5 100644 --- a/Marlin/src/core/serial_hook.h +++ b/Marlin/src/core/serial_hook.h @@ -179,7 +179,7 @@ struct RuntimeSerial : public SerialBase< RuntimeSerial >, public Seria // Append Hookable for this class SerialFeature features(serial_index_t index) const { return SerialFeature::Hookable | CALL_IF_EXISTS(SerialFeature, static_cast(this), features, index); } - void setHook(WriteHook writeHook = 0, EndOfMessageHook eofHook = 0, void * userPointer = 0) { + void setHook(WriteHook writeHook=0, EndOfMessageHook eofHook=0, void * userPointer=0) { // Order is important here as serial code can be called inside interrupts // When setting a hook, the user pointer must be set first so if writeHook is called as soon as it's set, it'll be valid if (userPointer) this->userPointer = userPointer; @@ -292,7 +292,7 @@ struct MultiSerial : public SerialBase< MultiSerial< REPEAT(NUM_SERIAL, _S_NAME) #define _S_REFS(N) Serial##N##T & serial##N, #define _S_INIT(N) ,serial##N (serial##N) - MultiSerial(REPEAT(NUM_SERIAL, _S_REFS) const SerialMask mask = ALL, const bool e = false) + MultiSerial(REPEAT(NUM_SERIAL, _S_REFS) const SerialMask mask=ALL, const bool e=false) : BaseClassT(e), portMask(mask) REPEAT(NUM_SERIAL, _S_INIT) {} }; diff --git a/Marlin/src/feature/babystep.h b/Marlin/src/feature/babystep.h index eeacde3e2f..32e1375535 100644 --- a/Marlin/src/feature/babystep.h +++ b/Marlin/src/feature/babystep.h @@ -31,7 +31,7 @@ #define BABYSTEP_TICKS ((TEMP_TIMER_RATE) / (BABYSTEPS_PER_SEC)) #endif -#if IS_CORE || ANY(BABYSTEP_XY, I2C_POSITION_ENCODERS) +#if ANY(IS_CORE, BABYSTEP_XY, I2C_POSITION_ENCODERS) #define BS_AXIS_IND(A) A #define BS_AXIS(I) AxisEnum(I) #else diff --git a/Marlin/src/feature/bedlevel/abl/bbl.cpp b/Marlin/src/feature/bedlevel/abl/bbl.cpp index 6b9888f875..62d2471d85 100644 --- a/Marlin/src/feature/bedlevel/abl/bbl.cpp +++ b/Marlin/src/feature/bedlevel/abl/bbl.cpp @@ -153,7 +153,7 @@ void LevelingBilinear::extrapolate_unprobed_bed_level() { } } -void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values /*= NULL*/) { +void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values/*=nullptr*/) { // print internal grid(s) or just the one passed as a parameter SERIAL_ECHOLNPGM("Bilinear Leveling Grid:"); print_2d_array(GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y, 3, _z_values ? *_z_values[0] : z_values[0]); diff --git a/Marlin/src/feature/bedlevel/abl/bbl.h b/Marlin/src/feature/bedlevel/abl/bbl.h index c2be4fee82..60dde9060f 100644 --- a/Marlin/src/feature/bedlevel/abl/bbl.h +++ b/Marlin/src/feature/bedlevel/abl/bbl.h @@ -53,7 +53,7 @@ public: static void reset(); static void set_grid(const xy_pos_t& _grid_spacing, const xy_pos_t& _grid_start); static void extrapolate_unprobed_bed_level(); - static void print_leveling_grid(const bed_mesh_t* _z_values = NULL); + static void print_leveling_grid(const bed_mesh_t *_z_values=nullptr); static void refresh_bed_level(); static bool has_mesh() { return !!grid_spacing.x; } static bool mesh_is_valid() { return has_mesh(); } diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index fc5eb6337d..9d3d21f680 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -620,7 +620,6 @@ void unified_bed_leveling::G29() { #endif // UBL_DEVEL_DEBUGGING - // // Load a Mesh from the EEPROM // diff --git a/Marlin/src/feature/digipot/digipot_mcp4018.cpp b/Marlin/src/feature/digipot/digipot_mcp4018.cpp index f776c5a339..48d7ff492c 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4018.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4018.cpp @@ -37,7 +37,7 @@ #ifndef DIGIPOT_A4988_Vrefmax #define DIGIPOT_A4988_Vrefmax 1.666 #endif -#define DIGIPOT_MCP4018_MAX_VALUE 127 +#define DIGIPOT_MCP4018_MAX_VALUE 127 #define DIGIPOT_A4988_Itripmax(Vref) ((Vref) / (8.0 * DIGIPOT_A4988_Rsx)) diff --git a/Marlin/src/feature/digipot/digipot_mcp4451.cpp b/Marlin/src/feature/digipot/digipot_mcp4451.cpp index 7416fe9f8d..e35b42a28b 100644 --- a/Marlin/src/feature/digipot/digipot_mcp4451.cpp +++ b/Marlin/src/feature/digipot/digipot_mcp4451.cpp @@ -35,8 +35,8 @@ // Settings for the I2C based DIGIPOT (MCP4451) on Azteeg X3 Pro #if MB(5DPRINT) - #define DIGIPOT_I2C_FACTOR 117.96f - #define DIGIPOT_I2C_MAX_CURRENT 1.736f + #define DIGIPOT_I2C_FACTOR 117.96f + #define DIGIPOT_I2C_MAX_CURRENT 1.736f #elif MB(AZTEEG_X5_MINI, AZTEEG_X5_MINI_WIFI) #define DIGIPOT_I2C_FACTOR 113.5f #define DIGIPOT_I2C_MAX_CURRENT 2.0f diff --git a/Marlin/src/feature/easythreed_ui.cpp b/Marlin/src/feature/easythreed_ui.cpp index b15daffc09..96f5f68e06 100644 --- a/Marlin/src/feature/easythreed_ui.cpp +++ b/Marlin/src/feature/easythreed_ui.cpp @@ -190,31 +190,28 @@ void EasythreedUI::printButton() { print_key_flag = PF_PAUSE; // The "Print" button now pauses the print card.mount(); // Force SD card to mount - now! if (!card.isMounted) { // Failed to mount? - blink_interval_ms = LED_OFF; // Turn off LED - print_key_flag = PF_START; - return; // Bail out + blink_interval_ms = LED_OFF; // Turn off LED + print_key_flag = PF_START; + return; // Bail out } card.ls(); // List all files to serial output const uint16_t filecnt = card.countFilesInWorkDir(); // Count printable files in cwd if (filecnt == 0) return; // None are printable? card.selectFileByIndex(filecnt); // Select the last file according to current sort options card.openAndPrintFile(card.filename); // Start printing it - break; - } + } break; case PF_PAUSE: { // Pause printing (not currently firing) if (!printingIsActive()) break; blink_interval_ms = LED_ON; // Set indicator to steady ON queue.inject(F("M25")); // Queue Pause print_key_flag = PF_RESUME; // The "Print" button now resumes the print - break; - } + } break; case PF_RESUME: { // Resume printing if (printingIsActive()) break; blink_interval_ms = LED_BLINK_2; // Blink the indicator LED at 1 second intervals queue.inject(F("M24")); // Queue resume print_key_flag = PF_PAUSE; // The "Print" button now pauses the print - break; - } + } break; } } else { // Register a longer press diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index b73cdbd91a..cc9cf2e7c8 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -27,7 +27,6 @@ //todo: try faster I2C speed; tweak TWI_FREQ (400000L, or faster?); or just TWBR = ((CPU_FREQ / 400000L) - 16) / 2; //todo: consider Marlin-optimized Wire library; i.e. MarlinWire, like MarlinSerial - #include "../inc/MarlinConfig.h" #if ENABLED(I2C_POSITION_ENCODERS) @@ -425,22 +424,22 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { travelledDistance = mm_from_count(ABS(stopCount - startCount)); SERIAL_ECHOLNPGM("Attempted travel: ", travelDistance, "mm"); - SERIAL_ECHOLNPGM(" Actual travel: ", travelledDistance, "mm"); + SERIAL_ECHOLNPGM(" Actual travel: ", travelledDistance, "mm"); - //Calculate new axis steps per unit + // Calculate new axis steps per unit old_steps_mm = planner.settings.axis_steps_per_mm[encoderAxis]; new_steps_mm = (old_steps_mm * travelDistance) / travelledDistance; SERIAL_ECHOLNPGM("Old steps/mm: ", old_steps_mm); SERIAL_ECHOLNPGM("New steps/mm: ", new_steps_mm); - //Save new value + // Save new value planner.settings.axis_steps_per_mm[encoderAxis] = new_steps_mm; if (iter > 1) { total += new_steps_mm; - // swap start and end points so next loop runs from current position + // Swap start and end points so next loop runs from current position const float tempCoord = startCoord[encoderAxis]; startCoord[encoderAxis] = endCoord[encoderAxis]; endCoord[encoderAxis] = tempCoord; @@ -465,7 +464,6 @@ void I2CPositionEncoder::reset() { TERN_(I2CPE_ERR_ROLLING_AVERAGE, ZERO(err)); } - bool I2CPositionEncodersMgr::I2CPE_anyaxis; uint8_t I2CPositionEncodersMgr::I2CPE_addr, I2CPositionEncodersMgr::I2CPE_idx; diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index 28355640d2..8f2edad158 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -195,8 +195,6 @@ void FWRetract::retract(const bool retracting E_OPTARG(bool swapping/*=false*/)) //*/ } -//extern const char SP_Z_STR[]; - /** * M207: Set firmware retraction values * @@ -265,5 +263,4 @@ void FWRetract::M208_report() { #endif // FWRETRACT_AUTORETRACT - #endif // FWRETRACT diff --git a/Marlin/src/feature/leds/neopixel.cpp b/Marlin/src/feature/leds/neopixel.cpp index 848c8500c2..d157ba73d3 100644 --- a/Marlin/src/feature/leds/neopixel.cpp +++ b/Marlin/src/feature/leds/neopixel.cpp @@ -54,7 +54,7 @@ Adafruit_NeoPixel Marlin_NeoPixel::adaneo1(NEOPIXEL_PIXELS, NEOPIXEL_PIN, NEOPIX set_background_color(background_color); } -#endif +#endif // NEOPIXEL_BKGD_INDEX_FIRST void Marlin_NeoPixel::set_color(const uint32_t color) { if (neoindex >= 0) { diff --git a/Marlin/src/feature/leds/pca9533.cpp b/Marlin/src/feature/leds/pca9533.cpp index 914db21ba3..d71760e2cb 100644 --- a/Marlin/src/feature/leds/pca9533.cpp +++ b/Marlin/src/feature/leds/pca9533.cpp @@ -1,4 +1,4 @@ -/* +/** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * diff --git a/Marlin/src/feature/leds/pca9533.h b/Marlin/src/feature/leds/pca9533.h index 431058c491..3a18e96b24 100644 --- a/Marlin/src/feature/leds/pca9533.h +++ b/Marlin/src/feature/leds/pca9533.h @@ -1,4 +1,4 @@ -/* +/** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * @@ -21,7 +21,7 @@ */ #pragma once -/* +/** * Driver for the PCA9533 LED controller found on the MightyBoard * used by FlashForge Creator Pro, MakerBot, etc. * Written 2020 APR 01 by grauerfuchs diff --git a/Marlin/src/feature/max7219.cpp b/Marlin/src/feature/max7219.cpp index b4ff645e11..e55a8d2ae9 100644 --- a/Marlin/src/feature/max7219.cpp +++ b/Marlin/src/feature/max7219.cpp @@ -39,7 +39,7 @@ #if ENABLED(MAX7219_DEBUG) -#define MAX7219_ERRORS // Disable to save 406 bytes of Program Memory +#define MAX7219_ERRORS // Requires ~400 bytes of flash #include "max7219.h" diff --git a/Marlin/src/feature/meatpack.h b/Marlin/src/feature/meatpack.h index 98a535e592..0de1f792c1 100644 --- a/Marlin/src/feature/meatpack.h +++ b/Marlin/src/feature/meatpack.h @@ -20,7 +20,7 @@ * */ -/* +/** * MeatPack G-code Compression * * Algorithm & Implementation: Scott Mudge - mail@scottmudge.com @@ -144,7 +144,6 @@ struct MeatpackSerial : public SerialBase > { void flushTX() { CALL_IF_EXISTS(void, &out, flushTX); } SerialFeature features(serial_index_t index) const { return SerialFeature::MeatPack | CALL_IF_EXISTS(SerialFeature, &out, features, index); } - int available(serial_index_t index) { if (charCount) return charCount; // The buffer still has data if (out.available(index) <= 0) return 0; // No data to read diff --git a/Marlin/src/feature/mixing.h b/Marlin/src/feature/mixing.h index a43b059944..bc3ca794ad 100644 --- a/Marlin/src/feature/mixing.h +++ b/Marlin/src/feature/mixing.h @@ -108,7 +108,7 @@ class Mixer { } // Used when dealing with blocks - FORCE_INLINE static void populate_block(mixer_comp_t b_color[MIXING_STEPPERS]) { + FORCE_INLINE static void populate_block(mixer_comp_t (&b_color)[MIXING_STEPPERS]) { #if ENABLED(GRADIENT_MIX) if (gradient.enabled) { MIXER_STEPPER_LOOP(i) b_color[i] = gradient.color[i]; @@ -118,7 +118,7 @@ class Mixer { MIXER_STEPPER_LOOP(i) b_color[i] = color[selected_vtool][i]; } - FORCE_INLINE static void stepper_setup(mixer_comp_t b_color[MIXING_STEPPERS]) { + FORCE_INLINE static void stepper_setup(mixer_comp_t (&b_color)[MIXING_STEPPERS]) { MIXER_STEPPER_LOOP(i) s_color[i] = b_color[i]; } @@ -233,13 +233,7 @@ class Mixer { for (;;) { if (--runner < 0) runner = MIXING_STEPPERS - 1; accu[runner] += s_color[runner]; - if ( - #ifdef MIXER_ACCU_SIGNED - accu[runner] < 0 - #else - accu[runner] & COLOR_A_MASK - #endif - ) { + if (TERN(MIXER_ACCU_SIGNED, accu[runner] < 0, accu[runner] & COLOR_A_MASK)) { accu[runner] &= COLOR_MASK; return runner; } diff --git a/Marlin/src/feature/mmu/mmu2-serial-protocol.md b/Marlin/src/feature/mmu/mmu2-serial-protocol.md index 93135e406f..088d41b446 100644 --- a/Marlin/src/feature/mmu/mmu2-serial-protocol.md +++ b/Marlin/src/feature/mmu/mmu2-serial-protocol.md @@ -28,11 +28,8 @@ Now we are sure MMU is available and ready. If there was a timeout or other comm - *Build number* is an integer value and has to be >=126, or =>132 if 12V mode is enabled - *FINDA status* is 1 if the filament is loaded to the extruder, 0 otherwise - *Build number* is checked against the required value, if it does not match, printer is halted. - - Toolchange ========== @@ -54,7 +51,6 @@ When done, the MMU sends We don't wait for a response here but immediately continue with the next G-code which should be one or more extruder moves to feed the filament into the hotend. - FINDA status ============ @@ -63,8 +59,6 @@ FINDA status *FINDA status* is 1 if the is filament loaded to the extruder, 0 otherwise. This could be used as filament runout sensor if probed regularly. - - Load filament ============= @@ -74,7 +68,6 @@ MMU will feed filament down to the extruder, when done - MMU => 'ok\n' - Unload filament ============= @@ -84,11 +77,8 @@ MMU will retract current filament from the extruder, when done - MMU => 'ok\n' - - Eject filament ============== - MMU <= 'E*Filament index*\n' - MMU => 'ok\n' - diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index e37b4c33ef..5053c3fbaf 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -136,9 +136,7 @@ void MMU2::reset() { #endif } -uint8_t MMU2::get_current_tool() { - return extruder == MMU2_NO_TOOL ? -1 : extruder; -} +int8_t MMU2::get_current_tool() { return extruder == MMU2_NO_TOOL ? -1 : extruder; } #if ANY(HAS_PRUSA_MMU2S, MMU_EXTRUDER_SENSOR) #define FILAMENT_PRESENT() (READ(FIL_RUNOUT1_PIN) != FIL_RUNOUT1_STATE) @@ -149,6 +147,7 @@ void mmu2_attn_buzz(const bool two=false) { if (two) { BUZZ(10, 0); BUZZ(200, 404); } } +// Avoiding sscanf significantly reduces build size void MMU2::mmu_loop() { switch (state) { @@ -190,7 +189,6 @@ void MMU2::mmu_loop() { DEBUG_ECHOLNPGM("MMU <= 'M1'"); MMU2_SEND("M1"); // Stealth Mode state = -5; - #else DEBUG_ECHOLNPGM("MMU <= 'P0'"); MMU2_SEND("P0"); // Read FINDA @@ -200,15 +198,15 @@ void MMU2::mmu_loop() { break; #if ENABLED(MMU2_MODE_12V) - case -5: - // response to M1 - if (rx_ok()) { - DEBUG_ECHOLNPGM("MMU => ok"); - DEBUG_ECHOLNPGM("MMU <= 'P0'"); - MMU2_SEND("P0"); // Read FINDA - state = -4; - } - break; + case -5: + // response to M1 + if (rx_ok()) { + DEBUG_ECHOLNPGM("MMU => ok"); + DEBUG_ECHOLNPGM("MMU <= 'P0'"); + MMU2_SEND("P0"); // Read FINDA + state = -4; + } + break; #endif case -4: @@ -460,6 +458,11 @@ static void mmu2_not_responding() { #if HAS_PRUSA_MMU2S + /** + * Load filament until the sensor at the gears is triggered + * and give up after a number of attempts set with MMU2_C0_RETRY. + * Each try has a timeout before returning a fail state. + */ bool MMU2::load_to_gears() { command(MMU_CMD_C0); manage_response(true, true); @@ -830,7 +833,6 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { thermalManager.setTargetHotend(resume_hotend_temp, active_extruder); LCD_MESSAGE(MSG_HEATING); ERR_BUZZ(); - while (!thermalManager.wait_for_hotend(active_extruder, false)) safe_delay(1000); } @@ -843,7 +845,6 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { if (move_axes && all_axes_homed()) { // Move XY to starting position, then Z do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); - // Move Z_AXIS to saved position do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); } @@ -1038,7 +1039,7 @@ void MMU2::execute_extruder_sequence(const E_Step * sequence, int steps) { planner.synchronize(); stepper.enable_extruder(); - const E_Step* step = sequence; + const E_Step *step = sequence; for (uint8_t i = 0; i < steps; ++i) { const float es = pgm_read_float(&(step->extrude)); diff --git a/Marlin/src/feature/mmu/mmu2.h b/Marlin/src/feature/mmu/mmu2.h index 18d6d38a35..515f400b4c 100644 --- a/Marlin/src/feature/mmu/mmu2.h +++ b/Marlin/src/feature/mmu/mmu2.h @@ -47,7 +47,7 @@ public: static void mmu_loop(); static void tool_change(const uint8_t index); static void tool_change(const char *special); - static uint8_t get_current_tool(); + static int8_t get_current_tool(); static void set_filament_type(const uint8_t index, const uint8_t type); static bool unload(); diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 802f7723f1..36088e4e2a 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -440,7 +440,7 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool // Wait for buffered blocks to complete planner.synchronize(); - #if ENABLED(ADVANCED_PAUSE_FANS_PAUSE) && HAS_FAN + #if ALL(ADVANCED_PAUSE_FANS_PAUSE, HAS_FAN) thermalManager.set_fans_paused(true); #endif diff --git a/Marlin/src/feature/pause.h b/Marlin/src/feature/pause.h index 7ea0c03b6b..45f62dc310 100644 --- a/Marlin/src/feature/pause.h +++ b/Marlin/src/feature/pause.h @@ -48,15 +48,15 @@ enum PauseMessage : char { PAUSE_MESSAGE_PARKING, PAUSE_MESSAGE_CHANGING, PAUSE_MESSAGE_WAITING, - PAUSE_MESSAGE_UNLOAD, PAUSE_MESSAGE_INSERT, PAUSE_MESSAGE_LOAD, + PAUSE_MESSAGE_UNLOAD, PAUSE_MESSAGE_PURGE, PAUSE_MESSAGE_OPTION, PAUSE_MESSAGE_RESUME, - PAUSE_MESSAGE_STATUS, PAUSE_MESSAGE_HEAT, - PAUSE_MESSAGE_HEATING + PAUSE_MESSAGE_HEATING, + PAUSE_MESSAGE_STATUS }; #if M600_PURGE_MORE_RESUMABLE diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 57da66bddc..200014cbcb 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -221,9 +221,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW TERN_(HAS_HEATED_BED, info.target_temperature_bed = thermalManager.degTargetBed()); - #if HAS_FAN - COPY(info.fan_speed, thermalManager.fan_speed); - #endif + TERN_(HAS_FAN, COPY(info.fan_speed, thermalManager.fan_speed)); #if HAS_LEVELING info.flag.leveling = planner.leveling_active; diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index d241fdb74c..a754c5f93a 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -43,7 +43,7 @@ #endif #ifndef POWER_LOSS_ZRAISE - #define POWER_LOSS_ZRAISE 2 + #define POWER_LOSS_ZRAISE 2 // Default Z-raise on outage or resume #endif //#define DEBUG_POWER_LOSS_RECOVERY diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h index 807f6014a7..7b68c9fd87 100644 --- a/Marlin/src/feature/runout.h +++ b/Marlin/src/feature/runout.h @@ -324,7 +324,6 @@ class FilamentSensorBase { } }; - #endif // !FILAMENT_MOTION_SENSOR /********************************* RESPONSE TYPE *********************************/ diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index 8908ae6df5..681df2f081 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -38,7 +38,6 @@ #define PCT_TO_PWM(X) ((X) * 255 / 100) #define PCT_TO_SERVO(X) ((X) * 180 / 100) - // Laser/Cutter operation mode enum CutterMode : int8_t { CUTTER_MODE_ERROR = -1, diff --git a/Marlin/src/feature/stepper_driver_safety.h b/Marlin/src/feature/stepper_driver_safety.h index 46edf3390d..ac3d8b64f9 100644 --- a/Marlin/src/feature/stepper_driver_safety.h +++ b/Marlin/src/feature/stepper_driver_safety.h @@ -21,7 +21,6 @@ */ #pragma once - #include "../inc/MarlinConfigPre.h" void stepper_driver_backward_check(); diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index c10bab6274..fffa748f93 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -378,6 +378,7 @@ void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true)); return drv_status.stallGuard; } + #endif // SPI_ENDSTOPS #endif // USE_SENSORLESS diff --git a/Marlin/src/feature/twibus.h b/Marlin/src/feature/twibus.h index 806e2a147a..de23abbed5 100644 --- a/Marlin/src/feature/twibus.h +++ b/Marlin/src/feature/twibus.h @@ -74,7 +74,6 @@ class TWIBus { */ uint8_t buffer[TWIBUS_BUFFER_SIZE]; - public: /** * @brief Target device address diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index 6e0026f427..aa4ded0007 100644 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -57,8 +57,9 @@ * 41 - Counter-Clockwise M4 * 50 - Clockwise M5 * 51 - Counter-Clockwise M5 - **/ + */ void GcodeSuite::G35() { + DEBUG_SECTION(log_G35, "G35", DEBUGGING(LEVELING)); if (DEBUGGING(LEVELING)) log_machine_info(); @@ -82,9 +83,7 @@ void GcodeSuite::G35() { set_bed_leveling_enabled(false); #endif - #if ENABLED(CNC_WORKSPACE_PLANES) - workspace_plane = PLANE_XY; - #endif + TERN_(CNC_WORKSPACE_PLANES, workspace_plane = PLANE_XY); // Always home with tool 0 active #if HAS_MULTI_HOTEND diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index cd433b599a..28756e5b51 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -226,6 +226,7 @@ public: * There's no extra effect if you have a fixed Z probe. */ G29_TYPE GcodeSuite::G29() { + DEBUG_SECTION(log_G29, "G29", DEBUGGING(LEVELING)); // Leveling state is persistent when done manually with multiple G29 commands diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index e3e96a7960..5b16f938f2 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -64,6 +64,7 @@ inline void echo_not_entered(const char c) { SERIAL_CHAR(c); SERIAL_ECHOLNPGM(" * S5 Reset and disable mesh */ void GcodeSuite::G29() { + DEBUG_SECTION(log_G29, "G29", true); // G29 Q is also available if debugging diff --git a/Marlin/src/gcode/bedlevel/ubl/M421.cpp b/Marlin/src/gcode/bedlevel/ubl/M421.cpp index ff74f4c6f7..f1fd40010a 100644 --- a/Marlin/src/gcode/bedlevel/ubl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/ubl/M421.cpp @@ -66,7 +66,7 @@ void GcodeSuite::M421() { else if (!WITHIN(ij.x, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(ij.y, 0, GRID_MAX_POINTS_Y - 1)) SERIAL_ERROR_MSG(STR_ERR_MESH_XY); else { - float &zval = bedlevel.z_values[ij.x][ij.y]; // Altering this Mesh Point + float &zval = bedlevel.z_values[ij.x][ij.y]; // Altering this Mesh Point zval = hasN ? NAN : parser.value_linear_units() + (hasQ ? zval : 0); // N=NAN, Z=NEWVAL, or Q=ADDVAL TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ij.x, ij.y, zval)); // Ping ExtUI in case it's showing the mesh TERN_(DWIN_LCD_PROUI, DWIN_MeshUpdate(ij.x, ij.y, zval)); diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index d9dc3e6a52..5de15ef435 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -102,7 +102,7 @@ void print_signed_float(FSTR_P const prefix, const_float_t f) { } /** - * - Print the delta settings + * - Print the delta settings */ static void print_calibration_settings(const bool end_stops, const bool tower_angles) { SERIAL_ECHOPGM(".Height:", delta_height); @@ -128,7 +128,7 @@ static void print_calibration_settings(const bool end_stops, const bool tower_an } /** - * - Print the probe results + * - Print the probe results */ static void print_calibration_results(const float z_pt[NPP + 1], const bool tower_points, const bool opposite_points) { SERIAL_ECHOPGM(". "); @@ -152,7 +152,7 @@ static void print_calibration_results(const float z_pt[NPP + 1], const bool towe } /** - * - Calculate the standard deviation from the zero plane + * - Calculate the standard deviation from the zero plane */ static float std_dev_points(float z_pt[NPP + 1], const bool _0p_cal, const bool _1p_cal, const bool _4p_cal, const bool _4p_opp) { if (!_0p_cal) { @@ -170,7 +170,7 @@ static float std_dev_points(float z_pt[NPP + 1], const bool _0p_cal, const bool } /** - * - Probe a point + * - Probe a point */ static float calibration_probe(const xy_pos_t &xy, const bool stow, const bool probe_at_offset) { #if HAS_BED_PROBE @@ -182,7 +182,7 @@ static float calibration_probe(const xy_pos_t &xy, const bool stow, const bool p } /** - * - Probe a grid + * - Probe a grid */ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_points, const float dcr, const bool towers_set, const bool stow_after_each, const bool probe_at_offset) { const bool _0p_calibration = probe_points == 0, diff --git a/Marlin/src/gcode/calibrate/G34.cpp b/Marlin/src/gcode/calibrate/G34.cpp index 7ae1e7765c..9a0cb0054b 100644 --- a/Marlin/src/gcode/calibrate/G34.cpp +++ b/Marlin/src/gcode/calibrate/G34.cpp @@ -39,6 +39,23 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" +/** + * G34 - Align the ends of the X gantry. See https://youtu.be/3jAFQdTk8iw + * + * - The carriage moves to GANTRY_CALIBRATION_SAFE_POSITION, also called the “pounce” position. + * - If possible, the Z stepper current is reduced to the value specified by 'S' + * (or GANTRY_CALIBRATION_CURRENT) to prevent damage to steppers and other parts. + * The reduced current should be just high enough to move the Z axis when not blocked. + * - The Z axis is jogged past the Z limit, only as far as the specified Z distance + * (or GANTRY_CALIBRATION_EXTRA_HEIGHT) at the GANTRY_CALIBRATION_FEEDRATE. + * - The Z axis is moved back to the working area (also at GANTRY_CALIBRATION_FEEDRATE). + * - Stepper current is restored back to normal. + * - The machine is re-homed, according to GANTRY_CALIBRATION_COMMANDS_POST. + * + * Parameters: + * [S] - Current value to use for the raise move. (Default: GANTRY_CALIBRATION_CURRENT) + * [Z] - Extra distance past Z_MAX_POS to move the Z axis. (Default: GANTRY_CALIBRATION_EXTRA_HEIGHT) + */ void GcodeSuite::G34() { // Home before the alignment procedure diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 323a1e05ba..4255677032 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -79,6 +79,7 @@ * R Flag to recalculate points based on current probe offsets */ void GcodeSuite::G34() { + DEBUG_SECTION(log_G34, "G34", DEBUGGING(LEVELING)); if (DEBUGGING(LEVELING)) log_machine_info(); @@ -108,6 +109,7 @@ void GcodeSuite::G34() { } #if ENABLED(Z_STEPPER_AUTO_ALIGN) + do { // break out on error const int8_t z_auto_align_iterations = parser.intval('I', Z_STEPPER_ALIGN_ITERATIONS); diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp index 003a1cd69d..397459c630 100644 --- a/Marlin/src/gcode/calibrate/G76_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M871.cpp @@ -258,7 +258,7 @@ say_waiting_for_probe_heating(); SERIAL_ECHOLNPGM(" Bed:", target_bed, " Probe:", target_probe); - const millis_t probe_timeout_ms = millis() + SEC_TO_MS(900UL); + const millis_t probe_timeout_ms = millis() + MIN_TO_MS(15); while (thermalManager.degProbe() < target_probe) { if (report_temps(next_temp_report, probe_timeout_ms)) { SERIAL_ECHOLNPGM("!Probe heating timed out."); diff --git a/Marlin/src/gcode/calibrate/M666.cpp b/Marlin/src/gcode/calibrate/M666.cpp index 90fad1811c..dbee73f394 100644 --- a/Marlin/src/gcode/calibrate/M666.cpp +++ b/Marlin/src/gcode/calibrate/M666.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(DELTA) || HAS_EXTRA_ENDSTOPS +#if ANY(DELTA, HAS_EXTRA_ENDSTOPS) #include "../gcode.h" diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index c52a089569..de511d9e0e 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -25,7 +25,7 @@ #if ENABLED(PINS_DEBUGGING) #include "../gcode.h" -#include "../../MarlinCore.h" // for pin_is_protected +#include "../../MarlinCore.h" // for pin_is_protected, wait_for_user #include "../../pins/pinsDebug.h" #include "../../module/endstops.h" @@ -195,31 +195,30 @@ inline void servo_probe_test() { if (!blt) { // DEPLOY and STOW 4 times and see if the signal follows // Then it is a mechanical switch - uint8_t i = 0; SERIAL_ECHOLNPGM(". Deploy & stow 4 times"); - do { + for (uint8_t i = 0; i < 4; ++i) { servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][0]); // Deploy safe_delay(500); deploy_state = READ(PROBE_TEST_PIN); servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][1]); // Stow safe_delay(500); stow_state = READ(PROBE_TEST_PIN); - } while (++i < 4); + } if (probe_inverting != deploy_state) SERIAL_ECHOLNPGM("WARNING: INVERTING setting probably backwards."); if (deploy_state != stow_state) { SERIAL_ECHOLNPGM("= Mechanical Switch detected"); if (deploy_state) { - SERIAL_ECHOLNPGM(" DEPLOYED state: HIGH (logic 1)", - " STOWED (triggered) state: LOW (logic 0)"); + SERIAL_ECHOLNPGM(". DEPLOYED state: HIGH (logic 1)\n" + ". STOWED (triggered) state: LOW (logic 0)"); } else { - SERIAL_ECHOLNPGM(" DEPLOYED state: LOW (logic 0)", - " STOWED (triggered) state: HIGH (logic 1)"); + SERIAL_ECHOLNPGM(". DEPLOYED state: LOW (logic 0)\n" + ". STOWED (triggered) state: HIGH (logic 1)"); } #if ENABLED(BLTOUCH) - SERIAL_ECHOLNPGM("FAIL: BLTOUCH enabled - Set up this device as a Servo Probe with INVERTING set to 'true'."); + SERIAL_ECHOLNPGM("FAIL: Can't enable BLTOUCH. Check your settings."); #endif return; } diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index 5c924335f2..972f1713ff 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -37,6 +37,7 @@ * H - Specify micro-steps to use. Best guess if not supplied. * L - Desired layer height in current units. Nearest good heights are shown. */ + void GcodeSuite::M92() { const int8_t target_extruder = get_target_extruder_from_command(); diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp index 76fc335e25..053497c69c 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -71,7 +71,7 @@ void do_enable(const stepper_flags_t to_enable) { if (!shall_enable) return; // All specified axes already enabled? - ena_mask_t also_enabled = 0; // Track steppers enabled due to overlap + ena_mask_t also_enabled = 0; // Track steppers enabled due to overlap // Enable all flagged axes LOOP_NUM_AXES(a) { diff --git a/Marlin/src/gcode/control/M3-M5.cpp b/Marlin/src/gcode/control/M3-M5.cpp index 5d5d44e8bf..ee29fba871 100644 --- a/Marlin/src/gcode/control/M3-M5.cpp +++ b/Marlin/src/gcode/control/M3-M5.cpp @@ -32,21 +32,18 @@ * Laser: * M3 - Laser ON/Power (Ramped power) * M4 - Laser ON/Power (Ramped power) - * M5 - Set power output to 0 (leaving inline mode unchanged). * * M3I - Enable continuous inline power to be processed by the planner, with power * calculated and set in the planner blocks, processed inline during stepping. - * Within inline mode M3 S-Values will set the power for the next moves e.g. G1 X10 Y10 powers on with the last S-Value. + * In inline mode M3 S-Values will set the power for the next moves. + * (e.g., G1 X10 Y10 powers on with the last S-Value.) * M3I must be set before using planner-synced M3 inline S-Values (LASER_POWER_SYNC). * * M4I - Set dynamic mode which calculates laser power OCR based on the current feedrate. * - * M5I - Clear inline mode and set power to 0. - * * Spindle: * M3 - Spindle ON (Clockwise) * M4 - Spindle ON (Counter-clockwise) - * M5 - Spindle OFF * * Parameters: * S - Set power. S0 will turn the spindle/laser off. @@ -138,6 +135,13 @@ void GcodeSuite::M3_M4(const bool is_M4) { /** * M5 - Cutter OFF (when moves are complete) + * + * Laser: + * M5 - Set power output to 0 (leaving inline mode unchanged). + * M5I - Clear inline mode and set power to 0. + * + * Spindle: + * M5 - Spindle OFF */ void GcodeSuite::M5() { planner.synchronize(); diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp index 1b3a29d100..878d7113c9 100644 --- a/Marlin/src/gcode/control/M42.cpp +++ b/Marlin/src/gcode/control/M42.cpp @@ -43,7 +43,7 @@ void protected_pin_err() { } /** - * M42: Change pin status via GCode + * M42: Change pin status via G-Code * * P Pin number (LED if omitted) * For LPC1768 specify pin P1_02 as M42 P102, @@ -86,30 +86,8 @@ void GcodeSuite::M42() { #if HAS_FAN switch (pin) { - #if HAS_FAN0 - case FAN0_PIN: thermalManager.fan_speed[0] = pin_status; return; - #endif - #if HAS_FAN1 - case FAN1_PIN: thermalManager.fan_speed[1] = pin_status; return; - #endif - #if HAS_FAN2 - case FAN2_PIN: thermalManager.fan_speed[2] = pin_status; return; - #endif - #if HAS_FAN3 - case FAN3_PIN: thermalManager.fan_speed[3] = pin_status; return; - #endif - #if HAS_FAN4 - case FAN4_PIN: thermalManager.fan_speed[4] = pin_status; return; - #endif - #if HAS_FAN5 - case FAN5_PIN: thermalManager.fan_speed[5] = pin_status; return; - #endif - #if HAS_FAN6 - case FAN6_PIN: thermalManager.fan_speed[6] = pin_status; return; - #endif - #if HAS_FAN7 - case FAN7_PIN: thermalManager.fan_speed[7] = pin_status; return; - #endif + #define _CASE(N) case FAN##N##_PIN: thermalManager.fan_speed[N] = pin_status; return; + REPEAT(FAN_COUNT, _CASE) } #endif @@ -119,7 +97,7 @@ void GcodeSuite::M42() { } // An OUTPUT_OPEN_DRAIN should not be changed to normal OUTPUT (STM32) - // Use M42 Px M1/5 S0/1 to set the output type and then set value + // Use M42 Px T1/5 S0/1 to set the output type and then set value #ifndef OUTPUT_OPEN_DRAIN pinMode(pin, OUTPUT); #endif diff --git a/Marlin/src/gcode/control/T.cpp b/Marlin/src/gcode/control/T.cpp index 5e1579ec12..6a2027acff 100644 --- a/Marlin/src/gcode/control/T.cpp +++ b/Marlin/src/gcode/control/T.cpp @@ -41,8 +41,8 @@ * S1 Don't move the tool in XY after change * * For PRUSA_MMU2(S) and EXTENDABLE_EMU_MMU2(S) - * T[n] Gcode to extrude at least 38.10 mm at feedrate 19.02 mm/s must follow immediately to load to extruder wheels. - * T? Gcode to extrude shouldn't have to follow. Load to extruder wheels is done automatically. + * T[n] G-code to extrude at least 38.10 mm at feedrate 19.02 mm/s must follow immediately to load to extruder wheels. + * T? G-code to extrude shouldn't have to follow. Load to extruder wheels is done automatically. * Tx Same as T?, but nozzle doesn't have to be preheated. Tc requires a preheated nozzle to finish filament load. * Tc Load to nozzle after filament was prepared by Tc and nozzle is already heated. */ diff --git a/Marlin/src/gcode/feature/advance/M900.cpp b/Marlin/src/gcode/feature/advance/M900.cpp index 8c0da41801..ec295f4139 100644 --- a/Marlin/src/gcode/feature/advance/M900.cpp +++ b/Marlin/src/gcode/feature/advance/M900.cpp @@ -120,8 +120,7 @@ void GcodeSuite::M900() { EXTRUDER_LOOP() { const bool slot = TEST(lin_adv_slot, e); SERIAL_ECHOLNPGM("Advance T", e, " S", slot, " K", planner.extruder_advance_K[e], - "(S", !slot, " K", other_extruder_advance_K[e], ")"); - SERIAL_EOL(); + "(S", !slot, " K", other_extruder_advance_K[e], ")"); } #endif diff --git a/Marlin/src/gcode/feature/camera/M240.cpp b/Marlin/src/gcode/feature/camera/M240.cpp index f79e80bcc2..bb1d3f9eee 100644 --- a/Marlin/src/gcode/feature/camera/M240.cpp +++ b/Marlin/src/gcode/feature/camera/M240.cpp @@ -111,7 +111,7 @@ * B - Y offset to the return position * F - Override the XY movement feedrate * R - Retract/recover length (current units) - * S - Retract/recover feedrate (mm/m) + * S - Retract/recover feedrate (mm/min) * X - Move to X before triggering the shutter * Y - Move to Y before triggering the shutter * Z - Raise Z by a distance before triggering the shutter diff --git a/Marlin/src/gcode/feature/mixing/M163-M165.cpp b/Marlin/src/gcode/feature/mixing/M163-M165.cpp index a4cb64e7d6..f4ea52df0a 100644 --- a/Marlin/src/gcode/feature/mixing/M163-M165.cpp +++ b/Marlin/src/gcode/feature/mixing/M163-M165.cpp @@ -76,7 +76,7 @@ void GcodeSuite::M164() { * I[factor] Mix factor for extruder stepper 6 */ void GcodeSuite::M165() { - // Get mixing parameters from the GCode + // Get mixing parameters from the G-Code // The total "must" be 1.0 (but it will be normalized) // If no mix factors are given, the old mix is preserved const char mixing_codes[] = { LIST_N(MIXING_STEPPERS, 'A', 'B', 'C', 'D', 'H', 'I') }; diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp index 889709c045..0efcfbf208 100644 --- a/Marlin/src/gcode/feature/pause/G61.cpp +++ b/Marlin/src/gcode/feature/pause/G61.cpp @@ -71,7 +71,7 @@ void GcodeSuite::G61() { if (!TEST(saved_slots[slot >> 3], slot & 0x07)) return; // Apply any given feedrate over 0.0 - feedRate_t saved_feedrate = feedrate_mm_s; + REMEMBER(saved, feedrate_mm_s); const float fr = parser.linearval('F'); if (fr > 0.0) feedrate_mm_s = MMM_TO_MMS(fr); @@ -101,8 +101,6 @@ void GcodeSuite::G61() { } #endif } - - feedrate_mm_s = saved_feedrate; } #endif // SAVED_POSITIONS diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index 61786d51ad..a1765bfb43 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -30,6 +30,14 @@ /** * M122: Debug TMC drivers + * + * I - Flag to re-initialize stepper drivers with current settings. + * X, Y, Z, E - Flags to only report the specified axes. + * + * With TMC_DEBUG: + * V - Report raw register data. Refer to the datasheet to decipher the report. + * S - Flag to enable/disable continuous debug reporting. + * P - Interval between continuous debug reports, in milliseconds. */ void GcodeSuite::M122() { xyze_bool_t print_axis = ARRAY_N_1(LOGICAL_AXES, false); diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index b2cab13553..b949200ad7 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/Marlin/src/gcode/feature/trinamic/M906.cpp @@ -328,7 +328,6 @@ void GcodeSuite::M906_report(const bool forReplay/*=true*/) { say_M906(forReplay); SERIAL_ECHOLNPGM(" T7 E", stepperE7.getMilliamps()); #endif - SERIAL_EOL(); } #endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index b4b322895e..38f81c368a 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -166,7 +166,7 @@ int8_t GcodeSuite::get_target_e_stepper_from_command(const int8_t dval/*=-1*/) { } /** - * Set XYZ...E destination and feedrate from the current GCode command + * Set XYZ...E destination and feedrate from the current G-Code command * * - Set destination from included axis codes * - Set to current for missing axis codes @@ -472,7 +472,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #endif #if ENABLED(DEBUG_GCODE_PARSER) - case 800: parser.debug(); break; // G800: GCode Parser Test for G + case 800: parser.debug(); break; // G800: G-Code Parser Test for G #endif default: parser.unknown_command_warning(); break; @@ -671,6 +671,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 82: M82(); break; // M82: Set E axis normal mode (same as other axes) case 83: M83(); break; // M83: Set E axis relative mode #endif + case 18: case 84: M18_M84(); break; // M18/M84: Disable Steppers / Set Timeout case 85: M85(); break; // M85: Set inactivity stepper shutdown timeout case 92: M92(); break; // M92: Set the steps-per-unit for one or more axes @@ -950,7 +951,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 665: M665(); break; // M665: Set Kinematics parameters #endif - #if ENABLED(DELTA) || HAS_EXTRA_ENDSTOPS + #if ANY(DELTA, HAS_EXTRA_ENDSTOPS) case 666: M666(); break; // M666: Set delta or multiple endstop adjustment #endif @@ -1029,7 +1030,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { #endif #if ENABLED(DEBUG_GCODE_PARSER) - case 800: parser.debug(); break; // M800: GCode Parser Test for M + case 800: parser.debug(); break; // M800: G-Code Parser Test for M #endif #if ENABLED(GCODE_REPEAT_MARKERS) diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 7db66af038..440a02644b 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -454,7 +454,7 @@ public: */ enum MarlinBusyState : char { NOT_BUSY, // Not in a handler - IN_HANDLER, // Processing a GCode + IN_HANDLER, // Processing a G-Code IN_PROCESS, // Known to be blocking command input (as in G29) PAUSED_FOR_USER, // Blocking pending any input PAUSED_FOR_INPUT // Blocking pending text input (concept) diff --git a/Marlin/src/gcode/geometry/G92.cpp b/Marlin/src/gcode/geometry/G92.cpp index b36f21d3c0..dfe4170620 100644 --- a/Marlin/src/gcode/geometry/G92.cpp +++ b/Marlin/src/gcode/geometry/G92.cpp @@ -88,28 +88,28 @@ void GcodeSuite::G92() { case 0: LOOP_LOGICAL_AXES(i) { if (parser.seenval(AXIS_CHAR(i))) { - const float l = parser.value_axis_units((AxisEnum)i), // Given axis coordinate value, converted to millimeters + const float l = parser.value_axis_units((AxisEnum)i), // Given axis coordinate value, converted to millimeters v = TERN0(HAS_EXTRUDERS, i == E_AXIS) ? l : LOGICAL_TO_NATIVE(l, i), // Axis position in NATIVE space (applying the existing offset) - d = v - current_position[i]; // How much is the current axis position altered by? + d = v - current_position[i]; // How much is the current axis position altered by? if (!NEAR_ZERO(d)) { - #if HAS_POSITION_SHIFT && NONE(IS_SCARA, POLARGRAPH) // When using workspaces... + #if HAS_POSITION_SHIFT && NONE(IS_SCARA, POLARGRAPH) // When using workspaces... if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) { - position_shift[i] += d; // ...most axes offset the workspace... + position_shift[i] += d; // ...most axes offset the workspace... update_workspace_offset((AxisEnum)i); } else { #if HAS_EXTRUDERS sync_E = true; - current_position.e = v; // ...but E is set directly + current_position.e = v; // ...but E is set directly #endif } - #else // Without workspaces... + #else // Without workspaces... if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) sync_XYZE = true; else { TERN_(HAS_EXTRUDERS, sync_E = true); } - current_position[i] = v; // ...set Current Position directly (like Marlin 1.0) + current_position[i] = v; // ...set Current Position directly (like Marlin 1.0) #endif } } diff --git a/Marlin/src/gcode/geometry/M206_M428.cpp b/Marlin/src/gcode/geometry/M206_M428.cpp index 494b2115b8..b055f0e207 100644 --- a/Marlin/src/gcode/geometry/M206_M428.cpp +++ b/Marlin/src/gcode/geometry/M206_M428.cpp @@ -33,9 +33,7 @@ /** * M206: Set Additional Homing Offset (X Y Z). SCARA aliases T=X, P=Y * - * *** @thinkyhead: I recommend deprecating M206 for SCARA in favor of M665. - * *** M206 for SCARA will remain enabled in 1.1.x for compatibility. - * *** In the 2.0 release, it will simply be disabled by default. + * *** TODO: Deprecate M206 for SCARA in favor of M665. */ void GcodeSuite::M206() { if (!parser.seen_any()) return M206_report(); @@ -91,7 +89,7 @@ void GcodeSuite::M428() { diff[i] = -current_position[i]; if (!WITHIN(diff[i], -20, 20)) { SERIAL_ERROR_MSG(STR_ERR_M428_TOO_FAR); - LCD_ALERTMESSAGE_F("Err: Too far!"); + LCD_ALERTMESSAGE(MSG_ERR_M428_TOO_FAR); ERR_BUZZ(); return; } diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index cbd9a35288..bcc9f817f1 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -128,9 +128,7 @@ void GcodeSuite::M114() { #if ENABLED(M114_DETAIL) if (parser.seen_test('D')) { - #if DISABLED(M114_LEGACY) - planner.synchronize(); - #endif + IF_DISABLED(M114_LEGACY, planner.synchronize()); report_current_position(); report_current_position_detail(); return; @@ -143,9 +141,7 @@ void GcodeSuite::M114() { #endif #endif - #if ENABLED(M114_REALTIME) - if (parser.seen_test('R')) { report_real_position(); return; } - #endif + TERN_(M114_REALTIME, if (parser.seen_test('R')) return report_real_position()); TERN_(M114_LEGACY, planner.synchronize()); report_current_position_projected(); diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 0b42c9c7e6..4993964295 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -61,8 +61,12 @@ * M115: Capabilities string and extended capabilities report * If a capability is not reported, hosts should assume * the capability is not present. + * + * NOTE: Always make sure to add new capabilities to the RepRap Wiki + * at https://reprap.org/wiki/Firmware_Capabilities_Protocol */ void GcodeSuite::M115() { + SERIAL_ECHOPGM("FIRMWARE_NAME:Marlin" " " DETAILED_BUILD_VERSION " (" __DATE__ " " __TIME__ ")" " SOURCE_CODE_URL:" SOURCE_CODE_URL diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp index 90586e371f..ec50ad817c 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -21,7 +21,7 @@ */ /** - * parser.cpp - Parser for a GCode line, providing a parameter interface. + * parser.cpp - Parser for a G-Code line, providing a parameter interface. */ #include "parser.h" @@ -66,7 +66,7 @@ uint16_t GCodeParser::codenum; char *GCodeParser::command_args; // start of parameters #endif -// Create a global instance of the GCode parser singleton +// Create a global instance of the G-Code parser singleton GCodeParser parser; /** @@ -108,7 +108,7 @@ void GCodeParser::reset() { /** * Populate the command line state (command_letter, codenum, subcode, and string_arg) - * by parsing a single line of GCode. 58 bytes of SRAM are used to speed up seen/value. + * by parsing a single line of G-Code. 58 bytes of SRAM are used to speed up seen/value. */ void GCodeParser::parse(char *p) { @@ -229,7 +229,7 @@ void GCodeParser::parse(char *p) { } #endif - } break; + } break; #if ENABLED(GCODE_MOTION_MODES) @@ -311,7 +311,7 @@ void GCodeParser::parse(char *p) { #endif #if ENABLED(FASTER_GCODE_PARSER) - // Arguments MUST be uppercase for fast GCode parsing + // Arguments MUST be uppercase for fast G-Code parsing #define PARAM_OK(P) WITHIN((P), 'A', 'Z') #else #define PARAM_OK(P) true diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index c05d6f32c5..5d162c0a41 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -22,8 +22,8 @@ #pragma once /** - * parser.h - Parser for a GCode line, providing a parameter interface. - * Codes like M149 control the way the GCode parser behaves, + * parser.h - Parser for a G-Code line, providing a parameter interface. + * Codes like M149 control the way the G-Code parser behaves, * so settings for these codes are located in this class. */ @@ -43,7 +43,7 @@ #endif /** - * GCode parser + * G-Code parser * * - Parse a single G-code line for its letter, code, subcode, and parameters * - FASTER_GCODE_PARSER: @@ -68,7 +68,7 @@ private: public: - // Global states for GCode-level units features + // Global states for G-Code-level units features static bool volumetric_enabled; @@ -233,7 +233,7 @@ public: FORCE_INLINE static char* unescape_string(char* &src) { return src; } #endif - // Populate all fields by parsing a single line of GCode + // Populate all fields by parsing a single line of G-Code // This uses 54 bytes of SRAM to speed up seen/value static void parse(char * p); diff --git a/Marlin/src/gcode/probe/G30.cpp b/Marlin/src/gcode/probe/G30.cpp index fb62f93b6e..df9dc86c62 100644 --- a/Marlin/src/gcode/probe/G30.cpp +++ b/Marlin/src/gcode/probe/G30.cpp @@ -39,7 +39,7 @@ #endif /** - * G30: Do a single Z probe at the current XY + * G30: Do a single Z probe at the given XY (default: current) * * Parameters: * diff --git a/Marlin/src/gcode/probe/G38.cpp b/Marlin/src/gcode/probe/G38.cpp index 5b138fdaf6..1f22cc84ed 100644 --- a/Marlin/src/gcode/probe/G38.cpp +++ b/Marlin/src/gcode/probe/G38.cpp @@ -105,6 +105,7 @@ inline bool G38_run_probe() { * G38.5 - Probe away from workpiece, stop on contact break */ void GcodeSuite::G38(const int8_t subcode) { + // Get X Y Z E F get_destination_from_command(); diff --git a/Marlin/src/gcode/probe/M951.cpp b/Marlin/src/gcode/probe/M951.cpp index 7a06400e33..93feffdce9 100644 --- a/Marlin/src/gcode/probe/M951.cpp +++ b/Marlin/src/gcode/probe/M951.cpp @@ -46,7 +46,7 @@ void mpe_settings_init() { mpe_settings.parking_xpos[0] = pex[0]; // M951 L mpe_settings.parking_xpos[1] = pex[1]; // M951 R mpe_settings.grab_distance = PARKING_EXTRUDER_GRAB_DISTANCE; // M951 I - TERN_(HAS_HOME_OFFSET, set_home_offset(X_AXIS, mpe_settings.grab_distance * -1)); + TERN_(HAS_HOME_OFFSET, set_home_offset(X_AXIS, -mpe_settings.grab_distance)); mpe_settings.slow_feedrate = MMM_TO_MMS(MPE_SLOW_SPEED); // M951 J mpe_settings.fast_feedrate = MMM_TO_MMS(MPE_FAST_SPEED); // M951 H mpe_settings.travel_distance = MPE_TRAVEL_DISTANCE; // M951 D @@ -59,7 +59,7 @@ void GcodeSuite::M951() { if (parser.seenval('R')) mpe_settings.parking_xpos[1] = parser.value_linear_units(); if (parser.seenval('I')) { mpe_settings.grab_distance = parser.value_linear_units(); - TERN_(HAS_HOME_OFFSET, set_home_offset(X_AXIS, mpe_settings.grab_distance * -1)); + TERN_(HAS_HOME_OFFSET, set_home_offset(X_AXIS, -mpe_settings.grab_distance)); } if (parser.seenval('J')) mpe_settings.slow_feedrate = MMM_TO_MMS(parser.value_linear_units()); if (parser.seenval('H')) mpe_settings.fast_feedrate = MMM_TO_MMS(parser.value_linear_units()); diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 53c59ee305..cf34eb52fd 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -99,7 +99,11 @@ PGM_P GCodeQueue::injected_commands_P; // = nullptr */ char GCodeQueue::injected_commands[64]; // = { 0 } -void GCodeQueue::RingBuffer::commit_command(bool skip_ok +/** + * Commit the accumulated G-code command to the ring buffer, + * also setting its origin info. + */ +void GCodeQueue::RingBuffer::commit_command(const bool skip_ok OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind/*=-1*/) ) { commands[index_w].skip_ok = skip_ok; @@ -113,7 +117,7 @@ void GCodeQueue::RingBuffer::commit_command(bool skip_ok * Return true if the command was successfully added. * Return false for a full buffer, or if the 'command' is a comment. */ -bool GCodeQueue::RingBuffer::enqueue(const char *cmd, bool skip_ok/*=true*/ +bool GCodeQueue::RingBuffer::enqueue(const char *cmd, const bool skip_ok/*=true*/ OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind/*=-1*/) ) { if (*cmd == ';' || length >= BUFSIZE) return false; @@ -695,8 +699,8 @@ void GCodeQueue::advance() { void GCodeQueue::report_buffer_statistics() { SERIAL_ECHOLNPGM("D576" - " P:", planner.moves_free(), " ", -planner_buffer_underruns, " (", max_planner_buffer_empty_duration, ")" - " B:", BUFSIZE - ring_buffer.length, " ", -command_buffer_underruns, " (", max_command_buffer_empty_duration, ")" + " P:", planner.moves_free(), " ", planner_buffer_underruns, " (", max_planner_buffer_empty_duration, ")" + " B:", BUFSIZE - ring_buffer.length, " ", command_buffer_underruns, " (", max_command_buffer_empty_duration, ")" ); command_buffer_underruns = planner_buffer_underruns = 0; max_command_buffer_empty_duration = max_planner_buffer_empty_duration = 0; diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index c9c3095c08..e741b5c881 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -35,7 +35,7 @@ public: */ struct SerialState { /** - * GCode line number handling. Hosts may include line numbers when sending + * G-Code line number handling. Hosts may include line numbers when sending * commands to Marlin, and lines will be checked for sequentiality. * M110 N sets the current line number. */ @@ -48,7 +48,7 @@ public: static SerialState serial_state[NUM_SERIAL]; //!< Serial states for each serial port /** - * GCode Command Queue + * G-Code Command Queue * A simple (circular) ring buffer of BUFSIZE command strings. * * Commands are copied into this buffer by the command injectors @@ -79,12 +79,12 @@ public: void advance_pos(uint8_t &p, const int inc) { if (++p >= BUFSIZE) p = 0; length += inc; } - void commit_command(bool skip_ok - OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind = serial_index_t()) + void commit_command(const bool skip_ok + OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind=serial_index_t()) ); - bool enqueue(const char *cmd, bool skip_ok = true - OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind = serial_index_t()) + bool enqueue(const char *cmd, const bool skip_ok=true + OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind=serial_index_t()) ); void ok_to_send(); diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index c49909646e..a00ca61228 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -49,8 +49,6 @@ #if ENABLED(EXTENSIBLE_UI) #include "../../lcd/extui/ui_api.h" -#elif ENABLED(DWIN_LCD_PROUI) - #include "../../lcd/e3v2/proui/dwin.h" #endif #if ENABLED(HOST_ACTION_COMMANDS) diff --git a/Marlin/src/gcode/sd/M24_M25.cpp b/Marlin/src/gcode/sd/M24_M25.cpp index 7685a9fbd4..94fc45c7f9 100644 --- a/Marlin/src/gcode/sd/M24_M25.cpp +++ b/Marlin/src/gcode/sd/M24_M25.cpp @@ -70,7 +70,7 @@ void GcodeSuite::M24() { #endif if (card.isFileOpen()) { - card.startOrResumeFilePrinting(); // SD card will now be read for commands + card.startOrResumeFilePrinting(); // SD card will now be read for commands startOrResumeJob(); // Start (or resume) the print job timer TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); } @@ -101,9 +101,7 @@ void GcodeSuite::M25() { #else // Set initial pause flag to prevent more commands from landing in the queue while we try to pause - #if HAS_MEDIA - if (IS_SD_PRINTING()) card.pauseSDPrint(); - #endif + if (IS_SD_PRINTING()) card.pauseSDPrint(); #if ENABLED(POWER_LOSS_RECOVERY) && DISABLED(DGUS_LCD_UI_MKS) if (recovery.enabled) recovery.save(true); diff --git a/Marlin/src/gcode/temp/M106_M107.cpp b/Marlin/src/gcode/temp/M106_M107.cpp index ae517c977b..6ba64cd7ba 100644 --- a/Marlin/src/gcode/temp/M106_M107.cpp +++ b/Marlin/src/gcode/temp/M106_M107.cpp @@ -85,7 +85,7 @@ void GcodeSuite::M106() { if (!got_preset && parser.seenval('S')) speed = parser.value_ushort(); - TERN_(FOAMCUTTER_XYUV, speed *= 2.55); // Get command in % of max heat + TERN_(FOAMCUTTER_XYUV, speed *= 2.55f); // Get command in % of max heat // Set speed, with constraint thermalManager.set_fan_speed(pfan, speed); diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index 99f9388583..10145c952f 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -89,9 +89,7 @@ void GcodeSuite::M303() { } #endif - #if DISABLED(BUSY_WHILE_HEATING) - KEEPALIVE_STATE(NOT_BUSY); - #endif + IF_DISABLED(BUSY_WHILE_HEATING, KEEPALIVE_STATE(NOT_BUSY)); LCD_MESSAGE(MSG_PID_AUTOTUNE); thermalManager.PID_autotune(temp, hid, c, u); diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 4046935c06..60588bfd82 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -309,24 +309,22 @@ #define IS_ULTIPANEL 1 #endif -// TFT Compatibility +// TFT Legacy options masquerade as TFT_GENERIC #if ANY(FSMC_GRAPHICAL_TFT, SPI_GRAPHICAL_TFT, TFT_320x240, TFT_480x320, TFT_320x240_SPI, TFT_480x320_SPI, TFT_LVGL_UI_FSMC, TFT_LVGL_UI_SPI) #define IS_LEGACY_TFT 1 #define TFT_GENERIC -#endif - -#if ANY(FSMC_GRAPHICAL_TFT, TFT_320x240, TFT_480x320, TFT_LVGL_UI_FSMC) - #define TFT_INTERFACE_FSMC -#elif ANY(SPI_GRAPHICAL_TFT, TFT_320x240_SPI, TFT_480x320_SPI, TFT_LVGL_UI_SPI) - #define TFT_INTERFACE_SPI -#endif - -#if ANY(FSMC_GRAPHICAL_TFT, SPI_GRAPHICAL_TFT) - #define TFT_CLASSIC_UI -#elif ANY(TFT_320x240, TFT_480x320, TFT_320x240_SPI, TFT_480x320_SPI) - #define TFT_COLOR_UI -#elif ANY(TFT_LVGL_UI_FSMC, TFT_LVGL_UI_SPI) - #define TFT_LVGL_UI + #if ANY(FSMC_GRAPHICAL_TFT, TFT_320x240, TFT_480x320, TFT_LVGL_UI_FSMC) + #define TFT_INTERFACE_FSMC + #elif ANY(SPI_GRAPHICAL_TFT, TFT_320x240_SPI, TFT_480x320_SPI, TFT_LVGL_UI_SPI) + #define TFT_INTERFACE_SPI + #endif + #if ANY(FSMC_GRAPHICAL_TFT, SPI_GRAPHICAL_TFT) + #define TFT_CLASSIC_UI + #elif ANY(TFT_320x240, TFT_480x320, TFT_320x240_SPI, TFT_480x320_SPI) + #define TFT_COLOR_UI + #elif ANY(TFT_LVGL_UI_FSMC, TFT_LVGL_UI_SPI) + #define TFT_LVGL_UI + #endif #endif // FSMC/SPI TFT Panels (LVGL) @@ -1069,10 +1067,8 @@ * The BLTouch Probe emulates a servo probe * and uses "special" angles for its state. */ -#if ENABLED(BLTOUCH) - #ifndef Z_PROBE_SERVO_NR - #define Z_PROBE_SERVO_NR 0 - #endif +#if ENABLED(BLTOUCH) && !defined(Z_PROBE_SERVO_NR) + #define Z_PROBE_SERVO_NR 0 #endif /** diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index f7822603b4..0133a16a8e 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -456,7 +456,7 @@ #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1024 #endif - // mimic setting up the source TEMP_SENSOR + // Mimic setting up the source TEMP_SENSOR #if REDUNDANT_TEMP_MATCH(SOURCE, E0) #define TEMP_SENSOR_0_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN #define TEMP_SENSOR_0_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX @@ -479,11 +479,11 @@ #if (TEMP_SENSOR_IS_MAX_TC(0) && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_0) || (TEMP_SENSOR_IS_MAX_TC(1) && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_1) || (TEMP_SENSOR_IS_MAX_TC(2) && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_2) #if TEMP_SENSOR_REDUNDANT == -5 - #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_0/TEMP_SENSOR_1/TEMP_SENSOR_2 then TEMP_SENSOR_REDUNDANT must match." + #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_[0-2] then TEMP_SENSOR_REDUNDANT must match." #elif TEMP_SENSOR_REDUNDANT == -3 - #error "If MAX31855 Thermocouple (-3) is used for TEMP_SENSOR_0/TEMP_SENSOR_1/TEMP_SENSOR_2 then TEMP_SENSOR_REDUNDANT must match." + #error "If MAX31855 Thermocouple (-3) is used for TEMP_SENSOR_[0-2] then TEMP_SENSOR_REDUNDANT must match." #elif TEMP_SENSOR_REDUNDANT == -2 - #error "If MAX6675 Thermocouple (-2) is used for TEMP_SENSOR_0/TEMP_SENSOR_1/TEMP_SENSOR_2 then TEMP_SENSOR_REDUNDANT must match." + #error "If MAX6675 Thermocouple (-2) is used for TEMP_SENSOR_[0-2] then TEMP_SENSOR_REDUNDANT must match." #endif #endif #elif TEMP_SENSOR_REDUNDANT == -4 @@ -1201,7 +1201,8 @@ #endif /** - * LCD_SERIAL_PORT must be defined ahead of HAL.h + * LCD_SERIAL_PORT must be defined ahead of HAL.h and + * currently HAL.h must be included ahead of pins.h. */ #ifndef LCD_SERIAL_PORT #if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI || HAS_DGUS_LCD diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index e010aa448a..5c87daf2b6 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -555,7 +555,7 @@ #define REINIT_NOISY_LCD 1 // Have the LCD re-init on SD insertion #endif -#endif +#endif // SDSUPPORT /** * Power Supply @@ -1741,6 +1741,7 @@ #if ANY(SENSORLESS_HOMING, SENSORLESS_PROBING) #define USE_SENSORLESS 1 #endif + // Disable Z axis sensorless homing if a probe is used to home the Z axis #if HOMING_Z_WITH_PROBE #undef Z_STALL_SENSITIVITY @@ -1769,7 +1770,6 @@ #define X_SLAVE_ADDRESS 0 #endif #endif - #if AXIS_IS_TMC(X2) #if defined(X2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X2) #define X2_SENSORLESS 1 @@ -2432,7 +2432,7 @@ #define HAS_TEMP_ADC_REDUNDANT 1 #endif -#define HAS_TEMP(N) (TEMP_SENSOR_IS_MAX_TC(N) || ANY(HAS_TEMP_ADC_##N, TEMP_SENSOR_##N##_IS_DUMMY)) +#define HAS_TEMP(N) (TEMP_SENSOR_IS_MAX_TC(N) || HAS_TEMP_ADC_##N || TEMP_SENSOR_##N##_IS_DUMMY) #if HAS_HOTEND && HAS_TEMP(0) #define HAS_TEMP_HOTEND 1 #endif @@ -2747,11 +2747,8 @@ #define HAS_FAN 1 #endif -/** - * Part Cooling fan multipliexer - */ #if PIN_EXISTS(FANMUX0) - #define HAS_FANMUX 1 + #define HAS_FANMUX 1 // Part Cooling fan multipliexer #endif /** diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 1dd1a582c1..6f51ce741b 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -844,7 +844,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #endif /** - * Validate that the bed size fits + * Validate bed size */ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS) are too narrow to contain X_BED_SIZE."); #if HAS_Y_AXIS @@ -1009,6 +1009,9 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #endif #endif +/** + * Custom Event G-code + */ #if defined(EVENT_GCODE_SD_ABORT) && DISABLED(NOZZLE_PARK_FEATURE) static_assert(nullptr == strstr(EVENT_GCODE_SD_ABORT, "G27"), "NOZZLE_PARK_FEATURE is required to use G27 in EVENT_GCODE_SD_ABORT."); #endif @@ -1277,7 +1280,6 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #elif SWITCHING_NOZZLE_SERVO_NR == 3 && !PIN_EXISTS(SERVO3) #error "SERVO3_PIN must be defined for your SWITCHING_NOZZLE." #endif - #ifdef SWITCHING_NOZZLE_E1_SERVO_NR #if SWITCHING_NOZZLE_E1_SERVO_NR == SWITCHING_NOZZLE_SERVO_NR #error "SWITCHING_NOZZLE_E1_SERVO_NR must be different from SWITCHING_NOZZLE_SERVO_NR." @@ -1291,7 +1293,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #error "SERVO3_PIN must be defined for your SWITCHING_NOZZLE." #endif #endif -#endif +#endif // SWITCHING_NOZZLE /** * Single Stepper Dual Extruder with switching servo @@ -1323,7 +1325,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #error "SWITCHING_EXTRUDER_E23_SERVO_NR should be a different extruder from SWITCHING_EXTRUDER_SERVO_NR." #endif #endif -#endif +#endif // SWITCHING_EXTRUDER /** * Mixing Extruder requirements @@ -1538,8 +1540,8 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #error "To use BED_LIMIT_SWITCHING you must disable PIDTEMPBED." #endif -// Fan Kickstart -#if FAN_KICKSTART_TIME && defined(FAN_KICKSTART_POWER) && !WITHIN(FAN_KICKSTART_POWER, 64, 255) +// Fan Kickstart power +#if FAN_KICKSTART_TIME && !WITHIN(FAN_KICKSTART_POWER, 64, 255) #error "FAN_KICKSTART_POWER must be an integer from 64 to 255." #endif @@ -1998,7 +2000,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS * Allow only one bed leveling option to be defined */ #if MANY(AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL, MESH_BED_LEVELING) - #error "Select only one of: MESH_BED_LEVELING, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL." + #error "Select only one of: MESH_BED_LEVELING, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_UBL." #endif /** @@ -2080,7 +2082,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #elif !(ENABLED(MESH_BED_LEVELING) || HAS_ABL_NOT_UBL) #error "LCD_BED_LEVELING requires MESH_BED_LEVELING or AUTO_BED_LEVELING." #elif ENABLED(MESH_EDIT_MENU) && !HAS_MESH - #error "MESH_EDIT_MENU requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL." + #error "MESH_EDIT_MENU requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_UBL." #endif #endif @@ -3669,7 +3671,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE, "Movement bounds (X_MIN_POS, X_MAX_POS #undef U_ENDSTOP_INVERTING #undef V_ENDSTOP_INVERTING #undef W_ENDSTOP_INVERTING -#endif +#endif // SENSORLESS_HOMING // Sensorless probing requirements #if ENABLED(SENSORLESS_PROBING) @@ -4012,7 +4014,7 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #if ENABLED(DUAL_X_CARRIAGE) #error "DUAL_X_CARRIAGE requires both MIN_ and MAX_SOFTWARE_ENDSTOPS." #elif HAS_HOTEND_OFFSET - #error "MIN_ and MAX_SOFTWARE_ENDSTOPS are both required with offset hotends." + #error "Multi-hotends with offset requires both MIN_ and MAX_SOFTWARE_ENDSTOPS." #endif #endif @@ -4085,11 +4087,11 @@ static_assert(_PLUS_TEST(4), "HOMING_FEEDRATE_MM_M values must be positive."); #elif !(defined(SPEED_POWER_MIN) && defined(SPEED_POWER_MAX) && defined(SPEED_POWER_STARTUP)) #error "SPINDLE_LASER_USE_PWM equation constant(s) missing." #elif _PIN_CONFLICT(X_MIN) - #error "SPINDLE_LASER_USE_PWM pin conflicts with X_MIN_PIN." + #error "SPINDLE_LASER_PWM_PIN conflicts with X_MIN_PIN." #elif _PIN_CONFLICT(X_MAX) - #error "SPINDLE_LASER_USE_PWM pin conflicts with X_MAX_PIN." + #error "SPINDLE_LASER_PWM_PIN conflicts with X_MAX_PIN." #elif _PIN_CONFLICT(Z_STEP) - #error "SPINDLE_LASER_USE_PWM pin conflicts with Z_STEP_PIN." + #error "SPINDLE_LASER_PWM_PIN conflicts with Z_STEP_PIN." #elif _PIN_CONFLICT(CASE_LIGHT) #error "SPINDLE_LASER_PWM_PIN conflicts with CASE_LIGHT_PIN." #elif _PIN_CONFLICT(E0_AUTO_FAN) diff --git a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp index 48f5f97133..dd1ba06a78 100644 --- a/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp +++ b/Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp @@ -449,7 +449,6 @@ static const hd44780_charmap_t g_hd44780_charmap_device[] PROGMEM = { {IV('⭢'), 0xC7, 0}, {IV('⭣'), 0xC6, 0}, - {IV('⯆'), 0xF5, 0}, {IV('⯇'), 0xF7, 0}, // ⯅ {IV('⯈'), 0xF6, 0}, @@ -500,7 +499,6 @@ static const hd44780_charmap_t g_hd44780_charmap_device[] PROGMEM = { //{IV(''), 0x9E, 0}, //{IV(''), 0x9F, 0}, - {IV('¼'), 0xF0, 0}, // 00BC {IV('⅓'), 0xF1, 0}, {IV('½'), 0xF2, 0}, // 00BD @@ -1043,7 +1041,7 @@ int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) { * @param cb_read_byte : the callback function to read one byte from the utf8_str (from RAM or ROM) * @param max_length : the pixel length of the string allowed (or number of slots in HD44780) * - * @return the number of pixels advanced + * @return the number of characters emitted * * Draw a UTF-8 string */ diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index 364a60a47f..b8f6875d9a 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -81,7 +81,7 @@ #elif ENABLED(SR_LCD_2W_NL) // 2 wire Non-latching LCD SR from: - // https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection + // https://github.com/fmalpartida/New-LiquidCrystal/wiki/schematics#user-content-ShiftRegister_connection LCD_CLASS lcd(SR_DATA_PIN, SR_CLK_PIN #if PIN_EXISTS(SR_STROBE) @@ -758,6 +758,7 @@ void MarlinUI::draw_status_message(const bool blink) { } #if HAS_PRINT_PROGRESS + #define TPOFFSET (LCD_WIDTH - 1) static uint8_t timepos = TPOFFSET - 6; static char buffer[8]; @@ -774,6 +775,7 @@ void MarlinUI::draw_status_message(const bool blink) { } } #endif + #if ENABLED(SHOW_REMAINING_TIME) void MarlinUI::drawRemain() { if (printJobOngoing()) { @@ -785,6 +787,7 @@ void MarlinUI::draw_status_message(const bool blink) { } } #endif + #if ENABLED(SHOW_INTERACTION_TIME) void MarlinUI::drawInter() { const duration_t interactt = ui.interaction_time; @@ -796,6 +799,7 @@ void MarlinUI::draw_status_message(const bool blink) { } } #endif + #if ENABLED(SHOW_ELAPSED_TIME) void MarlinUI::drawElapsed() { if (printJobOngoing()) { @@ -807,6 +811,7 @@ void MarlinUI::draw_status_message(const bool blink) { } } #endif + #endif // HAS_PRINT_PROGRESS /** diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.h b/Marlin/src/lcd/HD44780/marlinui_HD44780.h index 62c0c76202..f9e6dd9595 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.h +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.h @@ -70,7 +70,7 @@ #elif ENABLED(SR_LCD_2W_NL) // 2 wire Non-latching LCD SR from: - // https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection + // https://github.com/fmalpartida/New-LiquidCrystal/wiki/schematics#user-content-ShiftRegister_connection #include #include #define LCD_CLASS LiquidCrystal_SR diff --git a/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp index e681ff0a91..c0b9975014 100644 --- a/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp @@ -446,7 +446,6 @@ static const TFTGLCD_charmap_t g_TFTGLCD_charmap_device[] PROGMEM = { {IV('⭢'), 0xC7, 0}, {IV('⭣'), 0xC6, 0}, - {IV('⯆'), 0xF5, 0}, {IV('⯇'), 0xF7, 0}, // ⯅ {IV('⯈'), 0xF6, 0}, @@ -1041,7 +1040,7 @@ int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) { * @param cb_read_byte : the callback function to read one byte from the utf8_str (from RAM or ROM) * @param max_length : the pixel length of the string allowed (or number of slots in HD44780) * - * @return the number of pixels advanced + * @return the number of characters emitted * * Draw a UTF-8 string */ diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp index f1969c61a9..77f9cb8a6a 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp @@ -596,8 +596,8 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const #endif // HAS_CUTTER - #if HAS_PRINT_PROGRESS // UNTESTED!!! + #define TPOFFSET (LCD_WIDTH - 1) static uint8_t timepos = TPOFFSET - 6; @@ -648,6 +648,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const } } #endif + #endif // HAS_PRINT_PROGRESS #if ENABLED(LCD_PROGRESS_BAR) diff --git a/Marlin/src/lcd/dogm/HAL_LCD_class_defines.h b/Marlin/src/lcd/dogm/HAL_LCD_class_defines.h index 28ca26134e..f07064ea71 100644 --- a/Marlin/src/lcd/dogm/HAL_LCD_class_defines.h +++ b/Marlin/src/lcd/dogm/HAL_LCD_class_defines.h @@ -31,12 +31,12 @@ extern u8g_dev_t u8g_dev_st7565_64128n_HAL_2x_hw_spi; class U8GLIB_64128N_2X_HAL : public U8GLIB { public: U8GLIB_64128N_2X_HAL() : U8GLIB() { } - U8GLIB_64128N_2X_HAL(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) { init(sck, mosi, cs, a0, reset); } - U8GLIB_64128N_2X_HAL(pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) { init(cs, a0, reset); } - void init(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) { + U8GLIB_64128N_2X_HAL(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset=U8G_PIN_NONE) { init(sck, mosi, cs, a0, reset); } + U8GLIB_64128N_2X_HAL(pin_t cs, pin_t a0, pin_t reset=U8G_PIN_NONE) { init(cs, a0, reset); } + void init(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_st7565_64128n_HAL_2x_sw_spi, (uint8_t)sck, (uint8_t)mosi, (uint8_t)cs, (uint8_t)a0, (uint8_t)reset); } - void init(pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) { + void init(pin_t cs, pin_t a0, pin_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_st7565_64128n_HAL_2x_hw_spi, (uint8_t)cs, (uint8_t)a0, (uint8_t)reset); } }; @@ -47,12 +47,12 @@ extern u8g_dev_t u8g_dev_st7920_128x64_HAL_4x_hw_spi; class U8GLIB_ST7920_128X64_4X_HAL : public U8GLIB { public: U8GLIB_ST7920_128X64_4X_HAL() : U8GLIB() { } - U8GLIB_ST7920_128X64_4X_HAL(pin_t sck, pin_t mosi, pin_t cs, pin_t reset = U8G_PIN_NONE) { init(sck, mosi, cs, reset); } - U8GLIB_ST7920_128X64_4X_HAL(pin_t cs, pin_t reset = U8G_PIN_NONE) { init(cs, reset); } - void init(pin_t sck, pin_t mosi, pin_t cs, pin_t reset = U8G_PIN_NONE) { + U8GLIB_ST7920_128X64_4X_HAL(pin_t sck, pin_t mosi, pin_t cs, pin_t reset=U8G_PIN_NONE) { init(sck, mosi, cs, reset); } + U8GLIB_ST7920_128X64_4X_HAL(pin_t cs, pin_t reset=U8G_PIN_NONE) { init(cs, reset); } + void init(pin_t sck, pin_t mosi, pin_t cs, pin_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_st7920_128x64_HAL_4x_sw_spi, (uint8_t)sck, (uint8_t)mosi, (uint8_t)cs, U8G_PIN_NONE, (uint8_t)reset); // a0 = U8G_PIN_NONE } - void init(pin_t cs, pin_t reset = U8G_PIN_NONE) { + void init(pin_t cs, pin_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_st7920_128x64_HAL_4x_hw_spi, (uint8_t)cs, U8G_PIN_NONE, (uint8_t)reset); // a0 = U8G_PIN_NONE } }; @@ -66,8 +66,8 @@ extern u8g_dev_t u8g_dev_st7920_128x64_rrd_sw_spi; class U8GLIB_ST7920_128X64_RRD : public U8GLIB { public: U8GLIB_ST7920_128X64_RRD() : U8GLIB() { } - U8GLIB_ST7920_128X64_RRD(pin_t sck, pin_t mosi, pin_t cs, pin_t reset = U8G_PIN_NONE) { init(sck, mosi, cs, reset); } - void init(pin_t sck, pin_t mosi, pin_t cs, pin_t reset = U8G_PIN_NONE) { + U8GLIB_ST7920_128X64_RRD(pin_t sck, pin_t mosi, pin_t cs, pin_t reset=U8G_PIN_NONE) { init(sck, mosi, cs, reset); } + void init(pin_t sck, pin_t mosi, pin_t cs, pin_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_st7920_128x64_rrd_sw_spi, (uint8_t)sck, (uint8_t)mosi, (uint8_t)cs, U8G_PIN_NONE, (uint8_t)reset); // a0 = U8G_PIN_NONE } }; @@ -99,22 +99,21 @@ extern u8g_dev_t u8g_dev_tft_320x240_upscale_from_128x64; class U8GLIB_TFT_320X240_UPSCALE_FROM_128X64 : public U8GLIB { public: U8GLIB_TFT_320X240_UPSCALE_FROM_128X64() : U8GLIB() { } - U8GLIB_TFT_320X240_UPSCALE_FROM_128X64(uint8_t cs, uint8_t rs, uint8_t reset = U8G_PIN_NONE) { init(cs, rs, reset); } - void init(uint8_t cs, uint8_t rs, uint8_t reset = U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_tft_320x240_upscale_from_128x64, cs, rs, reset); } + U8GLIB_TFT_320X240_UPSCALE_FROM_128X64(uint8_t cs, uint8_t rs, uint8_t reset=U8G_PIN_NONE) { init(cs, rs, reset); } + void init(uint8_t cs, uint8_t rs, uint8_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_tft_320x240_upscale_from_128x64, cs, rs, reset); } }; - extern u8g_dev_t u8g_dev_uc1701_mini12864_HAL_2x_sw_spi, u8g_dev_uc1701_mini12864_HAL_2x_hw_spi; class U8GLIB_MINI12864_2X_HAL : public U8GLIB { public: U8GLIB_MINI12864_2X_HAL() : U8GLIB() { } - U8GLIB_MINI12864_2X_HAL(uint8_t sck, uint8_t mosi, uint8_t cs, uint8_t a0, uint8_t reset = U8G_PIN_NONE) { init(sck, mosi, cs, a0, reset); } - U8GLIB_MINI12864_2X_HAL(uint8_t cs, uint8_t a0, uint8_t reset = U8G_PIN_NONE) { init(cs, a0, reset); } - void init(uint8_t sck, uint8_t mosi, uint8_t cs, uint8_t a0, uint8_t reset = U8G_PIN_NONE) { + U8GLIB_MINI12864_2X_HAL(uint8_t sck, uint8_t mosi, uint8_t cs, uint8_t a0, uint8_t reset=U8G_PIN_NONE) { init(sck, mosi, cs, a0, reset); } + U8GLIB_MINI12864_2X_HAL(uint8_t cs, uint8_t a0, uint8_t reset=U8G_PIN_NONE) { init(cs, a0, reset); } + void init(uint8_t sck, uint8_t mosi, uint8_t cs, uint8_t a0, uint8_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_uc1701_mini12864_HAL_2x_sw_spi, sck, mosi, cs, a0, reset); } - void init(uint8_t cs, uint8_t a0, uint8_t reset = U8G_PIN_NONE) { + void init(uint8_t cs, uint8_t a0, uint8_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_uc1701_mini12864_HAL_2x_hw_spi, cs, a0, reset); } }; @@ -125,12 +124,12 @@ extern u8g_dev_t u8g_dev_ssd1309_hw_spi; class U8GLIB_SSD1309_128X64_HAL : public U8GLIB { public: U8GLIB_SSD1309_128X64_HAL() : U8GLIB() { } - U8GLIB_SSD1309_128X64_HAL(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) { init(sck, mosi, cs, a0, reset); } - U8GLIB_SSD1309_128X64_HAL(pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) { init(cs, a0, reset); } - void init(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) { + U8GLIB_SSD1309_128X64_HAL(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset=U8G_PIN_NONE) { init(sck, mosi, cs, a0, reset); } + U8GLIB_SSD1309_128X64_HAL(pin_t cs, pin_t a0, pin_t reset=U8G_PIN_NONE) { init(cs, a0, reset); } + void init(pin_t sck, pin_t mosi, pin_t cs, pin_t a0, pin_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_ssd1309_sw_spi, (uint8_t)sck, (uint8_t)mosi, (uint8_t)cs, (uint8_t)a0, (uint8_t)reset); } - void init(pin_t cs, pin_t a0, pin_t reset = U8G_PIN_NONE) { + void init(pin_t cs, pin_t a0, pin_t reset=U8G_PIN_NONE) { U8GLIB::init(&u8g_dev_ssd1309_hw_spi, (uint8_t)cs, (uint8_t)a0, (uint8_t)reset); } }; diff --git a/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h b/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h index cfba12acff..6df6413158 100644 --- a/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h +++ b/Marlin/src/lcd/dogm/HAL_LCD_com_defines.h @@ -41,11 +41,9 @@ #define U8G_COM_HAL_HW_SPI_FN u8g_com_samd51_hw_spi_fn #define U8G_COM_ST7920_HAL_HW_SPI u8g_com_samd51_st7920_hw_spi_fn - #elif defined(__SAMD21__) uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); - #define U8G_COM_ST7920_HAL_HW_SPI u8g_com_samd21_st7920_hw_spi_fn #elif defined(__STM32F1__) diff --git a/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h b/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h index 524ff18778..c81c63f2ed 100644 --- a/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h +++ b/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h @@ -22,15 +22,15 @@ #pragma once /** - Fontname: -Misc-Fixed-Medium-R-Normal--9-90-75-75-C-60-ISO10646-1 - Copyright: Public domain font. Share and enjoy. - Capital A Height: 6, '1' Height: 6 - Calculated Max Values w= 6 h= 9 x= 5 y= 5 dx= 6 dy= 0 ascent= 7 len= 9 - Font Bounding box w= 6 h= 9 x= 0 y=-2 - Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 - Pure Font ascent = 6 descent=-2 - X Font ascent = 6 descent=-2 - Max Font ascent = 7 descent=-2 + * Fontname: -Misc-Fixed-Medium-R-Normal--9-90-75-75-C-60-ISO10646-1 + * Copyright: Public domain font. Share and enjoy. + * Capital A Height: 6, '1' Height: 6 + * Calculated Max Values w= 6 h= 9 x= 5 y= 5 dx= 6 dy= 0 ascent= 7 len= 9 + * Font Bounding box w= 6 h= 9 x= 0 y=-2 + * Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 + * Pure Font ascent = 6 descent=-2 + * X Font ascent = 6 descent=-2 + * Max Font ascent = 7 descent=-2 */ #include const u8g_fntpgm_uint8_t u8g_font_6x9[2434] U8G_FONT_SECTION(".progmem.u8g_font_6x9") = { @@ -186,4 +186,5 @@ const u8g_fntpgm_uint8_t u8g_font_6x9[2434] U8G_FONT_SECTION(".progmem.u8g_font_ 0x00,0x50,0x00,0x90,0x90,0x90,0x70,0x04,0x09,0x09,0x06,0x01,0xFE,0x20,0x40,0x00, 0x90,0x90,0x90,0x70,0x90,0x60,0x04,0x08,0x08,0x06,0x01,0xFE,0x80,0x80,0xE0,0x90, 0x90,0xE0,0x80,0x80,0x04,0x08,0x08,0x06,0x01,0xFE,0x50,0x00,0x90,0x90,0x90,0x70, - 0x90,0x60}; + 0x90,0x60 +}; diff --git a/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h b/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h index 6f55d3bc3d..1ebe9884c0 100644 --- a/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h +++ b/Marlin/src/lcd/dogm/fontdata/fontdata_ISO10646_1.h @@ -25,17 +25,17 @@ #if defined(__AVR__) && ENABLED(NOT_EXTENDED_ISO10646_1_5X7) // reduced font (only symbols 1 - 127) - saves about 1278 bytes of FLASH -/* - Fontname: -Marlin6x12-Fixed-Medium-R-SemiCondensed--12-90-100-100-C-111-ISO10646-1 - Copyright: Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1 - Capital A Height: 7, '1' Height: 7 - Calculated Max Values w= 7 h=10 x= 5 y= 5 dx= 7 dy= 0 ascent= 8 len=10 - Font Bounding box w=12 h=15 x= 0 y=-2 - Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 - Pure Font ascent = 7 descent=-2 - X Font ascent = 8 descent=-2 - Max Font ascent = 8 descent=-2 -*/ +/** + * Fontname: -Marlin6x12-Fixed-Medium-R-SemiCondensed--12-90-100-100-C-111-ISO10646-1 + * Copyright: Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1 + * Capital A Height: 7, '1' Height: 7 + * Calculated Max Values w= 7 h=10 x= 5 y= 5 dx= 7 dy= 0 ascent= 8 len=10 + * Font Bounding box w=12 h=15 x= 0 y=-2 + * Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 + * Pure Font ascent = 7 descent=-2 + * X Font ascent = 8 descent=-2 + * Max Font ascent = 8 descent=-2 + */ const u8g_fntpgm_uint8_t ISO10646_1_5x7[1324] U8G_FONT_SECTION("ISO10646_1_5x7") = { 0x00,0x0C,0x0F,0x00,0xFE,0x07,0x02,0x25,0x03,0xBB,0x01,0x7F,0xFE,0x08,0xFE,0x08, 0xFE,0x05,0x08,0x08,0x06,0x00,0x00,0x40,0xF0,0xC8,0x88,0x88,0x98,0x78,0x10,0x05, @@ -123,17 +123,17 @@ const u8g_fntpgm_uint8_t ISO10646_1_5x7[1324] U8G_FONT_SECTION("ISO10646_1_5x7") #else // extended (original) font (symbols 1 - 255) -/* - Fontname: -Marlin6x12-Fixed-Medium-R-SemiCondensed--12-90-100-100-C-111-ISO10646-1 - Copyright: Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1 - Capital A Height: 7, '1' Height: 7 - Calculated Max Values w= 7 h=10 x= 5 y= 7 dx= 7 dy= 0 ascent=10 len=10 - Font Bounding box w=12 h=15 x= 0 y=-2 - Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 - Pure Font ascent = 7 descent=-2 - X Font ascent = 8 descent=-2 - Max Font ascent =10 descent=-2 -*/ +/** + * Fontname: -Marlin6x12-Fixed-Medium-R-SemiCondensed--12-90-100-100-C-111-ISO10646-1 + * Copyright: Public domain terminal emulator font. Share and enjoy. original font -Misc-Fixed-Medium-R-SemiCondensed--12-110-75-75-C-60-ISO10646-1 + * Capital A Height: 7, '1' Height: 7 + * Calculated Max Values w= 7 h=10 x= 5 y= 7 dx= 7 dy= 0 ascent=10 len=10 + * Font Bounding box w=12 h=15 x= 0 y=-2 + * Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 + * Pure Font ascent = 7 descent=-2 + * X Font ascent = 8 descent=-2 + * Max Font ascent =10 descent=-2 + */ const u8g_fntpgm_uint8_t ISO10646_1_5x7[2647] U8G_FONT_SECTION("ISO10646_1_5x7") = { 0x00,0x0C,0x0F,0x00,0xFE,0x07,0x02,0x25,0x03,0xBB,0x01,0xFF,0xFE,0x0A,0xFE,0x08, 0xFE,0x05,0x08,0x08,0x06,0x00,0x00,0x40,0xF0,0xC8,0x88,0x88,0x98,0x78,0x10,0x05, diff --git a/Marlin/src/lcd/dogm/fontdata/langdata.h b/Marlin/src/lcd/dogm/fontdata/langdata.h index 746a3bd0b4..a9e1b6cd94 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/lcd/dogm/lcdprint_u8g.cpp b/Marlin/src/lcd/dogm/lcdprint_u8g.cpp index 74a49b0950..9a69ceefa8 100644 --- a/Marlin/src/lcd/dogm/lcdprint_u8g.cpp +++ b/Marlin/src/lcd/dogm/lcdprint_u8g.cpp @@ -27,7 +27,7 @@ void lcd_moveto(const lcd_uint_t col, const lcd_uint_t row) { u8g.setPrintPos(co void lcd_put_int(const int i) { u8g.print(i); } // return < 0 on error -// return the advanced pixels +// return the number of pixels advanced int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) { if (c < 256) { u8g.print((char)c); @@ -39,6 +39,9 @@ int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) { return ret; } +/** + * @return output width in pixels + */ int lcd_put_u8str_max(const char * utf8_str, const pixel_len_t max_length) { u8g_uint_t x = u8g.getPrintCol(), y = u8g.getPrintRow(), ret = uxg_DrawUtf8Str(u8g.getU8g(), x, y, utf8_str, max_length); @@ -46,6 +49,9 @@ int lcd_put_u8str_max(const char * utf8_str, const pixel_len_t max_length) { return ret; } +/** + * @return output width in pixels + */ int lcd_put_u8str_max_P(PGM_P utf8_pstr, const pixel_len_t max_length) { u8g_uint_t x = u8g.getPrintCol(), y = u8g.getPrintRow(), ret = uxg_DrawUtf8StrP(u8g.getU8g(), x, y, utf8_pstr, max_length); diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 3d905bdf15..6538fd8c64 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -234,13 +234,8 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co const celsius_t temp = thermalManager.wholeDegHotend(heater_id), target = thermalManager.degTargetHotend(heater_id); - #if DISABLED(STATUS_HOTEND_ANIM) - #define STATIC_HOTEND true - #define HOTEND_DOT isHeat - #else - #define STATIC_HOTEND false - #define HOTEND_DOT false - #endif + #define STATIC_HOTEND DISABLED(STATUS_HOTEND_ANIM) + #define HOTEND_DOT TERN(STATUS_HOTEND_ANIM, false, isHeat) #if ENABLED(STATUS_HOTEND_NUMBERLESS) #define OFF_BMP(N) TERN(STATUS_HOTEND_INVERTED, status_hotend_b_bmp, status_hotend_a_bmp) @@ -333,13 +328,8 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co const bool isHeat = BED_ALT(); #endif - #if DISABLED(STATUS_BED_ANIM) - #define STATIC_BED true - #define BED_DOT isHeat - #else - #define STATIC_BED false - #define BED_DOT false - #endif + #define STATIC_BED DISABLED(STATUS_BED_ANIM) + #define BED_DOT TERN(STATUS_BED_ANIM, false, isHeat) if (PAGE_CONTAINS(STATUS_HEATERS_Y, STATUS_HEATERS_BOT)) { @@ -472,19 +462,23 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const #if ENABLED(SHOW_REMAINING_TIME) void MarlinUI::drawRemain() { if (printJobOngoing() && get_remaining_time() != 0) - prepare_time_string(get_remaining_time(), 'R'); } + prepare_time_string(get_remaining_time(), 'R'); + } #endif #if ENABLED(SHOW_INTERACTION_TIME) void MarlinUI::drawInter() { if (printingIsActive() && interaction_time) - prepare_time_string(interaction_time, 'C'); } + prepare_time_string(interaction_time, 'C'); + } #endif #if ENABLED(SHOW_ELAPSED_TIME) void MarlinUI::drawElapsed() { if (printJobOngoing()) - prepare_time_string(print_job_timer.duration(), 'E'); } + prepare_time_string(print_job_timer.duration(), 'E'); + } #endif -#endif // HAS_PRINT_PROGRESS + +#endif // HAS_EXTRA_PROGRESS /** * Draw the Status Screen for a 128x64 DOGM (U8glib) display. @@ -826,9 +820,7 @@ void MarlinUI::draw_status_screen() { #endif - #if HAS_Z_AXIS - _draw_axis_value(Z_AXIS, zstring, blink); - #endif + TERN_(HAS_Z_AXIS, _draw_axis_value(Z_AXIS, zstring, blink)); #if NONE(XYZ_NO_FRAME, XYZ_HOLLOW_FRAME) u8g.setColorIndex(1); // black on white diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index 400f632a0c..d114fdb418 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -690,7 +690,7 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { void ST7920_Lite_Status_Screen::drawPercent() { #define LSHIFT TERN(HOTENDS == 1, 0, 1) const uint8_t progress = ui.get_progress_percent(); - memset(&screenstr, 0x20, 8); // fill with spaces to avoid artifacts + memset(&screenstr, ' ', 8); // fill with spaces to avoid artifacts if (progress){ memcpy(&screenstr[2 - LSHIFT], \ TERN(PRINT_PROGRESS_SHOW_DECIMALS, permyriadtostr4(ui.get_progress_permyriad()), ui8tostr3rj(progress)), \ @@ -705,7 +705,7 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { void ST7920_Lite_Status_Screen::drawRemain() { const duration_t remaint = TERN0(SET_REMAINING_TIME, ui.get_remaining_time()); if (printJobOngoing() && remaint.value) { - draw_progress_string( PPOS, prepare_time_string(remaint, 'R')); + draw_progress_string(PPOS, prepare_time_string(remaint, 'R')); } } #endif @@ -714,7 +714,7 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { void ST7920_Lite_Status_Screen::drawInter() { const duration_t interactt = ui.interaction_time; if (printingIsActive() && interactt.value) { - draw_progress_string( PPOS, prepare_time_string(interactt, 'C')); + draw_progress_string(PPOS, prepare_time_string(interactt, 'C')); } } #endif @@ -723,7 +723,7 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { void ST7920_Lite_Status_Screen::drawElapsed() { if (printJobOngoing()) { const duration_t elapsedt = print_job_timer.duration(); - draw_progress_string( PPOS, prepare_time_string(elapsedt, 'E')); + draw_progress_string(PPOS, prepare_time_string(elapsedt, 'E')); } } #endif diff --git a/Marlin/src/lcd/dogm/u8g_dev_ssd1306_sh1106_128x64_I2C.cpp b/Marlin/src/lcd/dogm/u8g_dev_ssd1306_sh1106_128x64_I2C.cpp index b3e579e6a4..5865bb1187 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_ssd1306_sh1106_128x64_I2C.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_ssd1306_sh1106_128x64_I2C.cpp @@ -230,12 +230,10 @@ uint8_t u8g_dev_ssd1306_128x64_2x_2_wire_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t return u8g_dev_pb16v1_base_fn(u8g, dev, msg, arg); } - uint8_t u8g_dev_ssd1306_128x64_2x_i2c_2_wire_buf[WIDTH*2] U8G_NOCOMMON ; u8g_pb_t u8g_dev_ssd1306_128x64_2x_i2c_2_wire_pb = { {16, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_ssd1306_128x64_2x_i2c_2_wire_buf}; u8g_dev_t u8g_dev_ssd1306_128x64_2x_i2c_2_wire = { u8g_dev_ssd1306_128x64_2x_2_wire_fn, &u8g_dev_ssd1306_128x64_2x_i2c_2_wire_pb, U8G_COM_SSD_I2C_HAL }; - ///////////////////////////////////////////////////////////////////////////////////////////// // This routine adds the instruction byte in between the command bytes. This makes the init diff --git a/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp b/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp index 63e7b2e2b8..6c7066179e 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_st7565_64128n_HAL.cpp @@ -234,7 +234,6 @@ uint8_t u8g_dev_st7565_64128n_HAL_2x_buf[WIDTH*2] U8G_NOCOMMON ; u8g_pb_t u8g_dev_st7565_64128n_HAL_2x_pb = { {16, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_st7565_64128n_HAL_2x_buf}; u8g_dev_t u8g_dev_st7565_64128n_HAL_2x_sw_spi = { u8g_dev_st7565_64128n_HAL_2x_fn, &u8g_dev_st7565_64128n_HAL_2x_pb, U8G_COM_HAL_SW_SPI_FN }; - U8G_PB_DEV(u8g_dev_st7565_64128n_HAL_hw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_st7565_64128n_HAL_fn, U8G_COM_HAL_HW_SPI_FN); u8g_dev_t u8g_dev_st7565_64128n_HAL_2x_hw_spi = { u8g_dev_st7565_64128n_HAL_2x_fn, &u8g_dev_st7565_64128n_HAL_2x_pb, U8G_COM_HAL_HW_SPI_FN }; diff --git a/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp b/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp index 41bc99fedd..2372bd4880 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp @@ -88,8 +88,8 @@ TFT_IO tftio; #define X_HI (UPSCALE(TFT_PIXEL_OFFSET_X, WIDTH) - 1) #define Y_HI (UPSCALE(TFT_PIXEL_OFFSET_Y, HEIGHT) - 1) -// 16 bit color generator: https://ee-programming-notepad.blogspot.com/2016/10/16-bit-color-generator-picker.html -// RGB565 color picker: https://trolsoft.ru/en/articles/rgb565-color-picker +// RGB565 color picker: https://embeddednotepad.com/page/rgb565-color-picker +// Hex code to color name: https://www.color-name.com/ #define COLOR_BLACK 0x0000 // #000000 #define COLOR_WHITE 0xFFFF // #FFFFFF @@ -136,8 +136,8 @@ TFT_IO tftio; #define TFT_BTOKMENU_COLOR COLOR_RED #endif -static void setWindow(u8g_t *u8g, u8g_dev_t *dev, uint16_t Xmin, uint16_t Ymin, uint16_t Xmax, uint16_t Ymax) { - tftio.set_window(Xmin, Ymin, Xmax, Ymax); +static void setWindow(u8g_t *u8g, u8g_dev_t *dev, uint16_t xMin, uint16_t yMin, uint16_t xMax, uint16_t yMax) { + tftio.set_window(xMin, yMin, xMax, yMax); } #if HAS_TOUCH_BUTTONS @@ -556,4 +556,4 @@ U8G_PB_DEV(u8g_dev_tft_320x240_upscale_from_128x64, WIDTH, HEIGHT, PAGE_HEIGHT, #endif // TOUCH_SCREEN_CALIBRATION -#endif // HAS_MARLINUI_U8GLIB && (FSMC_CS_PIN || HAS_SPI_GRAPHICAL_TFT) +#endif // HAS_MARLINUI_U8GLIB && (FSMC_CS_PIN || HAS_SPI_GRAPHICAL_TFT || HAS_LTDC_GRAPHICAL_TFT) diff --git a/Marlin/src/lcd/dogm/u8g_fontutf8.cpp b/Marlin/src/lcd/dogm/u8g_fontutf8.cpp index e9d1535096..ce0e77a598 100644 --- a/Marlin/src/lcd/dogm/u8g_fontutf8.cpp +++ b/Marlin/src/lcd/dogm/u8g_fontutf8.cpp @@ -121,8 +121,8 @@ static font_group_t g_fontgroup_root = { nullptr, 0 }; */ static inline bool uxg_Utf8FontIsInited() { return flag_fontgroup_was_inited; } -int uxg_SetUtf8Fonts (const uxg_fontinfo_t * fntinfo, int number) { - flag_fontgroup_was_inited = 1; +int uxg_SetUtf8Fonts(const uxg_fontinfo_t *fntinfo, int number) { + flag_fontgroup_was_inited = true; return fontgroup_init(&g_fontgroup_root, fntinfo, number); } diff --git a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp index e844eee251..5578997669 100644 --- a/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp +++ b/Marlin/src/lcd/dogm/ultralcd_st7920_u8glib_rrd_AVR.cpp @@ -20,8 +20,8 @@ * */ -// NOTE - the HAL version of the rrd device uses a generic ST7920 device. See the -// file u8g_dev_st7920_128x64_HAL.cpp for the HAL version. +// NOTE - the HAL version of the rrd device uses a generic ST7920 device. +// See u8g_dev_st7920_128x64_HAL.cpp for the HAL version. #include "../../inc/MarlinConfigPre.h" diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.h b/Marlin/src/lcd/e3v2/common/dwin_api.h index dc97ef2723..3ef20f076d 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.h +++ b/Marlin/src/lcd/e3v2/common/dwin_api.h @@ -162,7 +162,6 @@ inline void DWIN_Draw_Box(uint8_t mode, uint16_t color, uint16_t xStart, uint16_ void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis, uint16_t color, uint16_t xStart, uint16_t yStart, uint16_t xEnd, uint16_t yEnd); - /*---------------------------------------- Text related functions ----------------------------------------*/ // Draw a string diff --git a/Marlin/src/lcd/e3v2/common/dwin_color.h b/Marlin/src/lcd/e3v2/common/dwin_color.h index d327f21a93..ad01fb0912 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_color.h +++ b/Marlin/src/lcd/e3v2/common/dwin_color.h @@ -22,7 +22,7 @@ #pragma once // Extended and default UI Colors -#define RGB(R,G,B) (R << 11) | (G << 5) | (B) // R,B: 0..31; G: 0..63 +#define RGB(R,G,B) (R << 11) | (G << 5) | (B) // R: 0..31, G: 0..63, B: 0..31 #define GetRColor(color) ((color >> 11) & 0x1F) #define GetGColor(color) ((color >> 5) & 0x3F) #define GetBColor(color) ((color >> 0) & 0x1F) diff --git a/Marlin/src/lcd/e3v2/common/encoder.cpp b/Marlin/src/lcd/e3v2/common/encoder.cpp index 5081e27690..ebcca26c48 100644 --- a/Marlin/src/lcd/e3v2/common/encoder.cpp +++ b/Marlin/src/lcd/e3v2/common/encoder.cpp @@ -164,9 +164,9 @@ EncoderState Encoder_ReceiveAnalyze() { // LED light operation void LED_Action() { - LED_Control(RGB_SCALE_WARM_WHITE,0x0F); + LED_Control(RGB_SCALE_WARM_WHITE, 0x0F); delay(30); - LED_Control(RGB_SCALE_WARM_WHITE,0x00); + LED_Control(RGB_SCALE_WARM_WHITE, 0x00); } // LED initialization diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index e27e0dac34..90c8a39e06 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -1038,7 +1038,9 @@ void CrealityDWINClass::Update_Status_Bar(const bool refresh/*=false*/) { } } -/* Menu Item Config */ +// +// Menu Item Config +// void CrealityDWINClass::Menu_Item_Handler(const uint8_t menu, const uint8_t item, bool draw/*=true*/) { const uint8_t row = item - scrollpos; @@ -3908,7 +3910,6 @@ void CrealityDWINClass::Menu_Item_Handler(const uint8_t menu, const uint8_t item } break; - #define _PREHEAT_HOTEND_CASE(N) \ case PREHEATHOTEND_##N: \ if (draw) Draw_Menu_Item(row, ICON_Temperature, F(PREHEAT_## N ##_LABEL)); \ @@ -4154,7 +4155,7 @@ void CrealityDWINClass::Menu_Control() { if (encoder_diffState == ENCODER_DIFF_CW && selection < Get_Menu_Size(active_menu)) { DWIN_Draw_Rectangle(1, Color_Bg_Black, 0, MBASE(selection - scrollpos) - 18, 14, MBASE(selection - scrollpos) + 33); selection++; // Select Down - if (selection > scrollpos+MROWS) { + if (selection > scrollpos + MROWS) { scrollpos++; DWIN_Frame_AreaMove(1, 2, MLINE, Color_Bg_Black, 0, 31, DWIN_WIDTH, 349); Menu_Item_Handler(active_menu, selection); @@ -4580,7 +4581,9 @@ void CrealityDWINClass::Confirm_Control() { DWIN_UpdateLCD(); } -/* In-Menu Value Modification */ +// +// In-Menu Value Modification +// void CrealityDWINClass::Setup_Value(const_float_t value, const_float_t min, const_float_t max, const_float_t unit, const uint8_t type) { if (TERN0(HAS_HOTEND, valuepointer == &thermalManager.temp_hotend[0].pid.Ki) || TERN0(HAS_HEATED_BED, valuepointer == &thermalManager.temp_bed.pid.Ki)) @@ -4639,7 +4642,9 @@ void CrealityDWINClass::Modify_Option(const uint8_t value, const char * const * Draw_Option(value, options, selection - scrollpos, true); } -/* Main Functions */ +// +// Main Functions +// void CrealityDWINClass::Update_Status(const char * const text) { if (strncmp_P(text, PSTR(""), 3) == 0) { diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h index 686b1aa2b1..ed79c45b1f 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h +++ b/Marlin/src/lcd/e3v2/marlinui/dwin_string.h @@ -525,7 +525,6 @@ const dwin_charmap_t g_dwin_charmap_device[] PROGMEM = { {IV('⭢'), 0xC7, 0}, {IV('⭣'), 0xC6, 0}, - {IV('⯆'), 0xF5, 0}, {IV('⯇'), 0xF7, 0}, // ⯅ {IV('⯈'), 0xF6, 0}, @@ -576,7 +575,6 @@ const dwin_charmap_t g_dwin_charmap_device[] PROGMEM = { //{IV(''), 0x9E, 0}, //{IV(''), 0x9F, 0}, - {IV('¼'), 0xF0, 0}, // 00BC {IV('⅓'), 0xF1, 0}, {IV('½'), 0xF2, 0}, // 00BD diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp index 48e07cc207..a675130a1f 100644 --- a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp +++ b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp @@ -89,9 +89,10 @@ char cmd[MAX_CMD_SIZE+16], str_1[16], str_2[16], str_3[16]; struct linear_fit_data lsf_results; incremental_LSF_reset(&lsf_results); GRID_LOOP(x, y) { - if (!isnan(bedlevel.z_values[x][y])) { + const float z = bedlevel.z_values[x][y]; + if (!isnan(z)) { xy_pos_t rpos = { bedlevel.get_mesh_x(x), bedlevel.get_mesh_y(y) }; - incremental_LSF(&lsf_results, rpos, bedlevel.z_values[x][y]); + incremental_LSF(&lsf_results, rpos, z); } } diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h index 6e642f030c..f307bd16e6 100644 --- a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h +++ b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h @@ -1,4 +1,4 @@ -/* +/** * Marlin 3D Printer Firmware * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index eb2f7fb53a..b45ac667ff 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -530,8 +530,7 @@ void DWIN_ResetStatusLine() { // Djb2 hash algorithm uint32_t GetHash(char * str) { uint32_t hash = 5381; - char c; - while ((c = *str++)) hash = ((hash << 5) + hash) + c; /* hash * 33 + c */ + for (char c; (c = *str++);) hash = ((hash << 5) + hash) + c; /* hash * 33 + c */ return hash; } @@ -793,7 +792,8 @@ void update_variable() { _new_hotend_target = _hotendtarget != ht; if (_new_hotend_temp) _hotendtemp = hc; if (_new_hotend_target) _hotendtarget = ht; - #endif + #endif // HAS_HOTEND + #if HAS_HEATED_BED static celsius_t _bedtemp = 0, _bedtarget = 0; const celsius_t bc = thermalManager.wholeDegBed(), @@ -802,7 +802,8 @@ void update_variable() { _new_bed_target = _bedtarget != bt; if (_new_bed_temp) _bedtemp = bc; if (_new_bed_target) _bedtarget = bt; - #endif + #endif // HAS_HEATED_BED + #if HAS_FAN static uint8_t _fanspeed = 0; const bool _new_fanspeed = _fanspeed != thermalManager.fan_speed[0]; @@ -976,8 +977,11 @@ void onClickSDItem() { shift_amt = shift_new; // Set new scroll } } -#else + +#else // !SCROLL_LONG_FILENAMES + char shift_name[FILENAME_LENGTH + 1] = ""; + #endif void onDrawFileName(MenuItemClass* menuitem, int8_t line) { @@ -1403,7 +1407,6 @@ void EachMomentUpdate() { #endif // POWER_LOSS_RECOVERY - void DWIN_HandleScreen() { switch (checkkey) { case MainMenu: HMI_MainMenu(); break; diff --git a/Marlin/src/lcd/e3v2/proui/dwin_defines.h b/Marlin/src/lcd/e3v2/proui/dwin_defines.h index 8031ca86e8..90413a90aa 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_defines.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_defines.h @@ -80,4 +80,3 @@ #define DEF_HOTENDPIDT TERN(PREHEAT_1_TEMP_BED, PREHEAT_1_TEMP_HOTEND, 195) #define DEF_BEDPIDT TERN(PREHEAT_1_TEMP_BED, PREHEAT_1_TEMP_HOTEND, 60) #define DEF_PIDCYCLES 5 - diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h index bdcd248dd6..a8701fa894 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h @@ -241,7 +241,6 @@ enum DGUSLCD_Screens : uint8_t { DGUSLCD_SCREEN_UNUSED = 255 }; - // Place for status messages. constexpr uint16_t VP_M117 = 0x7020; constexpr uint8_t VP_M117_LEN = 0x20; @@ -299,7 +298,6 @@ constexpr uint16_t SP_T_Bed_Set = 0x5040; constexpr uint16_t VP_MARLIN_VERSION = 0x1A00; constexpr uint8_t VP_MARLIN_VERSION_LEN = 16; // there is more space on the display, if needed. - constexpr uint16_t VP_SCREENCHANGE_ASK = 0x1500; constexpr uint16_t VP_SCREENCHANGE = 0x1501; // Key-Return button to new menu pressed. Data contains target screen in low byte and info in high byte. constexpr uint16_t VP_TEMP_ALL_OFF = 0x1502; // Turn all heaters off. Value arbitrary ;)= @@ -515,7 +513,6 @@ constexpr uint16_t SP_T_Bed_Set = 0x5040; constexpr uint16_t VP_TMC_E1_Current = 0x3442; constexpr uint16_t VP_TMC_Z1_Current = 0x3444; - constexpr uint16_t VP_PrintTime_H = 0x3500; constexpr uint16_t VP_PrintTime_M = 0x3502; constexpr uint16_t VP_PrintTime_S = 0x3504; @@ -591,7 +588,6 @@ constexpr uint16_t SP_T_Bed_Set = 0x5040; constexpr uint16_t VP_Level_Point_Five_X = 0x4110; constexpr uint16_t VP_Level_Point_Five_Y = 0x4112; - /* H43 Version */ constexpr uint16_t VP_MKS_H43_VERSION = 0x4A00; // MKS H43 V1.0.0 constexpr uint16_t VP_MKS_H43_VERSION_LEN = 16; @@ -630,7 +626,6 @@ constexpr uint16_t SP_T_Bed_Set = 0x5040; constexpr uint16_t VP_E0_Max_Acc_Speed_Dis = 0x5210; constexpr uint16_t VP_E1_Max_Acc_Speed_Dis = 0x5220; - constexpr uint16_t VP_PrintTime_Dis = 0x5470; constexpr uint16_t VP_E0_Temp_Dis = 0x5310; constexpr uint16_t VP_E1_Temp_Dis = 0x5320; @@ -641,12 +636,10 @@ constexpr uint16_t SP_T_Bed_Set = 0x5040; constexpr uint16_t VP_Min_Ex_Temp_Dis = 0x5380; - constexpr uint16_t VP_X_PARK_POS_Dis = 0x53E0; constexpr uint16_t VP_Y_PARK_POS_Dis = 0x53F0; constexpr uint16_t VP_Z_PARK_POS_Dis = 0x5400; - constexpr uint16_t VP_TravelAcc_Dis = 0x5440; constexpr uint16_t VP_FeedRateMin_Dis = 0x5450; constexpr uint16_t VP_TravelFeeRateMin_Dis = 0x5460; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h index e7ade7d2e3..b566a2a6e6 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSDisplay.h @@ -47,13 +47,13 @@ public: enum DGUS_ControlType : uint8_t { VARIABLE_DATA_INPUT = 0x00, - POPUP_WINDOW = 0x01, - INCREMENTAL_ADJUST = 0x02, - SLIDER_ADJUST = 0x03, - RTC_SETTINGS = 0x04, - RETURN_KEY_CODE = 0x05, - TEXT_INPUT = 0x06, - FIRMWARE_SETTINGS = 0x07 + POPUP_WINDOW = 0x01, + INCREMENTAL_ADJUST = 0x02, + SLIDER_ADJUST = 0x03, + RTC_SETTINGS = 0x04, + RETURN_KEY_CODE = 0x05, + TEXT_INPUT = 0x06, + FIRMWARE_SETTINGS = 0x07 }; DGUSDisplay() = default; @@ -154,7 +154,7 @@ private: }; enum dgus_system_addr : uint16_t { - DGUS_VERSION = 0x000f // OS/GUI version + DGUS_VERSION = 0x000F // OS/GUI version }; static void WriteHeader(uint16_t addr, uint8_t command, uint8_t len); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Addr.h b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Addr.h index 39e97156d0..0eea6416a2 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Addr.h +++ b/Marlin/src/lcd/extui/dgus_reloaded/config/DGUS_Addr.h @@ -36,138 +36,138 @@ constexpr uint8_t DGUS_FILAMENTUSED_LEN = 24; constexpr uint8_t DGUS_GCODE_LEN = 32; enum class DGUS_Addr : uint16_t { - MESSAGE_Line1 = 0x1100, // 0x1100 - 0x111F - MESSAGE_Line2 = 0x1120, // 0x1120 - 0x113F - MESSAGE_Line3 = 0x1140, // 0x1140 - 0x115F - MESSAGE_Line4 = 0x1160, // 0x1160 - 0x117F + MESSAGE_Line1 = 0x1100, // 0x1100 - 0x111F + MESSAGE_Line2 = 0x1120, // 0x1120 - 0x113F + MESSAGE_Line3 = 0x1140, // 0x1140 - 0x115F + MESSAGE_Line4 = 0x1160, // 0x1160 - 0x117F // READ-ONLY VARIABLES - SCREENCHANGE = 0x2000, // Screen change request. Data contains target screen in low byte. - SCREENCHANGE_SD = 0x2001, // Only change if SD card present. - SCREENCHANGE_Idle = 0x2002, // Only change if not printing. - SCREENCHANGE_Printing = 0x2003, // Only change if printing. - SD_SelectFile = 0x2004, // Data: file index (0-4) - SD_Scroll = 0x2005, // Data: DGUS_Data::Scroll - SD_Print = 0x2006, - STATUS_Abort = 0x2007, // Popup / Data: DGUS_Data::Popup - STATUS_Pause = 0x2008, // Popup / Data: DGUS_Data::Popup - STATUS_Resume = 0x2009, // Popup / Data: DGUS_Data::Popup - ADJUST_SetFeedrate = 0x200A, // Type: Integer (16 bits signed) - ADJUST_SetFlowrate_CUR = 0x200B, // Type: Integer (16 bits signed) + SCREENCHANGE = 0x2000, // Screen change request. Data contains target screen in low byte. + SCREENCHANGE_SD = 0x2001, // Only change if SD card present. + SCREENCHANGE_Idle = 0x2002, // Only change if not printing. + SCREENCHANGE_Printing = 0x2003, // Only change if printing. + SD_SelectFile = 0x2004, // Data: file index (0-4) + SD_Scroll = 0x2005, // Data: DGUS_Data::Scroll + SD_Print = 0x2006, + STATUS_Abort = 0x2007, // Popup / Data: DGUS_Data::Popup + STATUS_Pause = 0x2008, // Popup / Data: DGUS_Data::Popup + STATUS_Resume = 0x2009, // Popup / Data: DGUS_Data::Popup + ADJUST_SetFeedrate = 0x200A, // Type: Integer (16 bits signed) + ADJUST_SetFlowrate_CUR = 0x200B, // Type: Integer (16 bits signed) #if HAS_MULTI_EXTRUDER - ADJUST_SetFlowrate_E0 = 0x200C, // Type: Integer (16 bits signed) - ADJUST_SetFlowrate_E1 = 0x200D, // Type: Integer (16 bits signed) + ADJUST_SetFlowrate_E0 = 0x200C, // Type: Integer (16 bits signed) + ADJUST_SetFlowrate_E1 = 0x200D, // Type: Integer (16 bits signed) #endif - ADJUST_SetBabystep = 0x200E, // Type: Fixed point, 2 decimals (16 bits signed) - ADJUST_Babystep = 0x200F, // Data: DGUS_Data::Adjust - TEMP_Preset = 0x2010, // Popup / Data: DGUS_Data::TempPreset - TEMP_SetTarget_Bed = 0x2011, // Type: Integer (16 bits signed) - TEMP_SetTarget_H0 = 0x2012, // Type: Integer (16 bits signed) + ADJUST_SetBabystep = 0x200E, // Type: Fixed point, 2 decimals (16 bits signed) + ADJUST_Babystep = 0x200F, // Data: DGUS_Data::Adjust + TEMP_Preset = 0x2010, // Popup / Data: DGUS_Data::TempPreset + TEMP_SetTarget_Bed = 0x2011, // Type: Integer (16 bits signed) + TEMP_SetTarget_H0 = 0x2012, // Type: Integer (16 bits signed) #if HAS_MULTI_HOTEND - TEMP_SetTarget_H1 = 0x2013, // Type: Integer (16 bits signed) + TEMP_SetTarget_H1 = 0x2013, // Type: Integer (16 bits signed) #endif - TEMP_Cool = 0x2014, // Data: DGUS_Data::Heater - STEPPER_Control = 0x2015, // Popup / Data: DGUS_Data::Control - LEVEL_OFFSET_Set = 0x2016, // Type: Fixed point, 2 decimals (16 bits signed) - LEVEL_OFFSET_Step = 0x2017, // Data: DGUS_Data::Adjust - LEVEL_OFFSET_SetStep = 0x2018, // Data: DGUS_Data::StepSize - LEVEL_MANUAL_Point = 0x2019, // Data: point index (1-5) - LEVEL_AUTO_Probe = 0x201A, - LEVEL_AUTO_Disable = 0x201B, - FILAMENT_Select = 0x201C, // Data: DGUS_Data::Extruder - FILAMENT_SetLength = 0x201D, // Type: Integer (16 bits unsigned) - FILAMENT_Move = 0x201E, // Data: DGUS_Data::FilamentMove - MOVE_Home = 0x201F, // Data: DGUS_Data::Axis - MOVE_SetX = 0x2020, // Type: Fixed point, 1 decimal (16 bits signed) - MOVE_SetY = 0x2021, // Type: Fixed point, 1 decimal (16 bits signed) - MOVE_SetZ = 0x2022, // Type: Fixed point, 1 decimal (16 bits signed) - MOVE_Step = 0x2023, // Data: DGUS_Data::MoveDirection - MOVE_SetStep = 0x2024, // Data: DGUS_Data::StepSize - GCODE_Clear = 0x2025, - GCODE_Execute = 0x2026, - EEPROM_Reset = 0x2027, // Popup / Data: DGUS_Data::Popup - SETTINGS2_Extra = 0x2028, // Data: DGUS_Data::Extra - PID_Select = 0x2029, // Data: DGUS_Data::Heater - PID_SetTemp = 0x202A, // Type: Integer (16 bits unsigned) - PID_Run = 0x202B, - POWERLOSS_Abort = 0x202C, // Popup / Data: DGUS_Data::Popup - POWERLOSS_Resume = 0x202D, // Popup / Data: DGUS_Data::Popup - WAIT_Abort = 0x202E, // Popup / Data: DGUS_Data::Popup - WAIT_Continue = 0x202F, + TEMP_Cool = 0x2014, // Data: DGUS_Data::Heater + STEPPER_Control = 0x2015, // Popup / Data: DGUS_Data::Control + LEVEL_OFFSET_Set = 0x2016, // Type: Fixed point, 2 decimals (16 bits signed) + LEVEL_OFFSET_Step = 0x2017, // Data: DGUS_Data::Adjust + LEVEL_OFFSET_SetStep = 0x2018, // Data: DGUS_Data::StepSize + LEVEL_MANUAL_Point = 0x2019, // Data: point index (1-5) + LEVEL_AUTO_Probe = 0x201A, + LEVEL_AUTO_Disable = 0x201B, + FILAMENT_Select = 0x201C, // Data: DGUS_Data::Extruder + FILAMENT_SetLength = 0x201D, // Type: Integer (16 bits unsigned) + FILAMENT_Move = 0x201E, // Data: DGUS_Data::FilamentMove + MOVE_Home = 0x201F, // Data: DGUS_Data::Axis + MOVE_SetX = 0x2020, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_SetY = 0x2021, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_SetZ = 0x2022, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_Step = 0x2023, // Data: DGUS_Data::MoveDirection + MOVE_SetStep = 0x2024, // Data: DGUS_Data::StepSize + GCODE_Clear = 0x2025, + GCODE_Execute = 0x2026, + EEPROM_Reset = 0x2027, // Popup / Data: DGUS_Data::Popup + SETTINGS2_Extra = 0x2028, // Data: DGUS_Data::Extra + PID_Select = 0x2029, // Data: DGUS_Data::Heater + PID_SetTemp = 0x202A, // Type: Integer (16 bits unsigned) + PID_Run = 0x202B, + POWERLOSS_Abort = 0x202C, // Popup / Data: DGUS_Data::Popup + POWERLOSS_Resume = 0x202D, // Popup / Data: DGUS_Data::Popup + WAIT_Abort = 0x202E, // Popup / Data: DGUS_Data::Popup + WAIT_Continue = 0x202F, // WRITE-ONLY VARIABLES - MESSAGE_Status = 0x3000, // 0x3000 - 0x301F - SD_Type = 0x3020, // 0x3020 - 0x3024 / Data: DGUS_Data::SDType - SD_FileName0 = 0x3025, // 0x3025 - 0x3044 - SD_FileName1 = 0x3045, // 0x3045 - 0x3064 - SD_FileName2 = 0x3065, // 0x3065 - 0x3084 - SD_FileName3 = 0x3085, // 0x3085 - 0x30A4 - SD_FileName4 = 0x30A5, // 0x30A5 - 0x30C4 - SD_ScrollIcons = 0x30C5, // Bits: DGUS_Data::ScrollIcon - SD_SelectedFileName = 0x30C6, // 0x30C6 - 0x30E5 - STATUS_PositionZ = 0x30E6, // Type: Fixed point, 1 decimal (16 bits signed) - STATUS_Ellapsed = 0x30E7, // 0x30E7 - 0x30F5 - STATUS_Percent = 0x30F6, // Type: Integer (16 bits unsigned) - STATUS_Icons = 0x30F7, // Bits: DGUS_Data::StatusIcon - ADJUST_Feedrate = 0x30F8, // Type: Integer (16 bits signed) - ADJUST_Flowrate_CUR = 0x30F9, // Type: Integer (16 bits signed) + MESSAGE_Status = 0x3000, // 0x3000 - 0x301F + SD_Type = 0x3020, // 0x3020 - 0x3024 / Data: DGUS_Data::SDType + SD_FileName0 = 0x3025, // 0x3025 - 0x3044 + SD_FileName1 = 0x3045, // 0x3045 - 0x3064 + SD_FileName2 = 0x3065, // 0x3065 - 0x3084 + SD_FileName3 = 0x3085, // 0x3085 - 0x30A4 + SD_FileName4 = 0x30A5, // 0x30A5 - 0x30C4 + SD_ScrollIcons = 0x30C5, // Bits: DGUS_Data::ScrollIcon + SD_SelectedFileName = 0x30C6, // 0x30C6 - 0x30E5 + STATUS_PositionZ = 0x30E6, // Type: Fixed point, 1 decimal (16 bits signed) + STATUS_Ellapsed = 0x30E7, // 0x30E7 - 0x30F5 + STATUS_Percent = 0x30F6, // Type: Integer (16 bits unsigned) + STATUS_Icons = 0x30F7, // Bits: DGUS_Data::StatusIcon + ADJUST_Feedrate = 0x30F8, // Type: Integer (16 bits signed) + ADJUST_Flowrate_CUR = 0x30F9, // Type: Integer (16 bits signed) #if HAS_MULTI_EXTRUDER - ADJUST_Flowrate_E0 = 0x30FA, // Type: Integer (16 bits signed) - ADJUST_Flowrate_E1 = 0x30FB, // Type: Integer (16 bits signed) + ADJUST_Flowrate_E0 = 0x30FA, // Type: Integer (16 bits signed) + ADJUST_Flowrate_E1 = 0x30FB, // Type: Integer (16 bits signed) #endif - TEMP_Current_Bed = 0x30FC, // Type: Integer (16 bits signed) - TEMP_Target_Bed = 0x30FD, // Type: Integer (16 bits signed) - TEMP_Max_Bed = 0x30FE, // Type: Integer (16 bits unsigned) - TEMP_Current_H0 = 0x30FF, // Type: Integer (16 bits signed) - TEMP_Target_H0 = 0x3100, // Type: Integer (16 bits signed) - TEMP_Max_H0 = 0x3101, // Type: Integer (16 bits unsigned) + TEMP_Current_Bed = 0x30FC, // Type: Integer (16 bits signed) + TEMP_Target_Bed = 0x30FD, // Type: Integer (16 bits signed) + TEMP_Max_Bed = 0x30FE, // Type: Integer (16 bits unsigned) + TEMP_Current_H0 = 0x30FF, // Type: Integer (16 bits signed) + TEMP_Target_H0 = 0x3100, // Type: Integer (16 bits signed) + TEMP_Max_H0 = 0x3101, // Type: Integer (16 bits unsigned) #if HAS_MULTI_HOTEND - TEMP_Current_H1 = 0x3102, // Type: Integer (16 bits signed) - TEMP_Target_H1 = 0x3103, // Type: Integer (16 bits signed) - TEMP_Max_H1 = 0x3104, // Type: Integer (16 bits unsigned) + TEMP_Current_H1 = 0x3102, // Type: Integer (16 bits signed) + TEMP_Target_H1 = 0x3103, // Type: Integer (16 bits signed) + TEMP_Max_H1 = 0x3104, // Type: Integer (16 bits unsigned) #endif - STEPPER_Status = 0x3105, // Data: DGUS_Data::Status - LEVEL_OFFSET_Current = 0x3106, // Type: Fixed point, 2 decimals (16 bits signed) - LEVEL_OFFSET_StepIcons = 0x3107, // Bits: DGUS_Data::StepIcon - LEVEL_AUTO_DisableIcon = 0x3108, // Data: DGUS_Data::Status - LEVEL_AUTO_Grid = 0x3109, // 0x3109 - 0x3121 / Type: Fixed point, 3 decimals (16 bits signed) - LEVEL_PROBING_Icons1 = 0x3122, // Type: Integer (16 bits unsigned) / Each bit represents a grid point - LEVEL_PROBING_Icons2 = 0x3123, // Type: Integer (16 bits unsigned) / Each bit represents a grid point - FILAMENT_ExtruderIcons = 0x3124, // Data: DGUS_Data::ExtruderIcon - FILAMENT_Length = 0x3125, // Type: Integer (16 bits unsigned) - MOVE_CurrentX = 0x3126, // Type: Fixed point, 1 decimal (16 bits signed) - MOVE_CurrentY = 0x3127, // Type: Fixed point, 1 decimal (16 bits signed) - MOVE_CurrentZ = 0x3128, // Type: Fixed point, 1 decimal (16 bits signed) - MOVE_StepIcons = 0x3129, // Bits: DGUS_Data::StepIcon - SETTINGS2_BLTouch = 0x312A, // Data: DGUS_Data::Status - PID_HeaterIcons = 0x312B, // Data: DGUS_Data::HeaterIcon - PID_Temp = 0x312C, // Type: Integer (16 bits unsigned) - PID_Kp = 0x312D, // Type: Fixed point, 2 decimals (32 bits signed) - PID_Ki = 0x312F, // Type: Fixed point, 2 decimals (32 bits signed) - PID_Kd = 0x3131, // Type: Fixed point, 2 decimals (32 bits signed) - INFOS_Machine = 0x3133, // 0x3133 - 0x314A - INFOS_BuildVolume = 0x314B, // 0x314B - 0x3162 - INFOS_Version = 0x3163, // 0x3163 - 0x3172 - INFOS_TotalPrints = 0x3173, // Type: Integer (16 bits unsigned) - INFOS_FinishedPrints = 0x3174, // Type: Integer (16 bits unsigned) - INFOS_PrintTime = 0x3175, // 0x3175 - 0x318C - INFOS_LongestPrint = 0x318D, // 0x318D - 0x31A4 - INFOS_FilamentUsed = 0x31A5, // 0x31A5 - 0x31BC - WAIT_Icons = 0x31BD, // Bits: DGUS_Data::WaitIcon + STEPPER_Status = 0x3105, // Data: DGUS_Data::Status + LEVEL_OFFSET_Current = 0x3106, // Type: Fixed point, 2 decimals (16 bits signed) + LEVEL_OFFSET_StepIcons = 0x3107, // Bits: DGUS_Data::StepIcon + LEVEL_AUTO_DisableIcon = 0x3108, // Data: DGUS_Data::Status + LEVEL_AUTO_Grid = 0x3109, // 0x3109 - 0x3121 / Type: Fixed point, 3 decimals (16 bits signed) + LEVEL_PROBING_Icons1 = 0x3122, // Type: Integer (16 bits unsigned) / Each bit represents a grid point + LEVEL_PROBING_Icons2 = 0x3123, // Type: Integer (16 bits unsigned) / Each bit represents a grid point + FILAMENT_ExtruderIcons = 0x3124, // Data: DGUS_Data::ExtruderIcon + FILAMENT_Length = 0x3125, // Type: Integer (16 bits unsigned) + MOVE_CurrentX = 0x3126, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_CurrentY = 0x3127, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_CurrentZ = 0x3128, // Type: Fixed point, 1 decimal (16 bits signed) + MOVE_StepIcons = 0x3129, // Bits: DGUS_Data::StepIcon + SETTINGS2_BLTouch = 0x312A, // Data: DGUS_Data::Status + PID_HeaterIcons = 0x312B, // Data: DGUS_Data::HeaterIcon + PID_Temp = 0x312C, // Type: Integer (16 bits unsigned) + PID_Kp = 0x312D, // Type: Fixed point, 2 decimals (32 bits signed) + PID_Ki = 0x312F, // Type: Fixed point, 2 decimals (32 bits signed) + PID_Kd = 0x3131, // Type: Fixed point, 2 decimals (32 bits signed) + INFOS_Machine = 0x3133, // 0x3133 - 0x314A + INFOS_BuildVolume = 0x314B, // 0x314B - 0x3162 + INFOS_Version = 0x3163, // 0x3163 - 0x3172 + INFOS_TotalPrints = 0x3173, // Type: Integer (16 bits unsigned) + INFOS_FinishedPrints = 0x3174, // Type: Integer (16 bits unsigned) + INFOS_PrintTime = 0x3175, // 0x3175 - 0x318C + INFOS_LongestPrint = 0x318D, // 0x318D - 0x31A4 + INFOS_FilamentUsed = 0x31A5, // 0x31A5 - 0x31BC + WAIT_Icons = 0x31BD, // Bits: DGUS_Data::WaitIcon // READ-WRITE VARIABLES - FAN0_Speed = 0x4000, // Type: Integer (16 bits unsigned) / Data: fan speed as percent (0-100) - GCODE_Data = 0x4001, // 0x4001 - 0x4020 - PID_Cycles = 0x4021, // Type: Integer (16 bits unsigned) - VOLUME_Level = 0x4022, // Type: Integer (16 bits unsigned) / Data: volume as percent (0-100) - BRIGHTNESS_Level = 0x4023, // Type: Integer (16 bits unsigned) / Data: brightness as percent (0-100) + FAN0_Speed = 0x4000, // Type: Integer (16 bits unsigned) / Data: fan speed as percent (0-100) + GCODE_Data = 0x4001, // 0x4001 - 0x4020 + PID_Cycles = 0x4021, // Type: Integer (16 bits unsigned) + VOLUME_Level = 0x4022, // Type: Integer (16 bits unsigned) / Data: volume as percent (0-100) + BRIGHTNESS_Level = 0x4023, // Type: Integer (16 bits unsigned) / Data: brightness as percent (0-100) // SPECIAL CASES - STATUS_Percent_Complete = 0x5000, // Same as STATUS_Percent, but always 100% - INFOS_Debug = 0x5001, + STATUS_Percent_Complete = 0x5000, // Same as STATUS_Percent, but always 100% + INFOS_Debug = 0x5001, }; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h index 5276f64f44..11d87f9691 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h @@ -22,7 +22,6 @@ #pragma once - /********************************* DL CACHE SLOTS ******************************/ // In order to reduce SPI traffic, we cache display lists (DL) in RAMG. This diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h index 5168ef76af..b219bd88e1 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/boards.h @@ -248,7 +248,6 @@ #endif - /* this data is used to patch FT813 displays that use a GT911 as a touch-controller */ #ifdef PATCH_GT911 constexpr PROGMEM unsigned char GT911_data[] = { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp index 7fccb309f5..dd2e477d9f 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/event_loop.cpp @@ -71,7 +71,6 @@ void UIData::set_persistent_data(uint8_t value) { flags.value = value & get_persistent_data_mask(); } - void UIData::enable_touch_sounds(bool enabled) { UIData::flags.bits.touch_start_sound = enabled; UIData::flags.bits.touch_end_sound = enabled; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h index 30b1f84399..6a1a703e45 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/cyrillic_char_set_bitmap_31.h @@ -100,7 +100,6 @@ const uint8_t cyrillic_font_widths[] PROGMEM = { 21, // ё }; - /* This is a dump of "font_bitmaps/cyrillic_char_set_bitmap_31.png" * using the tool "bitmap2cpp.py". The tool converts the image into * 16-level grayscale and packs two pixels per byte. The resulting diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp index 9ff738e45c..c087bf41b5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language.cpp @@ -19,7 +19,6 @@ * location: . * ****************************************************************************/ - #include "../../../../MarlinCore.h" #if ENABLED(TOUCH_UI_FTDI_EVE) #include "language.h" diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp index ed210369c4..3a0f891a82 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp @@ -26,7 +26,6 @@ #include "screens.h" tiny_timer_t refresh_timer; - /** * DECL_SCREEN_IF_INCLUDED allows for a concise * definition of SCREEN_TABLE: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp index efeed19201..55a310dea9 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/sounds.cpp @@ -165,7 +165,6 @@ namespace Theme { {ORGAN, NOTE_A4, 4}, {SILENCE, REST, 36}, - {ORGAN, NOTE_C5S, 4}, {ORGAN, NOTE_D5, 2}, {ORGAN, NOTE_E5, 2}, diff --git a/Marlin/src/lcd/extui/malyan/malyan.cpp b/Marlin/src/lcd/extui/malyan/malyan.cpp index 05d05241d1..e91e66161c 100644 --- a/Marlin/src/lcd/extui/malyan/malyan.cpp +++ b/Marlin/src/lcd/extui/malyan/malyan.cpp @@ -106,7 +106,6 @@ void set_lcd_error(FSTR_P const error, FSTR_P const component/*=nullptr*/) { write_to_lcd(F("}")); } - /** * Process an LCD 'C' command. * These are currently all temperature commands diff --git a/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp index 43149dc60c..0554c34a19 100644 --- a/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp +++ b/Marlin/src/lcd/extui/mks_ui/SPIFlashStorage.cpp @@ -59,7 +59,7 @@ uint32_t SPIFlashStorage::m_startAddress; while (index < inputLength && index - count < max && input[index] == pixel) index++; if (index - count == 1) { - /* + /** * Failed to "replicate" the current pixel. See how many to copy. * Avoid a replicate run of only 2-pixels after a literal run. There * is no gain in this, and there is a risK of loss if the run after @@ -68,7 +68,7 @@ uint32_t SPIFlashStorage::m_startAddress; */ while (index < inputLength && index - count < max && (input[index] != input[index - 1] || (index > 1 && input[index] != input[index - 2]))) index++; - /* + /** * Check why this run stopped. If it found two identical pixels, reset * the index so we can add a run. Do this twice: the previous run * tried to detect a replicate run of at least 3 pixels. So we may be @@ -158,7 +158,6 @@ void SPIFlashStorage::beginWrite(const uint32_t startAddress) { #endif } - void SPIFlashStorage::endWrite() { // Flush remaining data #if HAS_SPI_FLASH_COMPRESSION diff --git a/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp b/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp index 2d978c3032..0fa4e23b0c 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp @@ -120,8 +120,6 @@ bool have_pre_pic(char *path) { static void event_handler(lv_obj_t *obj, lv_event_t event) { if (event != LV_EVENT_RELEASED) return; uint8_t i, file_count = 0; - //switch (obj->mks_obj_id) - //{ if (obj->mks_obj_id == ID_P_UP) { if (dir_offset[curDirLever].curPage > 0) { // 2015.05.19 @@ -130,9 +128,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { if (dir_offset[curDirLever].cur_page_first_offset >= FILE_NUM) list_file.Sd_file_offset = dir_offset[curDirLever].cur_page_first_offset - FILE_NUM; - #if HAS_MEDIA - file_count = search_file(); - #endif + TERN_(HAS_MEDIA, file_count = search_file()); if (file_count != 0) { dir_offset[curDirLever].curPage--; lv_clear_print_file(); @@ -144,9 +140,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { if (dir_offset[curDirLever].cur_page_last_offset > 0) { list_file.Sd_file_cnt = 0; list_file.Sd_file_offset = dir_offset[curDirLever].cur_page_last_offset + 1; - #if HAS_MEDIA - file_count = search_file(); - #endif + TERN_(HAS_MEDIA, file_count = search_file()); if (file_count != 0) { dir_offset[curDirLever].curPage++; lv_clear_print_file(); @@ -161,17 +155,13 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { int8_t *ch = (int8_t *)strrchr(list_file.curDirPath, '/'); if (ch) { *ch = 0; - #if HAS_MEDIA - card.cdup(); - #endif + TERN_(HAS_MEDIA, card.cdup()); dir_offset[curDirLever].curPage = 0; dir_offset[curDirLever].cur_page_first_offset = 0; dir_offset[curDirLever].cur_page_last_offset = 0; curDirLever--; list_file.Sd_file_offset = dir_offset[curDirLever].cur_page_first_offset; - #if HAS_MEDIA - file_count = search_file(); - #endif + TERN_(HAS_MEDIA, file_count = search_file()); lv_clear_print_file(); disp_gcode_icon(file_count); } @@ -189,9 +179,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { strcpy(list_file.curDirPath, list_file.file_name[i]); curDirLever++; list_file.Sd_file_offset = dir_offset[curDirLever].cur_page_first_offset; - #if HAS_MEDIA - file_count = search_file(); - #endif + TERN_(HAS_MEDIA, file_count = search_file()); lv_clear_print_file(); disp_gcode_icon(file_count); } @@ -396,8 +384,7 @@ int ascii2dec_test(char *ascii) { void lv_gcode_file_read(uint8_t *data_buf) { #if HAS_MEDIA - uint16_t i = 0, j = 0, k = 0; - uint16_t row_1 = 0; + uint16_t i = 0, j = 0, k = 0, row_1 = 0; bool ignore_start = true; char temp_test[200]; volatile uint16_t *p_index; @@ -435,24 +422,13 @@ void lv_gcode_file_read(uint8_t *data_buf) { break; } } - #if HAS_TFT_LVGL_UI_SPI - for (i = 0; i < 200;) { - p_index = (uint16_t *)(&public_buf[i]); - - //Color = (*p_index >> 8); - //*p_index = Color | ((*p_index & 0xFF) << 8); - i += 2; - if (*p_index == 0x0000) *p_index = LV_COLOR_BACKGROUND.full; - } - #else // !HAS_TFT_LVGL_UI_SPI - for (i = 0; i < 200;) { - p_index = (uint16_t *)(&public_buf[i]); - //Color = (*p_index >> 8); - //*p_index = Color | ((*p_index & 0xFF) << 8); - i += 2; - if (*p_index == 0x0000) *p_index = LV_COLOR_BACKGROUND.full; // 0x18C3; - } - #endif // !HAS_TFT_LVGL_UI_SPI + for (i = 0; i < 200;) { + p_index = (uint16_t *)(&public_buf[i]); + //Color = (*p_index >> 8); + //*p_index = Color | ((*p_index & 0xFF) << 8); + i += 2; + if (*p_index == 0x0000) *p_index = LV_COLOR_BACKGROUND.full; + } memcpy(data_buf, public_buf, 200); #endif // HAS_MEDIA } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.h b/Marlin/src/lcd/extui/mks_ui/draw_ui.h index 9bc583d3ad..da43f2a490 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.h @@ -133,16 +133,16 @@ #define FILE_PRE_PIC_Y_OFFSET 0 #define PREVIEW_LITTLE_PIC_SIZE 40910 // 400*100+9*101+1 - #define PREVIEW_SIZE 202720 // (PREVIEW_LITTLE_PIC_SIZE+800*200+201*9+1) + #define PREVIEW_SIZE 202720 // (PREVIEW_LITTLE_PIC_SIZE+800*200+201*9+1) // machine parameter ui - #define PARA_UI_POS_X 10 - #define PARA_UI_POS_Y 50 + #define PARA_UI_POS_X 10 + #define PARA_UI_POS_Y 50 #define PARA_UI_SIZE_X 450 - #define PARA_UI_SIZE_Y 40 + #define PARA_UI_SIZE_Y 40 - #define PARA_UI_ARROW_V 12 + #define PARA_UI_ARROW_V 12 #define PARA_UI_BACK_POS_X 400 #define PARA_UI_BACK_POS_Y 270 @@ -152,31 +152,31 @@ #define PARA_UI_VALUE_SIZE_X 370 #define PARA_UI_VALUE_POS_X 400 - #define PARA_UI_VALUE_V 5 + #define PARA_UI_VALUE_V 5 #define PARA_UI_STATE_POS_X 380 - #define PARA_UI_STATE_V 2 + #define PARA_UI_STATE_V 2 #define PARA_UI_VALUE_SIZE_X_2 200 #define PARA_UI_VALUE_POS_X_2 320 - #define PARA_UI_VALUE_V_2 5 + #define PARA_UI_VALUE_V_2 5 - #define PARA_UI_VALUE_BTN_X_SIZE 70 - #define PARA_UI_VALUE_BTN_Y_SIZE 28 + #define PARA_UI_VALUE_BTN_X_SIZE 70 + #define PARA_UI_VALUE_BTN_Y_SIZE 28 - #define PARA_UI_BACK_BTN_X_SIZE 70 - #define PARA_UI_BACK_BTN_Y_SIZE 40 + #define PARA_UI_BACK_BTN_X_SIZE 70 + #define PARA_UI_BACK_BTN_Y_SIZE 40 - #define QRCODE_X 20 - #define QRCODE_Y 40 + #define QRCODE_X 20 + #define QRCODE_Y 40 #define QRCODE_WIDTH 160 -#else // ifdef TFT35 +#else // !TFT35 #define TFT_WIDTH 320 #define TFT_HEIGHT 240 -#endif // ifdef TFT35 +#endif #ifdef __cplusplus extern "C" { diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi.h b/Marlin/src/lcd/extui/mks_ui/draw_wifi.h index a89bbd67d8..18cfd0755c 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_wifi.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi.h @@ -25,7 +25,6 @@ extern "C" { #endif - void lv_draw_wifi(); void lv_clear_wifi(); void disp_wifi_state(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.h b/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.h index ad15238932..6f1499a068 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.h +++ b/Marlin/src/lcd/extui/mks_ui/draw_wifi_tips.h @@ -25,7 +25,6 @@ extern "C" { #endif - void lv_draw_wifi_tips(); void lv_clear_wifi_tips(); @@ -38,7 +37,7 @@ extern TIPS_TYPE wifi_tips_type; typedef struct { unsigned char timer; - unsigned int timer_count; + uint16_t timer_count; } TIPS_DISP; extern TIPS_DISP tips_disp; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp b/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp index 9adcebbc36..a7fb3b0293 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp @@ -36,7 +36,7 @@ #if HAS_LEVELING #include "../../../feature/bedlevel/bedlevel.h" - bool leveling_was_active; + bool mks_leveling_was_active; #endif extern lv_group_t *g; @@ -110,7 +110,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { case ID_M_RETURN: probe.offset.z = z_offset_backup; SET_SOFT_ENDSTOP_LOOSE(false); - TERN_(HAS_LEVELING, set_bed_leveling_enabled(leveling_was_active)); + TERN_(HAS_LEVELING, set_bed_leveling_enabled(mks_leveling_was_active)); #if HOMING_Z_WITH_PROBE && defined(PROBE_OFFSET_WIZARD_START_Z) set_axis_never_homed(Z_AXIS); // On cancel the Z position needs correction queue.inject_P(PSTR("G28Z")); @@ -149,8 +149,8 @@ void lv_draw_z_offset_wizard() { // Store Bed-Leveling-State and disable #if HAS_LEVELING - leveling_was_active = planner.leveling_active; - set_bed_leveling_enabled(leveling_was_active); + mks_leveling_was_active = planner.leveling_active; + set_bed_leveling_enabled(mks_leveling_was_active); #endif queue.inject_P(PSTR("G28")); diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp index d898aa5754..7c0ec802c3 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp @@ -24,7 +24,6 @@ #if HAS_TFT_LVGL_UI -#include "string.h" #include "draw_ui.h" #include "pic_manager.h" #include "draw_ready_print.h" @@ -34,6 +33,8 @@ #include "../../../sd/cardreader.h" #include "../../../MarlinCore.h" +#include + extern uint16_t DeviceCode; #if HAS_MEDIA diff --git a/Marlin/src/lcd/extui/mks_ui/tft_Language_fr.h b/Marlin/src/lcd/extui/mks_ui/tft_Language_fr.h index f0b19d4e02..35c753ad1a 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_Language_fr.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_Language_fr.h @@ -154,7 +154,6 @@ #define FILAMENT_DIALOG_LOAD_COMPLETE_TIPS_FR "Chargement terminé,\n pour revenir!" #define FILAMENT_DIALOG_UNLOAD_COMPLETE_TIPS_FR "Déchargement terminé,\n pour revenir!" - #define PRE_HEAT_EXT_TEXT_FR "E" #define PRE_HEAT_BED_TEXT_FR "Bed" diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index 5595ac63c1..7d00f1a503 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -36,10 +36,11 @@ #include #include "../../../MarlinCore.h" +#include "../../marlinui.h" + #include "../../../inc/MarlinConfig.h" #include HAL_PATH(../../.., tft/xpt2046.h) -#include "../../marlinui.h" XPT2046 touch; #if ENABLED(POWER_LOSS_RECOVERY) diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h index 0368140b28..a71bdc9db7 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h @@ -32,8 +32,6 @@ #include -//#define TFT_ROTATION TFT_ROTATE_180 - extern uint8_t bmp_public_buf[14 * 1024]; extern uint8_t public_buf[513]; diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.h b/Marlin/src/lcd/extui/mks_ui/wifi_module.h index 36998899b4..0f594c7643 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.h +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.h @@ -163,8 +163,8 @@ typedef struct { //uint8_t uartTxBuffer[UART_FIFO_BUFFER_SIZE]; } SZ_USART_FIFO; -#define WIFI_GCODE_BUFFER_LEAST_SIZE 96 -#define WIFI_GCODE_BUFFER_SIZE (WIFI_GCODE_BUFFER_LEAST_SIZE * 3) +#define WIFI_GCODE_BUFFER_LEAST_SIZE 96 +#define WIFI_GCODE_BUFFER_SIZE (WIFI_GCODE_BUFFER_LEAST_SIZE * 3) typedef struct { uint8_t wait_tick; uint8_t Buffer[WIFI_GCODE_BUFFER_SIZE]; diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp index 3c981d602a..5517aba7d8 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp @@ -79,13 +79,13 @@ const uint32_t ESP_FLASH_ADDR = 0x40200000; // address of start of Flash UPLOAD_STRUCT esp_upload; -static const unsigned int retriesPerReset = 3; -static const uint32_t connectAttemptInterval = 50; -static const unsigned int percentToReportIncrement = 5; // how often we report % complete -static const uint32_t defaultTimeout = 500; -static const uint32_t eraseTimeout = 15000; -static const uint32_t blockWriteTimeout = 200; -static const uint32_t blockWriteInterval = 15; // 15ms is long enough, 10ms is mostly too short +static const uint16_t retriesPerReset = 3; +static const millis_t connectAttemptInterval = 50; +static const uint16_t percentToReportIncrement = 5; // how often we report % complete +static const millis_t defaultTimeout = 500; +static const millis_t eraseTimeout = 15000; +static const millis_t blockWriteTimeout = 200; +static const millis_t blockWriteInterval = 15; // 15ms is long enough, 10ms is mostly too short static MediaFile update_file, *update_curDir; // Messages corresponding to result codes, should make sense when followed by " error" @@ -103,12 +103,14 @@ const char *resultMessages[] = { "slip data" }; -// A note on baud rates. -// The ESP8266 supports 921600, 460800, 230400, 115200, 74880 and some lower baud rates. -// 921600b is not reliable because even though it sometimes succeeds in connecting, we get a bad response during uploading after a few blocks. -// Probably our UART ISR cannot receive bytes fast enough, perhaps because of the latency of the system tick ISR. -// 460800b doesn't always manage to connect, but if it does then uploading appears to be reliable. -// 230400b always manages to connect. +/** + * Baud Rate Notes: + * The ESP8266 supports 921600, 460800, 230400, 115200, 74880 and some lower baud rates. + * 921600b is not reliable because even though it sometimes succeeds in connecting, we get a bad response during uploading after a few blocks. + * Probably our UART ISR cannot receive bytes fast enough, perhaps because of the latency of the system tick ISR. + * 460800b doesn't always manage to connect, but if it does then uploading appears to be reliable. + * 230400b always manages to connect. + */ static const uint32_t uploadBaudRates[] = { 460800, 230400, 115200, 74880 }; signed char IsReady() { @@ -151,7 +153,7 @@ void flushInput() { uint32_t getData(unsigned byteCnt, const uint8_t *buf, int ofst) { uint32_t val = 0; if (buf && byteCnt) { - unsigned int shiftCnt = 0; + uint16_t shiftCnt = 0; NOMORE(byteCnt, 4U); do { val |= (uint32_t)buf[ofst++] << shiftCnt; @@ -172,14 +174,16 @@ void putData(uint32_t val, unsigned byteCnt, uint8_t *buf, int ofst) { } } -// Read a byte optionally performing SLIP decoding. The return values are: -// -// 2 - an escaped byte was read successfully -// 1 - a non-escaped byte was read successfully -// 0 - no data was available -// -1 - the value 0xC0 was encountered (shouldn't happen) -// -2 - a SLIP escape byte was found but the following byte wasn't available -// -3 - a SLIP escape byte was followed by an invalid byte +/** + * Read a byte optionally performing SLIP decoding. The return values are: + * + * 2 - an escaped byte was read successfully + * 1 - a non-escaped byte was read successfully + * 0 - no data was available + * -1 - the value 0xC0 was encountered (shouldn't happen) + * -2 - a SLIP escape byte was found but the following byte wasn't available + * -3 - a SLIP escape byte was followed by an invalid byte + */ int ReadByte(uint8_t *data, signed char slipDecode) { if (uploadPort_available() == 0) return 0; @@ -226,14 +230,16 @@ void WriteByteSlip(const uint8_t b) { uploadPort_write((const uint8_t *)&b, 1); } -// Wait for a data packet to be returned. If the body of the packet is -// non-zero length, return an allocated buffer indirectly containing the -// data and return the data length. Note that if the pointer for returning -// the data buffer is nullptr, the response is expected to be two bytes of zero. -// -// If an error occurs, return a negative value. Otherwise, return the number -// of bytes in the response (or zero if the response was not the standard "two bytes of zero"). -EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, uint32_t msTimeout) { +/** + * Wait for a data packet to be returned. If the body of the packet is + * non-zero length, return an allocated buffer indirectly containing the + * data and return the data length. Note that if the pointer for returning + * the data buffer is nullptr, the response is expected to be two bytes of zero. + * + * If an error occurs, return a negative value. Otherwise, return the number + * of bytes in the response (or zero if the response was not the standard "two bytes of zero"). + */ +EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, millis_t msTimeout) { typedef enum { begin = 0, header, @@ -246,7 +252,7 @@ EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, uint32_t const size_t headerLength = 8; - uint32_t startTime = getWifiTick(); + const millis_t startTime = getWifiTick(); uint8_t hdr[headerLength]; uint16_t hdrIdx = 0; @@ -348,7 +354,7 @@ EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, uint32_t // Send a block of data performing SLIP encoding of the content. void _writePacket(const uint8_t *data, size_t len) { unsigned char outBuf[2048] = {0}; - unsigned int outIndex = 0; + uint16_t outIndex = 0; while (len != 0) { if (*data == 0xC0) { outBuf[outIndex++] = 0xDB; @@ -405,7 +411,7 @@ void sendCommand(uint8_t op, uint32_t checkVal, const uint8_t *data, size_t data } // Send a command to the attached device together with the supplied data, if any, and get the response -EspUploadResult doCommand(uint8_t op, const uint8_t *data, size_t dataLen, uint32_t checkVal, uint32_t *valp, uint32_t msTimeout) { +EspUploadResult doCommand(uint8_t op, const uint8_t *data, size_t dataLen, uint32_t checkVal, uint32_t *valp, millis_t msTimeout) { size_t bodyLen; EspUploadResult stat; @@ -459,7 +465,7 @@ EspUploadResult flashBegin(uint32_t addr, uint32_t size) { // determine the number of blocks represented by the size uint32_t blkCnt; uint8_t buf[16]; - uint32_t timeout; + millis_t timeout; blkCnt = (size + EspFlashBlockSize - 1) / EspFlashBlockSize; @@ -597,7 +603,7 @@ void upload_spin() { case uploading: // The ESP needs several milliseconds to recover from one packet before it will accept another if (getWifiTickDiff(esp_upload.lastAttemptTime, getWifiTick()) >= 15) { - unsigned int percentComplete; + uint16_t percentComplete; const uint32_t blkCnt = (esp_upload.fileSize + EspFlashBlockSize - 1) / EspFlashBlockSize; if (esp_upload.uploadBlockNumber < blkCnt) { esp_upload.uploadResult = flashWriteBlock(0, 0); diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_upload.h b/Marlin/src/lcd/extui/mks_ui/wifi_upload.h index 2daa505d90..524fb28f85 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_upload.h +++ b/Marlin/src/lcd/extui/mks_ui/wifi_upload.h @@ -59,8 +59,8 @@ typedef struct { UploadState state; uint32_t retriesPerBaudRate; uint32_t connectAttemptNumber; - uint32_t lastAttemptTime; - uint32_t lastResetTime; + millis_t lastAttemptTime; + millis_t lastResetTime; uint32_t uploadBlockNumber; uint32_t uploadNextPercentToReport; EspUploadResult uploadResult; diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 66e531bde9..1b3bdaabdb 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -112,9 +112,9 @@ namespace ExtUI { static struct { - uint8_t printer_killed : 1; + bool printer_killed : 1; #if ENABLED(JOYSTICK) - uint8_t jogging : 1; + bool jogging : 1; #endif } flags; @@ -172,35 +172,6 @@ namespace ExtUI { if (!flags.printer_killed) thermalManager.task(); } - void enableHeater(const extruder_t extruder) { - #if HAS_HOTEND && HEATER_IDLE_HANDLER - thermalManager.reset_hotend_idle_timer(extruder - E0); - #else - UNUSED(extruder); - #endif - } - - void enableHeater(const heater_t heater) { - #if HEATER_IDLE_HANDLER - switch (heater) { - #if HAS_HEATED_BED - case BED: thermalManager.reset_bed_idle_timer(); return; - #endif - #if HAS_HEATED_CHAMBER - case CHAMBER: return; // Chamber has no idle timer - #endif - #if HAS_COOLER - case COOLER: return; // Cooler has no idle timer - #endif - default: - TERN_(HAS_HOTEND, thermalManager.reset_hotend_idle_timer(heater - H0)); - break; - } - #else - UNUSED(heater); - #endif - } - #if ENABLED(JOYSTICK) /** * Jogs in the direction given by the vector (dx, dy, dz). @@ -237,6 +208,39 @@ namespace ExtUI { } #endif + // + // Heaters locked / idle + // + + void enableHeater(const extruder_t extruder) { + #if HAS_HOTEND && HEATER_IDLE_HANDLER + thermalManager.reset_hotend_idle_timer(extruder - E0); + #else + UNUSED(extruder); + #endif + } + + void enableHeater(const heater_t heater) { + #if HEATER_IDLE_HANDLER + switch (heater) { + #if HAS_HEATED_BED + case BED: thermalManager.reset_bed_idle_timer(); return; + #endif + #if HAS_HEATED_CHAMBER + case CHAMBER: return; // Chamber has no idle timer + #endif + #if HAS_COOLER + case COOLER: return; // Cooler has no idle timer + #endif + default: + TERN_(HAS_HOTEND, thermalManager.reset_hotend_idle_timer(heater - H0)); + break; + } + #else + UNUSED(heater); + #endif + } + bool isHeaterIdle(const extruder_t extruder) { #if HAS_HOTEND && HEATER_IDLE_HANDLER return thermalManager.heater_idle[extruder - E0].timed_out; @@ -302,6 +306,9 @@ namespace ExtUI { return GET_TEMP_ADJUSTMENT(thermalManager.degTargetHotend(extruder - E0)); } + // + // Fan target/actual speed + // float getTargetFan_percent(const fan_t fan) { UNUSED(fan); return TERN0(HAS_FAN, thermalManager.fanSpeedPercent(fan - FAN0)); @@ -312,6 +319,9 @@ namespace ExtUI { return TERN0(HAS_FAN, thermalManager.scaledFanSpeedPercent(fan - FAN0)); } + // + // High level axis and extruder positions + // float getAxisPosition_mm(const axis_t axis) { return current_position[axis]; } @@ -349,6 +359,9 @@ namespace ExtUI { line_to_current_position(feedrate ?: manual_feedrate_mm_s.e); } + // + // Tool changing + // void setActiveTool(const extruder_t extruder, bool no_move) { #if HAS_MULTI_EXTRUDER const uint8_t e = extruder - E0; @@ -370,8 +383,14 @@ namespace ExtUI { extruder_t getActiveTool() { return getTool(active_extruder); } + // + // Moving axes and extruders + // bool isMoving() { return planner.has_blocks_queued(); } + // + // Motion might be blocked by NO_MOTION_BEFORE_HOMING + // bool canMove(const axis_t axis) { switch (axis) { #if IS_KINEMATIC || ENABLED(NO_MOTION_BEFORE_HOMING) @@ -385,20 +404,34 @@ namespace ExtUI { } } + // + // E Motion might be prevented by cold material + // bool canMove(const extruder_t extruder) { return !thermalManager.tooColdToExtrude(extruder - E0); } + // + // Host Keepalive, used by awaitingUserConfirm + // #if ENABLED(HOST_KEEPALIVE_FEATURE) GcodeSuite::MarlinBusyState getHostKeepaliveState() { return gcode.busy_state; } bool getHostKeepaliveIsPaused() { return gcode.host_keepalive_is_paused(); } #endif + // + // Soft Endstops Enabled/Disabled State + // + #if HAS_SOFTWARE_ENDSTOPS bool getSoftEndstopState() { return soft_endstop._enabled; } void setSoftEndstopState(const bool value) { soft_endstop._enabled = value; } #endif + // + // Trinamic Current / Bump Sensitivity + // + #if HAS_TRINAMIC_CONFIG float getAxisCurrent_mA(const axis_t axis) { switch (axis) { @@ -626,6 +659,10 @@ namespace ExtUI { } #endif + // + // Planner Accessors / Setters + // + float getAxisSteps_per_mm(const axis_t axis) { return planner.settings.axis_steps_per_mm[axis]; } @@ -932,7 +969,7 @@ namespace ExtUI { void moveToMeshPoint(const xy_uint8_t &pos, const_float_t z) { #if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL) - const feedRate_t old_feedrate = feedrate_mm_s; + REMEMBER(fr, feedrate_mm_s); const float x_target = MESH_MIN_X + pos.x * (MESH_X_DIST), y_target = MESH_MIN_Y + pos.y * (MESH_Y_DIST); if (x_target != current_position.x || y_target != current_position.y) { @@ -947,7 +984,6 @@ namespace ExtUI { feedrate_mm_s = Z_PROBE_FEEDRATE_FAST; destination.z = z; prepare_line_to_destination(); - feedrate_mm_s = old_feedrate; #else UNUSED(pos); UNUSED(z); @@ -1102,6 +1138,7 @@ namespace ExtUI { bool isMediaInserted() { return TERN0(HAS_MEDIA, IS_SD_INSERTED()); } + // Pause/Resume/Stop are implemented in MarlinUI void pausePrint() { ui.pause_print(); } void resumePrint() { ui.resume_print(); } void stopPrint() { ui.abort_print(); } diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index c2ce52ba4c..5e5c5d3fb7 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -43,8 +43,10 @@ ****************************************************************************/ #include "../../inc/MarlinConfig.h" + #include "../marlinui.h" #include "../../gcode/gcode.h" + #if M600_PURGE_MORE_RESUMABLE #include "../../feature/pause.h" #endif @@ -71,6 +73,28 @@ namespace ExtUI { typedef float bed_mesh_t[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; #endif + /** + * The Extensible UI API is a utility class that can be used to implement: + * - An LCD view that responds to standard events, e.g., onMediaInserted(...) + * - An LCD that polls firmware states and settings in a standard manner. + * (e.g., With tool indexes and extruder indexes). + * - Standard hooks to send data to a serial-based controller. + * + * ExtUI is best used when: + * - The display handles LCD touch / buttons so the firmware doesn't see these events. + * - Commands and value edits are sent over serial to Marlin as G-codes. + * - The display can get data from Marlin, but is not necessarily drawn by Marlin. + * - The display cannot implement a MarlinUI menu. + * - The display is implemented with code callbacks alongside ExtUI callbacks. + * + * Building an ExtUI layer: + * - Start by making an lcd/extui subfolder. Copy 'example' or another display. + * - Many of these methods are optional. Implement them according to your UI needs. + * - If your display needs information from Marlin, add an accessor to ExtUI. + * - If some addition seems like it should be standard part of ExtUI, submit a PR with the new + * methods added to this API. Implement in the ExtUI example and/or with some existing displays. + */ + bool isMoving(); bool isAxisPositionKnown(const axis_t); bool isAxisPositionKnown(const extruder_t); @@ -88,11 +112,6 @@ namespace ExtUI { bool getHostKeepaliveIsPaused(); #endif - bool isHeaterIdle(const heater_t); - bool isHeaterIdle(const extruder_t); - void enableHeater(const heater_t); - void enableHeater(const extruder_t); - #if ENABLED(JOYSTICK) void jog(const xyz_float_t &dir); void _joystick_update(xyz_float_t &norm_jog); @@ -100,7 +119,7 @@ namespace ExtUI { /** * Getters and setters - * Should be used by the EXTENSIBLE_UI to query or change Marlin's state. + * Use to query or change Marlin's state. */ PGM_P getFirmwareName_str(); @@ -109,6 +128,7 @@ namespace ExtUI { void setSoftEndstopState(const bool); #endif + // Trinamic Current / Bump Sensitivity #if HAS_TRINAMIC_CONFIG float getAxisCurrent_mA(const axis_t); float getAxisCurrent_mA(const extruder_t); @@ -119,37 +139,50 @@ namespace ExtUI { void setTMCBumpSensitivity(const_float_t, const axis_t); #endif + // Actual and target accessors, by Heater ID, Extruder ID, Fan ID + void enableHeater(const heater_t); + void enableHeater(const extruder_t); + bool isHeaterIdle(const heater_t); + bool isHeaterIdle(const extruder_t); celsius_float_t getActualTemp_celsius(const heater_t); celsius_float_t getActualTemp_celsius(const extruder_t); celsius_float_t getTargetTemp_celsius(const heater_t); celsius_float_t getTargetTemp_celsius(const extruder_t); - float getTargetFan_percent(const fan_t); float getActualFan_percent(const fan_t); + float getTargetFan_percent(const fan_t); + + // High level positions, by Axis ID, Extruder ID float getAxisPosition_mm(const axis_t); float getAxisPosition_mm(const extruder_t); + // Axis steps-per-mm, by Axis ID, Extruder ID float getAxisSteps_per_mm(const axis_t); float getAxisSteps_per_mm(const extruder_t); + // Speed and acceleration limits, per Axis ID or Extruder ID feedRate_t getAxisMaxFeedrate_mm_s(const axis_t); feedRate_t getAxisMaxFeedrate_mm_s(const extruder_t); float getAxisMaxAcceleration_mm_s2(const axis_t); float getAxisMaxAcceleration_mm_s2(const extruder_t); + // Standard speeds, as set in the planner feedRate_t getMinFeedrate_mm_s(); feedRate_t getMinTravelFeedrate_mm_s(); feedRate_t getFeedrate_mm_s(); + // Standard accelerations, as set in the planner float getPrintingAcceleration_mm_s2(); float getRetractAcceleration_mm_s2(); float getTravelAcceleration_mm_s2(); + // A speed multiplier for overall printing float getFeedrate_percent(); + // The flow percentage of an extruder int16_t getFlow_percent(const extruder_t); + // Progress / Elapsed Time inline uint8_t getProgress_percent() { return ui.get_progress_percent(); } - #if HAS_PRINT_PROGRESS_PERMYRIAD inline uint16_t getProgress_permyriad() { return ui.get_progress_permyriad(); } #endif - uint32_t getProgress_seconds_elapsed(); + // Material Preheat Presets #if HAS_PREHEAT uint16_t getMaterial_preset_E(const uint16_t); #if HAS_HEATED_BED @@ -157,6 +190,7 @@ namespace ExtUI { #endif #endif + // IDEX Machine Mode #if ENABLED(DUAL_X_CARRIAGE) uint8_t getIDEX_Mode(); #endif @@ -169,16 +203,18 @@ namespace ExtUI { #endif #if HAS_LEVELING + // Global leveling state, events bool getLevelingActive(); void setLevelingActive(const bool); bool getMeshValid(); + void onLevelingStart(); + void onLevelingDone(); #if HAS_MESH + // Mesh data, utilities, events bed_mesh_t& getMeshArray(); float getMeshPoint(const xy_uint8_t &pos); void setMeshPoint(const xy_uint8_t &pos, const_float_t zval); void moveToMeshPoint(const xy_uint8_t &pos, const_float_t z); - void onLevelingStart(); - void onLevelingDone(); void onMeshUpdate(const int8_t xpos, const int8_t ypos, const_float_t zval); inline void onMeshUpdate(const xy_int8_t &pos, const_float_t zval) { onMeshUpdate(pos.x, pos.y, zval); } @@ -197,10 +233,12 @@ namespace ExtUI { #endif #endif + // Send an 'M876 S' host response #if ENABLED(HOST_PROMPT_SUPPORT) void setHostResponse(const uint8_t); #endif + // Provide a simulated click to MarlinUI inline void simulateUserClick() { #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, DWIN_CREALITY_LCD_JYERSUI) ui.lcd_clicked = true; @@ -208,6 +246,7 @@ namespace ExtUI { } #if ENABLED(PRINTCOUNTER) + // Printcounter strings (See nextion_tft.cpp) char* getFailedPrints_str(char buffer[21]); char* getTotalPrints_str(char buffer[21]); char* getFinishedPrints_str(char buffer[21]); @@ -216,12 +255,17 @@ namespace ExtUI { char* getFilamentUsed_str(char buffer[21]); #endif + // Temperature Control void setTargetTemp_celsius(const_float_t, const heater_t); void setTargetTemp_celsius(const_float_t, const extruder_t); void setTargetFan_percent(const_float_t, const fan_t); void coolDown(); + + // Motion Control void setAxisPosition_mm(const_float_t, const axis_t, const feedRate_t=0); void setAxisPosition_mm(const_float_t, const extruder_t, const feedRate_t=0); + + // Planner Control void setAxisSteps_per_mm(const_float_t, const axis_t); void setAxisSteps_per_mm(const_float_t, const extruder_t); void setAxisMaxFeedrate_mm_s(const feedRate_t, const axis_t); @@ -236,20 +280,25 @@ namespace ExtUI { void setTravelAcceleration_mm_s2(const_float_t); void setFeedrate_percent(const_float_t); void setFlow_percent(const int16_t, const extruder_t); + + // Waiting for User Interaction bool awaitingUserConfirm(); void setUserConfirmed(); #if M600_PURGE_MORE_RESUMABLE + // "Purge More" has a control screen void setPauseMenuResponse(PauseMenuResponse); extern PauseMessage pauseModeStatus; PauseMode getPauseMode(); #endif #if ENABLED(LIN_ADVANCE) + // Linear Advance Control float getLinearAdvance_mm_mm_s(const extruder_t); void setLinearAdvance_mm_mm_s(const_float_t, const extruder_t); #endif + // JD or Jerk Control #if HAS_JUNCTION_DEVIATION float getJunctionDeviation_mm(); void setJunctionDeviation_mm(const_float_t); @@ -260,10 +309,12 @@ namespace ExtUI { void setAxisMaxJerk_mm_s(const_float_t, const extruder_t); #endif + // Tool Changing extruder_t getTool(const uint8_t extruder); extruder_t getActiveTool(); void setActiveTool(const extruder_t, bool no_move); + // Babystepping (axis, probe offset) #if ENABLED(BABYSTEPPING) int16_t mmToWholeSteps(const_float_t mm, const axis_t axis); float mmFromWholeSteps(int16_t steps, const axis_t axis); @@ -272,20 +323,24 @@ namespace ExtUI { void smartAdjustAxis_steps(const int16_t steps, const axis_t axis, bool linked_nozzles); #endif + // Hotend Offsets #if HAS_HOTEND_OFFSET float getNozzleOffset_mm(const axis_t, const extruder_t); void setNozzleOffset_mm(const_float_t, const axis_t, const extruder_t); void normalizeNozzleOffset(const axis_t axis); #endif + // The Probe Z Offset float getZOffset_mm(); void setZOffset_mm(const_float_t); + // The Probe XYZ Offset #if HAS_BED_PROBE float getProbeOffset_mm(const axis_t); void setProbeOffset_mm(const_float_t, const axis_t); #endif + // Backlash Control #if ENABLED(BACKLASH_GCODE) float getAxisBacklash_mm(const axis_t); void setAxisBacklash_mm(const_float_t, const axis_t); @@ -299,6 +354,7 @@ namespace ExtUI { #endif #endif + // Filament Runout Sensor #if HAS_FILAMENT_SENSOR bool getFilamentRunoutEnabled(); void setFilamentRunoutEnabled(const bool); @@ -311,6 +367,7 @@ namespace ExtUI { #endif #endif + // Case Light Control #if ENABLED(CASE_LIGHT_ENABLE) bool getCaseLightState(); void setCaseLightState(const bool); @@ -321,11 +378,13 @@ namespace ExtUI { #endif #endif + // Power-Loss Recovery #if ENABLED(POWER_LOSS_RECOVERY) bool getPowerLossRecoveryEnabled(); void setPowerLossRecoveryEnabled(const bool); #endif + // Hotend PID #if ENABLED(PIDTEMP) float getPID_Kp(const extruder_t); float getPID_Ki(const extruder_t); @@ -334,6 +393,7 @@ namespace ExtUI { void startPIDTune(const celsius_t, extruder_t); #endif + // Bed PID #if ENABLED(PIDTEMPBED) float getBedPID_Kp(); float getBedPID_Ki(); @@ -360,8 +420,7 @@ namespace ExtUI { /** * Media access routines - * - * Should be used by the EXTENSIBLE_UI to operate on files + * Use these to operate on files */ bool isMediaInserted(); bool isPrintingFromMediaPaused(); @@ -396,8 +455,7 @@ namespace ExtUI { /** * Event callback routines - * - * Should be declared by EXTENSIBLE_UI and will be called by Marlin + * Must be defined, and will be called by Marlin as needed */ void onStartup(); void onIdle(); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 9273eb105c..9dc0ec7cc3 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -482,7 +482,6 @@ namespace Language_pl { LSTR MSG_GAMES = _UxGT("Gry"); - LSTR MSG_EDIT_PASSWORD = _UxGT("Zmień hasło"); LSTR MSG_LOGIN_REQUIRED = _UxGT("Wymagane zalogowanie"); LSTR MSG_PASSWORD_SETTINGS = _UxGT("Ustawienia hasła"); diff --git a/Marlin/src/lcd/language/language_test.h b/Marlin/src/lcd/language/language_test.h index 20b5a7e686..c2ead69203 100644 --- a/Marlin/src/lcd/language/language_test.h +++ b/Marlin/src/lcd/language/language_test.h @@ -44,22 +44,18 @@ // Kanji (an other Japanese symbol set) uses far more than two codepages. So currently I don't see a chance to map the Unicodes. Its not // impossible to have a close to direct mapping but will need giant conversion tables and fonts (we don't want to have in a embedded system). - // Select the better font for full graphic displays. //#define DISPLAY_CHARSET_ISO10646_1 //#define DISPLAY_CHARSET_ISO10646_5 //#define DISPLAY_CHARSET_ISO10646_GREEK //#define DISPLAY_CHARSET_ISO10646_KANA - - // next 5 lines select variants in this file only #define DISPLAYTEST //#define WEST //#define CYRIL //#define KANA - // TESTSTRINGS #define STRG_ASCII_2 _UxGT(" !\"#$%&'()*+,-./") diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index e678cd872e..71a5c4ccd6 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -833,7 +833,6 @@ namespace Language_uk { LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("Не забудь зберегти!"); LSTR MSG_PASSWORD_REMOVED = _UxGT("Пароль видалений"); - // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 0d8af1be31..da252c80fd 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -419,7 +419,7 @@ void MarlinUI::init() { #if !HAS_GRAPHICAL_TFT - void _wrap_string(uint8_t &col, uint8_t &row, const char * const string, read_byte_cb_t cb_read_byte, bool wordwrap/*=false*/) { + void _wrap_string(uint8_t &col, uint8_t &row, const char * const string, read_byte_cb_t cb_read_byte, const bool wordwrap/*=false*/) { SETCURSOR(col, row); if (!string) return; @@ -487,10 +487,6 @@ void MarlinUI::init() { #endif // HAS_MARLINUI_MENU - //////////////////////////////////////////// - ///////////// Keypad Handling ////////////// - //////////////////////////////////////////// - #if IS_RRW_KEYPAD && HAS_ENCODER_ACTION volatile uint8_t MarlinUI::keypad_buttons; @@ -771,10 +767,6 @@ void MarlinUI::init() { #endif } - //////////////////////////////////////////// - /////////////// Manual Move //////////////// - //////////////////////////////////////////// - #if HAS_MARLINUI_MENU ManualMove MarlinUI::manual_move{}; @@ -881,8 +873,8 @@ void MarlinUI::init() { void MarlinUI::external_encoder() { if (external_control && encoderDiff) { bedlevel.encoder_diff += encoderDiff; // Encoder for UBL G29 mesh editing - encoderDiff = 0; // Hide encoder events from the screen handler - refresh(LCDVIEW_REDRAW_NOW); // ...but keep the refresh. + encoderDiff = 0; // Hide encoder events from the screen handler + refresh(LCDVIEW_REDRAW_NOW); // ...but keep the refresh. } } @@ -1424,10 +1416,6 @@ void MarlinUI::init() { #if HAS_STATUS_MESSAGE - //////////////////////////////////////////// - ////////////// Status Message ////////////// - //////////////////////////////////////////// - #if ENABLED(EXTENSIBLE_UI) #include "extui/ui_api.h" #endif @@ -1464,7 +1452,6 @@ void MarlinUI::init() { /** * Reset the status message */ - void MarlinUI::reset_status(const bool no_welcome) { #if SERVICE_INTERVAL_1 > 0 static PGMSTR(service1, "> " SERVICE_NAME_1 "!"); @@ -1707,13 +1694,13 @@ void MarlinUI::init() { #if HAS_TOUCH_BUTTONS - // - // Screen Click - // - On menu screens move directly to the touched item - // - On menu screens, right side (last 3 cols) acts like a scroll - half up => prev page, half down = next page - // - On select screens (and others) touch the Right Half for +, Left Half for - - // - On edit screens, touch Up Half for -, Bottom Half to + - // + /** + * Screen Click + * - On menu screens move directly to the touched item + * - On menu screens, right side (last 3 cols) acts like a scroll - half up => prev page, half down = next page + * - On select screens (and others) touch the Left Half for ←, Right Half for → + * - On edit screens, touch Top Half for ↑, Bottom Half for ↓ + */ void MarlinUI::screen_click(const uint8_t row, const uint8_t col, const uint8_t, const uint8_t) { const millis_t now = millis(); if (PENDING(now, next_button_update_ms)) return; diff --git a/Marlin/src/lcd/menu/game/invaders.cpp b/Marlin/src/lcd/menu/game/invaders.cpp index 1cb3e5bf3f..588523854f 100644 --- a/Marlin/src/lcd/menu/game/invaders.cpp +++ b/Marlin/src/lcd/menu/game/invaders.cpp @@ -193,7 +193,6 @@ inline void reset_invaders() { reset_bullets(); } - inline void spawn_ufo() { idat.ufov = random(0, 2) ? 1 : -1; idat.ufox = idat.ufov > 0 ? -(UFO_W) : LCD_PIXEL_WIDTH - 1; diff --git a/Marlin/src/lcd/menu/game/invaders.h b/Marlin/src/lcd/menu/game/invaders.h index c99e6c16ae..a3ae6ffaed 100644 --- a/Marlin/src/lcd/menu/game/invaders.h +++ b/Marlin/src/lcd/menu/game/invaders.h @@ -53,8 +53,8 @@ typedef struct { uint8_t bugs[INVADER_ROWS], shooters[(INVADER_ROWS) * (INVADER_COLS)]; int8_t ufox, ufov; bool game_blink; - int8_t laser_col() { return ((laser.x - pos.x) / (INVADER_COL_W)); }; - int8_t laser_row() { return ((laser.y - pos.y + 2) / (INVADER_ROW_H)); }; + int8_t laser_col() { return ((laser.x - pos.x) / (INVADER_COL_W)); } + int8_t laser_row() { return ((laser.y - pos.y + 2) / (INVADER_ROW_H)); } } invaders_data_t; class InvadersGame : MarlinGame { public: static void enter_game(), game_screen(); }; diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 399ac8a149..c269871c02 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -145,6 +145,7 @@ typedef union { uint32_t uint32; celsius_t celsius; } chimera_t; + extern chimera_t editable; // Base class for Menu Edit Items diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index 2a6a568062..0902466b95 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -242,6 +242,9 @@ class MenuItem_bool : public MenuEditItemBase { #define START_SCREEN() SCREEN_OR_MENU_LOOP(false) #define START_MENU() SCREEN_OR_MENU_LOOP(true) #define NEXT_ITEM() (++_thisItemNr) +#define MY_LINE() (_menuLineNr == _thisItemNr) +#define HIGHLIGHTED() (encoderLine == _thisItemNr) +#define CLICKED() (HIGHLIGHTED() && ui.use_click()) #define SKIP_ITEM() NEXT_ITEM() #define END_SCREEN() } screen_items = _thisItemNr #define END_MENU() END_SCREEN(); UNUSED(_skipStatic) @@ -274,19 +277,19 @@ class MenuItem_bool : public MenuEditItemBase { #define _MENU_INNER_F(TYPE, USE_MULTIPLIER, FLABEL, V...) do { \ FSTR_P const flabel = FLABEL; \ - if (encoderLine == _thisItemNr && ui.use_click()) { \ + if (CLICKED()) { \ _MENU_ITEM_MULTIPLIER_CHECK(USE_MULTIPLIER); \ MenuItem_##TYPE::action(flabel, ##V); \ if (ui.screen_changed) return; \ } \ if (ui.should_draw()) \ MenuItem_##TYPE::draw \ - (encoderLine == _thisItemNr, _lcdLineNr, flabel, ##V); \ + (HIGHLIGHTED(), _lcdLineNr, flabel, ##V); \ }while(0) // Item with optional data #define _MENU_ITEM_F(TYPE, V...) do { \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ _skipStatic = false; \ _MENU_INNER_F(TYPE, ##V); \ } \ @@ -295,7 +298,7 @@ class MenuItem_bool : public MenuEditItemBase { // Item with index value, C-string, and optional data #define _MENU_ITEM_N_S_F(TYPE, N, S, V...) do{ \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ _skipStatic = false; \ MenuItemBase::init(N, S); \ _MENU_INNER_F(TYPE, ##V); \ @@ -305,7 +308,7 @@ class MenuItem_bool : public MenuEditItemBase { // Item with index value and F-string #define _MENU_ITEM_N_f_F(TYPE, N, f, V...) do{ \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ _skipStatic = false; \ MenuItemBase::init(N, f); \ _MENU_INNER_F(TYPE, ##V); \ @@ -315,7 +318,7 @@ class MenuItem_bool : public MenuEditItemBase { // Item with index value #define _MENU_ITEM_N_F(TYPE, N, V...) do{ \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ _skipStatic = false; \ MenuItemBase::init(N); \ _MENU_INNER_F(TYPE, ##V); \ @@ -325,7 +328,7 @@ class MenuItem_bool : public MenuEditItemBase { // Items with a unique string #define _MENU_ITEM_S_F(TYPE, S, V...) do{ \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ _skipStatic = false; \ MenuItemBase::init(0, S); \ _MENU_INNER_F(TYPE, ##V); \ @@ -335,7 +338,7 @@ class MenuItem_bool : public MenuEditItemBase { // Items with a unique F-string #define _MENU_ITEM_f_F(TYPE, f, V...) do{ \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ _skipStatic = false; \ MenuItemBase::init(0, f); \ _MENU_INNER_F(TYPE, ##V); \ @@ -356,13 +359,13 @@ class MenuItem_bool : public MenuEditItemBase { } while(0) #define STATIC_ITEM_F(FLABEL, V...) do{ \ - if (_menuLineNr == _thisItemNr) \ + if (MY_LINE()) \ STATIC_ITEM_INNER_F(FLABEL, ##V); \ NEXT_ITEM(); \ } while(0) #define STATIC_ITEM_N_F(N, FLABEL, V...) do{ \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ MenuItemBase::init(N); \ STATIC_ITEM_INNER_F(FLABEL, ##V); \ } \ @@ -490,18 +493,18 @@ class MenuItem_bool : public MenuEditItemBase { #define EDIT_ITEM_FAST_f(TYPE, f, LABEL, V...) EDIT_ITEM_FAST_f_F(TYPE, f, GET_TEXT_F(LABEL), ##V) #define _CONFIRM_ITEM_INNER_F(FLABEL, V...) do { \ - if (encoderLine == _thisItemNr && ui.use_click()) { \ + if (CLICKED()) { \ ui.push_current_screen(); \ ui.goto_screen([]{MenuItem_confirm::select_screen(V);}); \ return; \ } \ if (ui.should_draw()) MenuItem_confirm::draw \ - (encoderLine == _thisItemNr, _lcdLineNr, FLABEL, ##V); \ + (HIGHLIGHTED(), _lcdLineNr, FLABEL, ##V); \ }while(0) // Indexed items set a global index value and optional data #define _CONFIRM_ITEM_F(FLABEL, V...) do { \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ _skipStatic = false; \ _CONFIRM_ITEM_INNER_F(FLABEL, ##V); \ } \ @@ -510,7 +513,7 @@ class MenuItem_bool : public MenuEditItemBase { // Indexed items set a global index value #define _CONFIRM_ITEM_N_S_F(N, S, V...) do{ \ - if (_menuLineNr == _thisItemNr) { \ + if (MY_LINE()) { \ _skipStatic = false; \ MenuItemBase::init(N, S); \ _CONFIRM_ITEM_INNER_F(TYPE, ##V); \ @@ -571,10 +574,10 @@ class MenuItem_bool : public MenuEditItemBase { }while(0) #if FAN_COUNT > 1 - #define FAN_EDIT_ITEMS(F) _FAN_EDIT_ITEMS(F,FAN_SPEED_N) + #define FAN_EDIT_ITEMS(F) _FAN_EDIT_ITEMS(F, FAN_SPEED_N) #endif - #define SNFAN(N) (ENABLED(SINGLENOZZLE_STANDBY_FAN) && !HAS_FAN##N && EXTRUDERS > N) + #define SNFAN(N) (ENABLED(SINGLENOZZLE_STANDBY_FAN) && !HAS_FAN##N && (N) < EXTRUDERS) #if SNFAN(1) || SNFAN(2) || SNFAN(3) || SNFAN(4) || SNFAN(5) || SNFAN(6) || SNFAN(7) #define DEFINE_SINGLENOZZLE_ITEM() \ diff --git a/Marlin/src/lcd/tft/tft_color.h b/Marlin/src/lcd/tft/tft_color.h index a8668179e5..bfc47a517f 100644 --- a/Marlin/src/lcd/tft/tft_color.h +++ b/Marlin/src/lcd/tft/tft_color.h @@ -30,8 +30,8 @@ #define COLOR(color) RGB(((color >> 16) & 0xFF), ((color >> 8) & 0xFF), (color & 0xFF)) #define HALF(color) RGB(RED(color) >> 1, GREEN(color) >> 1, BLUE(color) >> 1) -// 16 bit color generator: https://ee-programming-notepad.blogspot.com/2016/10/16-bit-color-generator-picker.html -// RGB565 color picker: https://trolsoft.ru/en/articles/rgb565-color-picker +// RGB565 color picker: https://embeddednotepad.com/page/rgb565-color-picker +// Hex code to color name: https://www.color-name.com/ #define COLOR_BLACK 0x0000 // #000000 #define COLOR_WHITE 0xFFFF // #FFFFFF diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index 1665e9ab77..ff2fb0e1c8 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -76,7 +76,6 @@ void Touch::add_control(TouchControlType type, uint16_t x, uint16_t y, uint16_t } void Touch::idle() { - uint16_t i; int16_t _x, _y; if (!enabled) return; @@ -121,7 +120,7 @@ void Touch::idle() { current_control = nullptr; } else { - for (i = 0; i < controls_count; i++) { + for (uint16_t i = 0; i < controls_count; i++) { if ((WITHIN(x, controls[i].x, controls[i].x + controls[i].width) && WITHIN(y, controls[i].y, controls[i].y + controls[i].height)) || (TERN(TOUCH_SCREEN_CALIBRATION, controls[i].type == CALIBRATE, false))) { touch_control_type = controls[i].type; touch(&controls[i]); @@ -273,12 +272,14 @@ bool Touch::get_point(int16_t *x, int16_t *y) { #elif ENABLED(TFT_TOUCH_DEVICE_GT911) bool is_touched = (TOUCH_ORIENTATION == TOUCH_PORTRAIT ? io.getPoint(y, x) : io.getPoint(x, y)); #endif + #if HAS_TOUCH_SLEEP if (is_touched) wakeUp(); else if (!isSleeping() && ELAPSED(millis(), next_sleep_ms) && ui.on_status_screen()) sleepTimeout(); #endif + return is_touched; } diff --git a/Marlin/src/lcd/tft/touch.h b/Marlin/src/lcd/tft/touch.h index eab85604f1..3d58f684ed 100644 --- a/Marlin/src/lcd/tft/touch.h +++ b/Marlin/src/lcd/tft/touch.h @@ -108,7 +108,7 @@ class Touch { static bool get_point(int16_t *x, int16_t *y); static void touch(touch_control_t *control); - static void hold(touch_control_t *control, millis_t delay = 0); + static void hold(touch_control_t *control, millis_t delay=0); public: static void init(); @@ -130,7 +130,7 @@ class Touch { static void sleepTimeout(); static void wakeUp(); #endif - static void add_control(TouchControlType type, uint16_t x, uint16_t y, uint16_t width, uint16_t height, intptr_t data = 0); + static void add_control(TouchControlType type, uint16_t x, uint16_t y, uint16_t width, uint16_t height, intptr_t data=0); }; extern Touch touch; diff --git a/Marlin/src/lcd/tft_io/ili9328.h b/Marlin/src/lcd/tft_io/ili9328.h index b50517adfe..591a4ec2ed 100644 --- a/Marlin/src/lcd/tft_io/ili9328.h +++ b/Marlin/src/lcd/tft_io/ili9328.h @@ -39,7 +39,7 @@ #define ILI9328_ETMOD_ID0 0x0010 // 0 - Horizontal Decrement / 1 - Horizontal Increment #define ILI9328_ETMOD_AM 0x0008 // 0 - Horizontal / 1 - Vertical -// MKS Robin TFT v1.1 - 320x240 ; Cable on the left side +// MKS Robin TFT v1.1 - 320x240 ; FPC cable on the left side #if TFT_ROTATION == TFT_ROTATE_180 #define ILI9328_DRVCTL_DATA 0x0000 @@ -65,7 +65,6 @@ #define ILI9328_ETMOD_DATA (ILI9328_ETMOD_ORIENTATION) | (ILI9328_ETMOD_COLOR) - #define ILI9328_RDDID 0x00 // ID code - 0x9328 #define ILI9328_DRVCTL 0x01 // Driver Output Control #define ILI9328_LCDCTL 0x02 // LCD Driving Wave Control @@ -128,7 +127,6 @@ #define ILI9328_RDOTP 0xA2 // OTP VCM Status and Enable #define ILI9328_OTPPKEY 0xA5 // OTP Programming ID Key - static const uint16_t ili9328_init[] = { DATASIZE_16BIT, ESC_REG(ILI9328_DRVCTL), ILI9328_DRVCTL_DATA, diff --git a/Marlin/src/lcd/tft_io/ili9341.h b/Marlin/src/lcd/tft_io/ili9341.h index dda326df6d..e48db82838 100644 --- a/Marlin/src/lcd/tft_io/ili9341.h +++ b/Marlin/src/lcd/tft_io/ili9341.h @@ -52,7 +52,7 @@ #define ILI9341_NOP 0x00 // No Operation #define ILI9341_SWRESET 0x01 // Software Reset -#define ILI9341_RDDIDIF 0x04 // Read display identification information +#define ILI9341_RDDIDIF 0x04 // Read Display Identification Information #define ILI9341_RDDST 0x09 // Read Display Status #define ILI9341_RDDPM 0x0A // Read Display Power Mode #define ILI9341_RDDMADCTL 0x0B // Read Display MADCTL @@ -136,7 +136,6 @@ #define ILI9341_IFCTL 0xF6 // Interface Control #define ILI9341_PUMPRCTL 0xF7 // Pump ratio control - static const uint16_t ili9341_init[] = { DATASIZE_8BIT, ESC_REG(ILI9341_SWRESET), ESC_DELAY(100), diff --git a/Marlin/src/lcd/tft_io/ili9488.h b/Marlin/src/lcd/tft_io/ili9488.h index e71c0d16d7..aedbaa1358 100644 --- a/Marlin/src/lcd/tft_io/ili9488.h +++ b/Marlin/src/lcd/tft_io/ili9488.h @@ -25,13 +25,13 @@ #include "../../inc/MarlinConfig.h" -#define ILI9488_MADCTL_MY 0x80 // Row Address Order -#define ILI9488_MADCTL_MX 0x40 // Column Address Order -#define ILI9488_MADCTL_MV 0x20 // Row/Column Exchange -#define ILI9488_MADCTL_ML 0x10 // Vertical Refresh Order -#define ILI9488_MADCTL_BGR 0x08 // RGB-BGR ORDER -#define ILI9488_MADCTL_RGB 0x00 -#define ILI9488_MADCTL_MH 0x04 // Horizontal Refresh Order +#define ILI9488_MADCTL_MY 0x80 // Row Address Order +#define ILI9488_MADCTL_MX 0x40 // Column Address Order +#define ILI9488_MADCTL_MV 0x20 // Row/Column Exchange +#define ILI9488_MADCTL_ML 0x10 // Vertical Refresh Order +#define ILI9488_MADCTL_BGR 0x08 // RGB-BGR ORDER +#define ILI9488_MADCTL_RGB 0x00 +#define ILI9488_MADCTL_MH 0x04 // Horizontal Refresh Order #define ILI9488_ORIENTATION_UP ILI9488_MADCTL_MY // 320x480 ; Cable on the upper side #define ILI9488_ORIENTATION_RIGHT ILI9488_MADCTL_MV // 480x320 ; Cable on the right side diff --git a/Marlin/src/lcd/tft_io/r65105.h b/Marlin/src/lcd/tft_io/r65105.h index 8be2afe442..70443a0e04 100644 --- a/Marlin/src/lcd/tft_io/r65105.h +++ b/Marlin/src/lcd/tft_io/r65105.h @@ -41,7 +41,7 @@ #define R61505_DRVCTRL_GS 0x8000 // Gate Scan direction -// MKS Robin TFT v1.1 - 320x240 ; Cable on the left side +// MKS Robin TFT v1.1 - 320x240 ; FPC cable on the left side #if TFT_ROTATION == TFT_ROTATE_180 #define R61505_DRVCTL_DATA 0x0000 @@ -67,7 +67,6 @@ #define R61505_ETMOD_DATA (R61505_ETMOD_ORIENTATION) | (R61505_ETMOD_COLOR) - #define R61505_RDDID 0x00 // ID code - 0x1505 #define R61505_DRVCTL 0x01 // Driver Output Control #define R61505_LCDCTL 0x02 // LCD Driving Wave Control @@ -129,7 +128,6 @@ #define R61505_OSC_CTRL 0xA4 // Oscillation Control - static const uint16_t r61505_init[] = { DATASIZE_16BIT, ESC_REG(R61505_DRVCTL), R61505_DRVCTL_DATA, diff --git a/Marlin/src/lcd/tft_io/tft_io.h b/Marlin/src/lcd/tft_io/tft_io.h index d6f178a020..4dfbbffabe 100644 --- a/Marlin/src/lcd/tft_io/tft_io.h +++ b/Marlin/src/lcd/tft_io/tft_io.h @@ -95,7 +95,7 @@ #endif #ifndef TFT_DRIVER - #define TFT_DRIVER AUTO + #define TFT_DRIVER AUTO #endif #define ESC_REG(x) 0xFFFF, 0x00FF & (uint16_t)x diff --git a/Marlin/src/lcd/tft_io/touch_calibration.h b/Marlin/src/lcd/tft_io/touch_calibration.h index 030b4977db..e903c90d99 100644 --- a/Marlin/src/lcd/tft_io/touch_calibration.h +++ b/Marlin/src/lcd/tft_io/touch_calibration.h @@ -27,7 +27,6 @@ #ifndef TOUCH_SCREEN_CALIBRATION_PRECISION #define TOUCH_SCREEN_CALIBRATION_PRECISION 80 #endif - #ifndef TOUCH_SCREEN_HOLD_TO_CALIBRATE_MS #define TOUCH_SCREEN_HOLD_TO_CALIBRATE_MS 2500 #endif diff --git a/Marlin/src/lcd/thermistornames.h b/Marlin/src/lcd/thermistornames.h index 54542bed4e..71f48775bd 100644 --- a/Marlin/src/lcd/thermistornames.h +++ b/Marlin/src/lcd/thermistornames.h @@ -35,15 +35,17 @@ #if THERMISTOR_ID == 1000 #define THERMISTOR_NAME "User Parameters" -// Thermcouples +// SPI RTD/Thermocouple Boards #elif THERMISTOR_ID == -5 #define THERMISTOR_NAME "MAX31865" -#elif THERMISTOR_ID == -4 - #define THERMISTOR_NAME "AD8495" #elif THERMISTOR_ID == -3 #define THERMISTOR_NAME "MAX31855" #elif THERMISTOR_ID == -2 #define THERMISTOR_NAME "MAX6675" + +// Analog Thermocouple Boards +#elif THERMISTOR_ID == -4 + #define THERMISTOR_NAME "AD8495" #elif THERMISTOR_ID == -1 #define THERMISTOR_NAME "AD595" @@ -94,44 +96,54 @@ #define THERMISTOR_NAME "E3104FXT (alt)" #elif THERMISTOR_ID == 13 #define THERMISTOR_NAME "Hisens 3950" +#elif THERMISTOR_ID == 14 + #define THERMISTOR_NAME "100k Ender-5 S1" #elif THERMISTOR_ID == 15 #define THERMISTOR_NAME "100k JGAurora A5" +#elif THERMISTOR_ID == 17 + #define THERMISTOR_NAME "100k Dagoma NTC" #elif THERMISTOR_ID == 18 #define THERMISTOR_NAME "ATC Semitec 204GT-2" -#elif THERMISTOR_ID == 20 - #define THERMISTOR_NAME "Pt100 UltiMB 5v" -#elif THERMISTOR_ID == 21 - #define THERMISTOR_NAME "Pt100 UltiMB 3.3v" -#elif THERMISTOR_ID == 201 - #define THERMISTOR_NAME "Pt100 OverLord" #elif THERMISTOR_ID == 60 #define THERMISTOR_NAME "Makers Tool" #elif THERMISTOR_ID == 70 #define THERMISTOR_NAME "Hephestos 2" #elif THERMISTOR_ID == 75 #define THERMISTOR_NAME "MGB18" -#elif THERMISTOR_ID == 99 - #define THERMISTOR_NAME "100k with 10k pull-up" -// Modified thermistors -#elif THERMISTOR_ID == 30 - #define THERMISTOR_NAME "Kis3d EN AW NTC100K/3950" +// Analog Thermistors - 1kΩ pullup #elif THERMISTOR_ID == 51 #define THERMISTOR_NAME "EPCOS 1K" #elif THERMISTOR_ID == 52 #define THERMISTOR_NAME "ATC204GT-2 1K" #elif THERMISTOR_ID == 55 #define THERMISTOR_NAME "ATC104GT-2 1K" -#elif THERMISTOR_ID == 1047 - #define THERMISTOR_NAME "PT1000 4K7" -#elif THERMISTOR_ID == 1022 - #define THERMISTOR_NAME "PT1000 2K2" -#elif THERMISTOR_ID == 1010 - #define THERMISTOR_NAME "PT1000 1K" -#elif THERMISTOR_ID == 147 - #define THERMISTOR_NAME "Pt100 4K7" + +// Analog Thermistors - 10kΩ pullup - Atypical +#elif THERMISTOR_ID == 99 + #define THERMISTOR_NAME "100k with 10k pull-up" + +// Analog RTDs (Pt100/Pt1000) #elif THERMISTOR_ID == 110 #define THERMISTOR_NAME "Pt100 1K" +#elif THERMISTOR_ID == 147 + #define THERMISTOR_NAME "Pt100 4K7" +#elif THERMISTOR_ID == 1010 + #define THERMISTOR_NAME "PT1000 1K" +#elif THERMISTOR_ID == 1022 + #define THERMISTOR_NAME "PT1000 2K2" +#elif THERMISTOR_ID == 1047 + #define THERMISTOR_NAME "PT1000 4K7" +#elif THERMISTOR_ID == 20 + #define THERMISTOR_NAME "Pt100 UltiMB 5v" +#elif THERMISTOR_ID == 21 + #define THERMISTOR_NAME "Pt100 UltiMB 3.3v" +#elif THERMISTOR_ID == 201 + #define THERMISTOR_NAME "Pt100 OverLord" + +// Modified thermistors +#elif THERMISTOR_ID == 30 + #define THERMISTOR_NAME "Kis3d EN AW NTC100K/3950" #elif THERMISTOR_ID == 666 #define THERMISTOR_NAME "Einstart S" #elif THERMISTOR_ID == 2000 diff --git a/Marlin/src/lcd/touch/touch_buttons.cpp b/Marlin/src/lcd/touch/touch_buttons.cpp index 032015cdd0..7c55c62c53 100644 --- a/Marlin/src/lcd/touch/touch_buttons.cpp +++ b/Marlin/src/lcd/touch/touch_buttons.cpp @@ -93,6 +93,7 @@ uint8_t TouchButtons::read_buttons() { #elif ENABLED(TFT_TOUCH_DEVICE_GT911) const bool is_touched = (TOUCH_ORIENTATION == TOUCH_PORTRAIT ? touchIO.getPoint(&y, &x) : touchIO.getPoint(&x, &y)); if (!is_touched) return 0; + #endif // Touch within the button area simulates an encoder button @@ -127,6 +128,7 @@ uint8_t TouchButtons::read_buttons() { #endif next_sleep_ms = TSLP_SLEEPING; } + void TouchButtons::wakeUp() { if (isSleeping()) { #if HAS_LCD_BRIGHTNESS @@ -135,7 +137,7 @@ uint8_t TouchButtons::read_buttons() { WRITE(TFT_BACKLIGHT_PIN, HIGH); #endif } - next_sleep_ms = millis() + SEC_TO_MS(ui.sleep_timeout_minutes * 60); + next_sleep_ms = millis() + MIN_TO_MS(ui.sleep_timeout_minutes); } #endif // HAS_TOUCH_SLEEP diff --git a/Marlin/src/libs/duration_t.h b/Marlin/src/libs/duration_t.h index 69a648441f..d648924dc9 100644 --- a/Marlin/src/libs/duration_t.h +++ b/Marlin/src/libs/duration_t.h @@ -67,7 +67,7 @@ struct duration_t { } /** - * @brief Formats the duration as years + * @brief Format the duration as years * @return The number of years */ inline uint8_t year() const { @@ -75,7 +75,7 @@ struct duration_t { } /** - * @brief Formats the duration as days + * @brief Format the duration as days * @return The number of days */ inline uint16_t day() const { @@ -83,7 +83,7 @@ struct duration_t { } /** - * @brief Formats the duration as hours + * @brief Format the duration as hours * @return The number of hours */ inline uint32_t hour() const { @@ -91,7 +91,7 @@ struct duration_t { } /** - * @brief Formats the duration as minutes + * @brief Format the duration as minutes * @return The number of minutes */ inline uint32_t minute() const { @@ -99,7 +99,7 @@ struct duration_t { } /** - * @brief Formats the duration as seconds + * @brief Format the duration as seconds * @return The number of seconds */ inline uint32_t second() const { @@ -112,11 +112,12 @@ struct duration_t { #endif /** - * @brief Formats the duration as a string + * @brief Format the duration as a string * @details String will be formatted using a "full" representation of duration * * @param buffer The array pointed to must be able to accommodate 22 bytes * (21 for the string, 1 more for the terminating nul) + * @param dense Whether to skip spaces in the resulting string * * Output examples: * 123456789012345678901 (strlen) @@ -142,10 +143,42 @@ struct duration_t { } /** - * @brief Formats the duration as a string + * @brief Format the duration as a compact string + * @details String will be formatted using a "full" representation of duration + * + * @param buffer The array pointed to must be able to accommodate 18 bytes + * (17 for the string, 1 more for the terminating nul) + * @param dense Whether to skip spaces in the resulting string + * + * Output examples: + * 12345678901234567 (strlen) + * 135y364d23h59m59s + * 364d23h59m59s + * 23h59m59s + * 59m59s + * 59s + */ + char* toCompactString(char * const buffer) const { + 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); + else if (h) sprintf_P(buffer, PSTR("%ih%im%is"), h, m, s); + else if (m) sprintf_P(buffer, PSTR("%im%is"), m, s); + else sprintf_P(buffer, PSTR("%is"), s); + return buffer; + } + + /** + * @brief Format the duration as a string * @details String will be formatted using a "digital" representation of duration * * @param buffer The array pointed to must be able to accommodate 10 bytes + * @return length of the formatted string (without terminating nul) * * Output examples: * 123456789 (strlen) diff --git a/Marlin/src/libs/heatshrink/heatshrink_decoder.cpp b/Marlin/src/libs/heatshrink/heatshrink_decoder.cpp index 073a7ed0b6..3d4d3fcd3f 100644 --- a/Marlin/src/libs/heatshrink/heatshrink_decoder.cpp +++ b/Marlin/src/libs/heatshrink/heatshrink_decoder.cpp @@ -142,7 +142,6 @@ HSD_sink_res heatshrink_decoder_sink(heatshrink_decoder *hsd, return HSDR_SINK_OK; } - /***************** * Decompression * *****************/ diff --git a/Marlin/src/libs/numtostr.h b/Marlin/src/libs/numtostr.h index 84027b44cd..d4959b513a 100644 --- a/Marlin/src/libs/numtostr.h +++ b/Marlin/src/libs/numtostr.h @@ -40,7 +40,7 @@ const char* ui8tostr3rj(const uint8_t i); const char* i8tostr3rj(const int8_t x); #if HAS_PRINT_PROGRESS_PERMYRIAD - // Convert 16-bit unsigned permyriad value to percent: 100 / 23 / 23.4 / 3.45 + // Convert 16-bit unsigned permyriad value to percent: _100 / __23 / 23.4 / 3.45 const char* permyriadtostr4(const uint16_t xx); #endif @@ -56,7 +56,7 @@ const char* ui16tostr3rj(const uint16_t x); // Convert int16_t to string with 123 format const char* i16tostr3rj(const int16_t x); -// Convert unsigned int to lj string with 123 format +// Convert signed int to lj string with 123 format const char* i16tostr3left(const int16_t xx); // Convert signed int to rj string with _123, -123, _-12, or __-1 format @@ -86,10 +86,10 @@ const char* ftostr53_63(const_float_t x); // Convert signed float to fixed-length string with 023.456 / -23.456 format const char* ftostr63(const_float_t x); -// Convert float to fixed-length string with +12.3 / -12.3 format +// Convert signed float to fixed-length string with +12.3 / -12.3 format const char* ftostr31sign(const_float_t x); -// Convert float to fixed-length string with +123.4 / -123.4 format +// Convert signed float to fixed-length string with +123.4 / -123.4 format const char* ftostr41sign(const_float_t x); // Convert signed float to string (6 digit) with -1.234 / _0.000 / +1.234 format @@ -101,7 +101,7 @@ const char* ftostr54sign(const_float_t x, char plus=' '); // Convert unsigned float to rj string with 12345 format const char* ftostr5rj(const_float_t x); -// Convert signed float to string with +1234.5 format +// Convert signed float to fixed-length string with +1234.5 format const char* ftostr51sign(const_float_t x); // Convert signed float to space-padded string with -_23.4_ format @@ -116,16 +116,16 @@ const char* ftostr53sign(const_float_t f); // Convert unsigned float to string with 12345.6 format omitting trailing zeros const char* ftostr61rj(const_float_t x); -// Convert unsigned float to string with 12345.67 format omitting trailing zeros +// Convert unsigned float to string with ____5.67, ___45.67, __345.67, _2345.67, 12345.67 format const char* ftostr72rj(const_float_t x); -// Convert float to rj string with 123 or -12 format +// Convert signed float to rj string with 123 or -12 format FORCE_INLINE const char* ftostr3rj(const_float_t x) { return i16tostr3rj(int16_t(x + (x < 0 ? -0.5f : 0.5f))); } #if ENABLED(LCD_DECIMAL_SMALL_XY) - // Convert float to rj string with 1234, _123, 12.3, _1.2, -123, _-12, or -1.2 format + // Convert signed float to rj string with 1234, _123, 12.3, _1.2, -123, _-12, or -1.2 format const char* ftostr4sign(const_float_t fx); #else - // Convert float to rj string with 1234, _123, -123, __12, _-12, ___1, or __-1 format + // Convert signed float to rj string with 1234, _123, -123, __12, _-12, ___1, or __-1 format FORCE_INLINE const char* ftostr4sign(const_float_t x) { return i16tostr4signrj(int16_t(x + (x < 0 ? -0.5f : 0.5f))); } #endif diff --git a/Marlin/src/libs/vector_3.h b/Marlin/src/libs/vector_3.h index 58bdb43c7b..ab719c6a7f 100644 --- a/Marlin/src/libs/vector_3.h +++ b/Marlin/src/libs/vector_3.h @@ -50,9 +50,9 @@ struct vector_3 { float pos[3]; }; vector_3(const_float_t _x, const_float_t _y, const_float_t _z) : x(_x), y(_y), z(_z) {} - vector_3(const xy_float_t &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); } - vector_3(const xyz_float_t &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); TERN_(HAS_Z_AXIS, z = in.z); } - vector_3(const xyze_float_t &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); TERN_(HAS_Z_AXIS, z = in.z); } + vector_3(const xy_float_t &in) { TERN_(HAS_X_AXIS, x = in.x); TERN_(HAS_Y_AXIS, y = in.y); } + vector_3(const xyz_float_t &in) { TERN_(HAS_X_AXIS, x = in.x); TERN_(HAS_Y_AXIS, y = in.y); TERN_(HAS_Z_AXIS, z = in.z); } + vector_3(const xyze_float_t &in) { TERN_(HAS_X_AXIS, x = in.x); TERN_(HAS_Y_AXIS, y = in.y); TERN_(HAS_Z_AXIS, z = in.z); } vector_3() { x = y = z = 0; } // Factory method @@ -75,8 +75,8 @@ struct vector_3 { vector_3 operator-(const vector_3 &v) { return vector_3(x - v.x, y - v.y, z - v.z); } vector_3 operator*(const float &v) { return vector_3(x * v, y * v, z * v); } - operator xy_float_t() { return xy_float_t({ x OPTARG(HAS_Y_AXIS, y) }); } - operator xyz_float_t() { return xyz_float_t({ x OPTARG(HAS_Y_AXIS, y) OPTARG(HAS_Z_AXIS, z) }); } + operator xy_float_t() { return xy_float_t({ TERN_(HAS_X_AXIS, x) OPTARG(HAS_Y_AXIS, y) }); } + operator xyz_float_t() { return xyz_float_t({ TERN_(HAS_X_AXIS, x) OPTARG(HAS_Y_AXIS, y) OPTARG(HAS_Z_AXIS, z) }); } void debug(FSTR_P const title); }; diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index 20e258f652..4988b8acbc 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -31,6 +31,24 @@ #define __ES_ITEM(N) N, #define _ES_ITEM(K,N) TERN_(K,DEFER4(__ES_ITEM)(N)) +/** + * Basic Endstop Flag Bits: + * - Each axis with an endstop gets a flag for its homing direction. + * (The use of "MIN" or "MAX" makes it easier to pair with similarly-named endstop pins.) + * - Bed probes with a single pin get a Z_MIN_PROBE flag. This includes Sensorless Z Probe. + * + * Extended Flag Bits: + * - Multi-stepper axes may have multi-endstops such as X2_MIN, Y2_MAX, etc. + * - DELTA gets X_MAX, Y_MAX, and Z_MAX corresponding to its "A", "B", "C" towers. + * - For DUAL_X_CARRIAGE the X axis has both X_MIN and X_MAX flags. + * - The Z axis may have both MIN and MAX when homing to MAX and the probe is Z_MIN. + * - DELTA Sensorless Probe uses X/Y/Z_MAX but sets the Z_MIN flag. + * + * Endstop Flag Bit Aliases: + * - Each *_MIN or *_MAX flag is aliased to *_ENDSTOP. + * - Z_MIN_PROBE is an alias to Z_MIN when the Z_MIN_PIN is being used as the probe pin. + * - When homing with the probe Z_ENDSTOP is a Z_MIN_PROBE alias, otherwise a Z_MIN/MAX alias. + */ enum EndstopEnum : char { // Common XYZ (ABC) endstops. Defined according to USE_[XYZ](MIN|MAX)_PLUG settings. _ES_ITEM(HAS_X_MIN, X_MIN) diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index f263325649..d265939b80 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -368,7 +368,6 @@ void report_current_position_projected() { #endif // CARTESIAN - void home_if_needed(const bool keeplev/*=false*/) { if (!all_axes_trusted()) gcode.home_all_axes(keeplev); } @@ -1835,72 +1834,72 @@ void prepare_line_to_destination() { case X_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(X); phaseCurrent = stepperX.get_microstep_counter(); - effectorBackoutDir = -X_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_X_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(X_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_X_DIR, -)(-effectorBackoutDir); break; #endif #ifdef Y_MICROSTEPS case Y_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(Y); phaseCurrent = stepperY.get_microstep_counter(); - effectorBackoutDir = -Y_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_Y_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(Y_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_Y_DIR, -)(-effectorBackoutDir); break; #endif #ifdef Z_MICROSTEPS case Z_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(Z); phaseCurrent = stepperZ.get_microstep_counter(); - effectorBackoutDir = -Z_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_Z_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(Z_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_Z_DIR, -)(-effectorBackoutDir); break; #endif #ifdef I_MICROSTEPS case I_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(I); phaseCurrent = stepperI.get_microstep_counter(); - effectorBackoutDir = -I_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_I_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(I_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_I_DIR, -)(-effectorBackoutDir); break; #endif #ifdef J_MICROSTEPS case J_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(J); phaseCurrent = stepperJ.get_microstep_counter(); - effectorBackoutDir = -J_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_J_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(J_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_J_DIR, -)(-effectorBackoutDir); break; #endif #ifdef K_MICROSTEPS case K_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(K); phaseCurrent = stepperK.get_microstep_counter(); - effectorBackoutDir = -K_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_K_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(K_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_K_DIR, -)(-effectorBackoutDir); break; #endif #ifdef U_MICROSTEPS case U_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(U); phaseCurrent = stepperU.get_microstep_counter(); - effectorBackoutDir = -U_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_U_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(U_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_U_DIR, -)(-effectorBackoutDir); break; #endif #ifdef V_MICROSTEPS case V_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(V); phaseCurrent = stepperV.get_microstep_counter(); - effectorBackoutDir = -V_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_V_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(V_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_V_DIR, -)(-effectorBackoutDir); break; #endif #ifdef W_MICROSTEPS case W_AXIS: phasePerUStep = PHASE_PER_MICROSTEP(W); phaseCurrent = stepperW.get_microstep_counter(); - effectorBackoutDir = -W_HOME_DIR; - stepperBackoutDir = IF_DISABLED(INVERT_W_DIR, -)effectorBackoutDir; + effectorBackoutDir = -(W_HOME_DIR); + stepperBackoutDir = TERN_(INVERT_W_DIR, -)(-effectorBackoutDir); break; #endif default: return; @@ -2348,7 +2347,7 @@ void set_axis_is_at_home(const AxisEnum axis) { #else - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("*** Z HOMED TO ENDSTOP ***"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("*** Z homed to ENDSTOP ***"); #endif } diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index c4bfcc63ee..d6ddb4e422 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -127,7 +127,7 @@ volatile uint8_t Planner::block_buffer_head, // Index of the next block to be Planner::block_buffer_planned, // Index of the optimally planned block Planner::block_buffer_tail; // Index of the busy block, if any uint16_t Planner::cleaning_buffer_counter; // A counter to disable queuing of blocks -uint8_t Planner::delay_before_delivering; // This counter delays delivery of blocks when queue becomes empty to allow the opportunity of merging blocks +uint8_t Planner::delay_before_delivering; // Delay block delivery so initial blocks in an empty queue may merge planner_settings_t Planner::settings; // Initialized by settings.load() @@ -252,11 +252,15 @@ void Planner::init() { position.reset(); TERN_(HAS_POSITION_FLOAT, position_float.reset()); TERN_(IS_KINEMATIC, position_cart.reset()); + previous_speed.reset(); previous_nominal_speed = 0; + TERN_(ABL_PLANAR, bed_level_matrix.set_to_identity()); + clear_block_buffer(); delay_before_delivering = 0; + #if ENABLED(DIRECT_STEPPING) last_page_step_rate = 0; last_page_dir.reset(); @@ -1495,7 +1499,7 @@ void Planner::check_axes_activity() { thermalManager.setTargetHotend(t, active_extruder); } -#endif +#endif // AUTOTEMP #if DISABLED(NO_VOLUMETRICS) @@ -1965,29 +1969,27 @@ bool Planner::_populate_block( if (db < 0) SBI(dm, Y_HEAD); // ...and Y TERN_(HAS_Z_AXIS, if (dc < 0) SBI(dm, Z_AXIS)); #endif - #if IS_CORE - #if CORE_IS_XY - if (da + db < 0) SBI(dm, A_AXIS); // Motor A direction - if (CORESIGN(da - db) < 0) SBI(dm, B_AXIS); // Motor B direction - #elif CORE_IS_XZ - if (da < 0) SBI(dm, X_HEAD); // Save the toolhead's true direction in X - if (db < 0) SBI(dm, Y_AXIS); - if (dc < 0) SBI(dm, Z_HEAD); // ...and Z - if (da + dc < 0) SBI(dm, A_AXIS); // Motor A direction - if (CORESIGN(da - dc) < 0) SBI(dm, C_AXIS); // Motor C direction - #elif CORE_IS_YZ - if (da < 0) SBI(dm, X_AXIS); - if (db < 0) SBI(dm, Y_HEAD); // Save the toolhead's true direction in Y - if (dc < 0) SBI(dm, Z_HEAD); // ...and Z - if (db + dc < 0) SBI(dm, B_AXIS); // Motor B direction - if (CORESIGN(db - dc) < 0) SBI(dm, C_AXIS); // Motor C direction - #endif + #if CORE_IS_XY + if (da + db < 0) SBI(dm, A_AXIS); // Motor A direction + if (CORESIGN(da - db) < 0) SBI(dm, B_AXIS); // Motor B direction + #elif CORE_IS_XZ + if (da < 0) SBI(dm, X_HEAD); // Save the toolhead's true direction in X + if (db < 0) SBI(dm, Y_AXIS); + if (dc < 0) SBI(dm, Z_HEAD); // ...and Z + if (da + dc < 0) SBI(dm, A_AXIS); // Motor A direction + if (CORESIGN(da - dc) < 0) SBI(dm, C_AXIS); // Motor C direction + #elif CORE_IS_YZ + if (da < 0) SBI(dm, X_AXIS); + if (db < 0) SBI(dm, Y_HEAD); // Save the toolhead's true direction in Y + if (dc < 0) SBI(dm, Z_HEAD); // ...and Z + if (db + dc < 0) SBI(dm, B_AXIS); // Motor B direction + if (CORESIGN(db - dc) < 0) SBI(dm, C_AXIS); // Motor C direction #elif ENABLED(MARKFORGED_XY) - if (da + db < 0) SBI(dm, A_AXIS); // Motor A direction - if (db < 0) SBI(dm, B_AXIS); // Motor B direction + if (da + db < 0) SBI(dm, A_AXIS); // Motor A direction + if (db < 0) SBI(dm, B_AXIS); // Motor B direction #elif ENABLED(MARKFORGED_YX) - if (da < 0) SBI(dm, A_AXIS); // Motor A direction - if (db + da < 0) SBI(dm, B_AXIS); // Motor B direction + if (da < 0) SBI(dm, A_AXIS); // Motor A direction + if (db + da < 0) SBI(dm, B_AXIS); // Motor B direction #else XYZ_CODE( if (da < 0) SBI(dm, X_AXIS), @@ -2089,23 +2091,21 @@ bool Planner::_populate_block( steps_dist_mm.head.y = db * mm_per_step[B_AXIS]; TERN_(HAS_Z_AXIS, steps_dist_mm.z = dc * mm_per_step[Z_AXIS]); #endif - #if IS_CORE - #if CORE_IS_XY - steps_dist_mm.a = (da + db) * mm_per_step[A_AXIS]; - steps_dist_mm.b = CORESIGN(da - db) * mm_per_step[B_AXIS]; - #elif CORE_IS_XZ - steps_dist_mm.head.x = da * mm_per_step[A_AXIS]; - steps_dist_mm.y = db * mm_per_step[Y_AXIS]; - steps_dist_mm.head.z = dc * mm_per_step[C_AXIS]; - steps_dist_mm.a = (da + dc) * mm_per_step[A_AXIS]; - steps_dist_mm.c = CORESIGN(da - dc) * mm_per_step[C_AXIS]; - #elif CORE_IS_YZ - steps_dist_mm.x = da * mm_per_step[X_AXIS]; - steps_dist_mm.head.y = db * mm_per_step[B_AXIS]; - steps_dist_mm.head.z = dc * mm_per_step[C_AXIS]; - steps_dist_mm.b = (db + dc) * mm_per_step[B_AXIS]; - steps_dist_mm.c = CORESIGN(db - dc) * mm_per_step[C_AXIS]; - #endif + #if CORE_IS_XY + steps_dist_mm.a = (da + db) * mm_per_step[A_AXIS]; + steps_dist_mm.b = CORESIGN(da - db) * mm_per_step[B_AXIS]; + #elif CORE_IS_XZ + steps_dist_mm.head.x = da * mm_per_step[A_AXIS]; + steps_dist_mm.y = db * mm_per_step[Y_AXIS]; + steps_dist_mm.head.z = dc * mm_per_step[C_AXIS]; + steps_dist_mm.a = (da + dc) * mm_per_step[A_AXIS]; + steps_dist_mm.c = CORESIGN(da - dc) * mm_per_step[C_AXIS]; + #elif CORE_IS_YZ + steps_dist_mm.x = da * mm_per_step[X_AXIS]; + steps_dist_mm.head.y = db * mm_per_step[B_AXIS]; + steps_dist_mm.head.z = dc * mm_per_step[C_AXIS]; + steps_dist_mm.b = (db + dc) * mm_per_step[B_AXIS]; + steps_dist_mm.c = CORESIGN(db - dc) * mm_per_step[C_AXIS]; #elif ENABLED(MARKFORGED_XY) steps_dist_mm.a = (da - db) * mm_per_step[A_AXIS]; steps_dist_mm.b = db * mm_per_step[B_AXIS]; @@ -2138,15 +2138,9 @@ bool Planner::_populate_block( #endif if (true NUM_AXIS_GANG( - && block->steps.a < MIN_STEPS_PER_SEGMENT, - && block->steps.b < MIN_STEPS_PER_SEGMENT, - && block->steps.c < MIN_STEPS_PER_SEGMENT, - && block->steps.i < MIN_STEPS_PER_SEGMENT, - && block->steps.j < MIN_STEPS_PER_SEGMENT, - && block->steps.k < MIN_STEPS_PER_SEGMENT, - && block->steps.u < MIN_STEPS_PER_SEGMENT, - && block->steps.v < MIN_STEPS_PER_SEGMENT, - && block->steps.w < MIN_STEPS_PER_SEGMENT + && block->steps.a < MIN_STEPS_PER_SEGMENT, && block->steps.b < MIN_STEPS_PER_SEGMENT, && block->steps.c < MIN_STEPS_PER_SEGMENT, + && block->steps.i < MIN_STEPS_PER_SEGMENT, && block->steps.j < MIN_STEPS_PER_SEGMENT, && block->steps.k < MIN_STEPS_PER_SEGMENT, + && block->steps.u < MIN_STEPS_PER_SEGMENT, && block->steps.v < MIN_STEPS_PER_SEGMENT, && block->steps.w < MIN_STEPS_PER_SEGMENT ) ) { block->millimeters = TERN0(HAS_EXTRUDERS, ABS(steps_dist_mm.e)); @@ -2302,12 +2296,9 @@ bool Planner::_populate_block( #endif #if ANY(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX) SECONDARY_AXIS_CODE( - if (block->steps.i) stepper.enable_axis(I_AXIS), - if (block->steps.j) stepper.enable_axis(J_AXIS), - if (block->steps.k) stepper.enable_axis(K_AXIS), - if (block->steps.u) stepper.enable_axis(U_AXIS), - if (block->steps.v) stepper.enable_axis(V_AXIS), - if (block->steps.w) stepper.enable_axis(W_AXIS) + if (block->steps.i) stepper.enable_axis(I_AXIS), if (block->steps.j) stepper.enable_axis(J_AXIS), + if (block->steps.k) stepper.enable_axis(K_AXIS), if (block->steps.u) stepper.enable_axis(U_AXIS), + if (block->steps.v) stepper.enable_axis(V_AXIS), if (block->steps.w) stepper.enable_axis(W_AXIS) ); #endif @@ -2590,6 +2581,7 @@ bool Planner::_populate_block( #if DISABLED(S_CURVE_ACCELERATION) block->acceleration_rate = (uint32_t)(accel * (float(1UL << 24) / (STEPPER_TIMER_RATE))); #endif + #if ENABLED(LIN_ADVANCE) block->la_advance_rate = 0; block->la_scaling = 0; diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index bc62d4d9e8..1f69c9275c 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -110,7 +110,6 @@ enum BlockFlagBit { // Direct stepping page OPTARG(DIRECT_STEPPING, BLOCK_BIT_PAGE) - // Sync the fan speeds from the block OPTARG(LASER_SYNCHRONOUS_M106_M107, BLOCK_BIT_SYNC_FANS) @@ -398,7 +397,6 @@ class Planner { static uint16_t cleaning_buffer_counter; // A counter to disable queuing of blocks static uint8_t delay_before_delivering; // This counter delays delivery of blocks when queue becomes empty to allow the opportunity of merging blocks - #if ENABLED(DISTINCT_E_FACTORS) static uint8_t last_extruder; // Respond to extruder change #endif @@ -414,15 +412,15 @@ class Planner { #endif #if DISABLED(NO_VOLUMETRICS) - static float filament_size[EXTRUDERS], // diameter of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder - volumetric_area_nominal, // Nominal cross-sectional area - volumetric_multiplier[EXTRUDERS]; // Reciprocal of cross-sectional area of filament (in mm^2). Pre-calculated to reduce computation in the planner + static float filament_size[EXTRUDERS], // (mm) Diameter of filament, typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder + volumetric_area_nominal, // (mm^3) Nominal cross-sectional area + volumetric_multiplier[EXTRUDERS]; // (1/mm^2) Reciprocal of cross-sectional area of filament. Pre-calculated to reduce computation in the planner // May be auto-adjusted by a filament width sensor #endif #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) - static float volumetric_extruder_limit[EXTRUDERS], // Maximum mm^3/sec the extruder can handle - volumetric_extruder_feedrate_limit[EXTRUDERS]; // Feedrate limit (mm/s) calculated from volume limit + static float volumetric_extruder_limit[EXTRUDERS], // (mm^3/sec) Maximum volume the extruder can handle + volumetric_extruder_feedrate_limit[EXTRUDERS]; // (mm/s) Feedrate limit calculated from volume limit #endif static planner_settings_t settings; diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index fb4519b899..95ebfc430e 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -196,35 +196,35 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() inline void run_deploy_moves() { #ifdef Z_PROBE_ALLEN_KEY_DEPLOY_1 #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE - #define Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE 0.0f #endif constexpr xyz_pos_t deploy_1 = Z_PROBE_ALLEN_KEY_DEPLOY_1; do_blocking_move_to(deploy_1, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_DEPLOY_2 #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE - #define Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE 0.0f #endif constexpr xyz_pos_t deploy_2 = Z_PROBE_ALLEN_KEY_DEPLOY_2; do_blocking_move_to(deploy_2, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_DEPLOY_3 #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE - #define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE 0.0f #endif constexpr xyz_pos_t deploy_3 = Z_PROBE_ALLEN_KEY_DEPLOY_3; do_blocking_move_to(deploy_3, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_DEPLOY_4 #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE - #define Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE 0.0f #endif constexpr xyz_pos_t deploy_4 = Z_PROBE_ALLEN_KEY_DEPLOY_4; do_blocking_move_to(deploy_4, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_DEPLOY_5 #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE - #define Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE 0.0f #endif constexpr xyz_pos_t deploy_5 = Z_PROBE_ALLEN_KEY_DEPLOY_5; do_blocking_move_to(deploy_5, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE)); @@ -234,35 +234,35 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() inline void run_stow_moves() { #ifdef Z_PROBE_ALLEN_KEY_STOW_1 #ifndef Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE - #define Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE 0.0f #endif constexpr xyz_pos_t stow_1 = Z_PROBE_ALLEN_KEY_STOW_1; do_blocking_move_to(stow_1, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_STOW_2 #ifndef Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE - #define Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE 0.0f #endif constexpr xyz_pos_t stow_2 = Z_PROBE_ALLEN_KEY_STOW_2; do_blocking_move_to(stow_2, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_STOW_3 #ifndef Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE - #define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE 0.0f #endif constexpr xyz_pos_t stow_3 = Z_PROBE_ALLEN_KEY_STOW_3; do_blocking_move_to(stow_3, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_STOW_4 #ifndef Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE - #define Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE 0.0f #endif constexpr xyz_pos_t stow_4 = Z_PROBE_ALLEN_KEY_STOW_4; do_blocking_move_to(stow_4, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_STOW_5 #ifndef Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE - #define Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE 0.0 + #define Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE 0.0f #endif constexpr xyz_pos_t stow_5 = Z_PROBE_ALLEN_KEY_STOW_5; do_blocking_move_to(stow_5, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE)); @@ -413,6 +413,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { #elif HAS_Z_SERVO_PROBE + // i.e., deploy ? DEPLOY_Z_SERVO() : STOW_Z_SERVO(); servo[Z_PROBE_SERVO_NR].move(servo_angles[Z_PROBE_SERVO_NR][deploy ? 0 : 1]); #elif ANY(TOUCH_MI_PROBE, Z_PROBE_ALLEN_KEY, MAG_MOUNTED_PROBE) @@ -533,7 +534,7 @@ bool Probe::set_deployed(const bool deploy) { } #endif - const xy_pos_t old_xy = current_position; + const xy_pos_t old_xy = current_position; // Remember location before probe deployment #if ENABLED(PROBE_TRIGGERED_WHEN_STOWED_TEST) @@ -560,6 +561,7 @@ bool Probe::set_deployed(const bool deploy) { #endif // If preheating is required before any probing... + // TODO: Consider skipping this for things like M401, G34, etc. TERN_(PREHEAT_BEFORE_PROBING, if (deploy) preheat_for_probing(PROBING_NOZZLE_TEMP, PROBING_BED_TEMP)); do_blocking_move_to(old_xy); @@ -592,6 +594,7 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { #if ALL(HAS_TEMP_HOTEND, WAIT_FOR_HOTEND) thermalManager.wait_for_hotend_heating(active_extruder); #endif + #if ENABLED(BLTOUCH) if (!bltouch.high_speed_mode && bltouch.deploy()) return true; // Deploy in LOW SPEED MODE on every probe action @@ -607,7 +610,7 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { if (test_sensitivity.z) stealth_states.z = tmc_enable_stallguard(stepperZ); // All machines will check Z-DIAG for stall endstops.set_homing_current(true); // The "homing" current also applies to probing endstops.enable(true); - #endif + #endif // SENSORLESS_PROBING TERN_(HAS_QUIET_PROBING, set_probing_paused(true)); @@ -615,17 +618,17 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { do_blocking_move_to_z(z, fr_mm_s); // Check to see if the probe was triggered - const bool probe_triggered = + const bool probe_triggered = ( #if HAS_DELTA_SENSORLESS_PROBING endstops.trigger_state() & (_BV(X_MAX) | _BV(Y_MAX) | _BV(Z_MAX)) #else TEST(endstops.trigger_state(), Z_MIN_PROBE) #endif - ; + ); // Offset sensorless probing #if HAS_DELTA_SENSORLESS_PROBING - if (probe_triggered) probe.refresh_largest_sensorless_adj(); + if (probe_triggered) refresh_largest_sensorless_adj(); #endif TERN_(HAS_QUIET_PROBING, set_probing_paused(false)); diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index c0bb60b995..d0658b7d85 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -76,9 +76,7 @@ class Probe { public: #if ENABLED(SENSORLESS_PROBING) - typedef struct { - bool x:1, y:1, z:1; - } sense_bool_t; + typedef struct { bool x:1, y:1, z:1; } sense_bool_t; static sense_bool_t test_sensitivity; #endif @@ -116,7 +114,7 @@ public: } #endif - #else + #else // !IS_KINEMATIC /** * Return whether the given position is within the bed, and whether the nozzle @@ -138,7 +136,7 @@ public: } } - #endif + #endif // !IS_KINEMATIC static void move_z_after_probing() { #ifdef Z_AFTER_PROBING @@ -150,7 +148,7 @@ public: return probe_at_point(pos.x, pos.y, raise_after, verbose_level, probe_relative, sanity_check); } - #else + #else // !HAS_BED_PROBE static constexpr xyz_pos_t offset = xyz_pos_t(NUM_AXIS_ARRAY_1(0)); // See #16767 @@ -158,7 +156,7 @@ public: static bool can_reach(const_float_t rx, const_float_t ry, const bool=true) { return position_is_reachable(rx, ry); } - #endif + #endif // !HAS_BED_PROBE static void move_z_after_homing() { #if ALL(DWIN_LCD_PROUI, INDIVIDUAL_AXIS_HOMING_SUBMENU, MESH_BED_LEVELING) || defined(Z_AFTER_HOMING) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 56a2b8ae6a..593be90717 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -585,12 +585,12 @@ typedef struct SettingsDataStruct { // Input Shaping // #if ENABLED(INPUT_SHAPING_X) - float shaping_x_frequency, // M593 X F - shaping_x_zeta; // M593 X D + float shaping_x_frequency, // M593 X F + shaping_x_zeta; // M593 X D #endif #if ENABLED(INPUT_SHAPING_Y) - float shaping_y_frequency, // M593 Y F - shaping_y_zeta; // M593 Y D + float shaping_y_frequency, // M593 Y F + shaping_y_zeta; // M593 Y D #endif } SettingsData; @@ -656,7 +656,7 @@ void MarlinSettings::postprocess() { if (oldpos != current_position) report_current_position(); - // Moved as last update due to interference with Neopixel init + // Moved as last update due to interference with NeoPixel init TERN_(HAS_LCD_CONTRAST, ui.refresh_contrast()); TERN_(HAS_LCD_BRIGHTNESS, ui.refresh_brightness()); @@ -1945,7 +1945,7 @@ void MarlinSettings::postprocess() { if (grid_max_x == (GRID_MAX_POINTS_X) && grid_max_y == (GRID_MAX_POINTS_Y)) { if (!validating) set_bed_leveling_enabled(false); bedlevel.set_grid(spacing, start); - EEPROM_READ(bedlevel.z_values); // 9 to 256 floats + EEPROM_READ(bedlevel.z_values); // 9 to 256 floats } else if (grid_max_x > (GRID_MAX_POINTS_X) || grid_max_y > (GRID_MAX_POINTS_Y)) { eeprom_error = ERR_EEPROM_CORRUPT; @@ -3288,7 +3288,6 @@ void MarlinSettings::reset() { // // Heated Bed PID // - #if ENABLED(PIDTEMPBED) thermalManager.temp_bed.pid.set(DEFAULT_bedKp, DEFAULT_bedKi, DEFAULT_bedKd); #endif @@ -3296,7 +3295,6 @@ void MarlinSettings::reset() { // // Heated Chamber PID // - #if ENABLED(PIDTEMPCHAMBER) thermalManager.temp_chamber.pid.set(DEFAULT_chamberKp, DEFAULT_chamberKi, DEFAULT_chamberKd); #endif @@ -3348,7 +3346,6 @@ void MarlinSettings::reset() { // // Volumetric & Filament Size // - #if DISABLED(NO_VOLUMETRICS) parser.volumetric_enabled = ENABLED(VOLUMETRIC_DEFAULT_ON); for (uint8_t q = 0; q < COUNT(planner.filament_size); ++q) diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 7ce32b6799..af223a9f10 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -2269,7 +2269,7 @@ uint32_t Stepper::block_phase_isr() { } #endif // LIN_ADVANCE - /* + /** * Adjust Laser Power - Decelerating * trap_ramp_entry_decr - holds the precalculated value to decrease the current power per decel step. */ diff --git a/Marlin/src/module/stepper/indirection.cpp b/Marlin/src/module/stepper/indirection.cpp index 427fd71cbe..0290d8135d 100644 --- a/Marlin/src/module/stepper/indirection.cpp +++ b/Marlin/src/module/stepper/indirection.cpp @@ -42,6 +42,6 @@ void reset_stepper_drivers() { } #if ENABLED(SOFTWARE_DRIVER_ENABLE) - // Flags to optimize XYZ Enabled state + // Flags to optimize axis enabled state xyz_bool_t axis_sw_enabled; // = { false, false, false } #endif diff --git a/Marlin/src/module/stepper/indirection.h b/Marlin/src/module/stepper/indirection.h index e9a9aa7de9..0c3577c7b6 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -22,14 +22,51 @@ #pragma once /** - * stepper/indirection.h + * stepper/indirection.h - Stepper Indirection Macros * - * Stepper motor driver indirection to allow some stepper functions to - * be done via SPI/I2c instead of direct pin manipulation. + * Each axis in a machine may have between 1 and 4 stepper motors. + * Currently X and Y allow for 1 or 2 steppers. Z can have up to 4. + * Extruders usually have one E stepper per nozzle. + * + * XYZ Special Cases + * - Delta: 3 steppers contribute to X, Y, and Z. + * - SCARA: A and B steppers contribute to X and Y by angular transformation. + * - CoreXY: A and B steppers contribute to X and Y in combination. + * - CoreXZ: A and B steppers contribute to X and Z in combination. + * - CoreYZ: A and B steppers contribute to Y and Z in combination. + * + * E Special Cases + * - SINGLENOZZLE: All Extruders have a single nozzle so there is one heater and no XYZ offset. + * - Switching Extruder: One stepper is used for each pair of nozzles with a switching mechanism. + * - Duplication Mode: Two or more steppers move in sync when `extruder_duplication_enabled` is set. + * With MULTI_NOZZLE_DUPLICATION a `duplication_e_mask` is also used. + * - Průša MMU1: One stepper is used with a switching mechanism. Odd numbered E indexes are reversed. + * - Průša MMU2: One stepper is used with a switching mechanism. + * - E_DUAL_STEPPER_DRIVERS: Two steppers always move in sync, possibly with opposite DIR states. + * + * Direct Stepper Control + * Where "Q" represents X Y Z I J K U V W / X2 Y2 Z2 Z3 Z4 / E0 E1 E2 E3 E4 E5 E6 E7 + * Here each E index corresponds to a single E stepper driver. + * + * Q_ENABLE_INIT() Q_ENABLE_WRITE(S) Q_ENABLE_READ() + * Q_DIR_INIT() Q_DIR_WRITE(S) Q_DIR_READ() + * Q_STEP_INIT() Q_STEP_WRITE(S) Q_STEP_READ() + * + * Steppers may not have an enable state or may be enabled by other methods + * beyond a single pin (SOFTWARE_DRIVER_ENABLE) so these can be overriden: + * ENABLE_STEPPER_Q() DISABLE_STEPPER_Q() + * + * Axis Stepper Control (X Y Z I J K U V W) + * SOFTWARE_DRIVER_ENABLE gives all axes a status flag, so these macros will + * skip sending commands to steppers that are already in the desired state: + * ENABLE_AXIS_Q() DISABLE_AXIS_Q() + * + * E-Axis Stepper Control (0..n) + * For these macros the E index indicates a logical extruder (e.g., active_extruder). + * + * E_STEP_WRITE(E,V) FWD_E_DIR(E) REV_E_DIR(E) * - * Copyright (c) 2015 Dominik Wenger */ - #include "../../inc/MarlinConfig.h" #if HAS_TMC26X diff --git a/Marlin/src/module/stepper/trinamic.h b/Marlin/src/module/stepper/trinamic.h index 569d213e56..c06b42703e 100644 --- a/Marlin/src/module/stepper/trinamic.h +++ b/Marlin/src/module/stepper/trinamic.h @@ -296,7 +296,7 @@ void reset_trinamic_drivers(); #define U_ENABLE_READ() stepperU.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(U) - #define U_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(U_STEP_PIN); }while(0) + #define U_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(U_STEP_PIN); }while(0) #endif #endif @@ -310,7 +310,7 @@ void reset_trinamic_drivers(); #define V_ENABLE_READ() stepperV.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(V) - #define V_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(V_STEP_PIN); }while(0) + #define V_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(V_STEP_PIN); }while(0) #endif #endif @@ -324,7 +324,7 @@ void reset_trinamic_drivers(); #define W_ENABLE_READ() stepperW.isEnabled() #endif #if AXIS_HAS_SQUARE_WAVE(W) - #define W_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(W_STEP_PIN); }while(0) + #define W_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(W_STEP_PIN); }while(0) #endif #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 6458fd760b..7d6a3d0bc1 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -585,7 +585,6 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); volatile bool Temperature::raw_temps_ready = false; - #if ENABLED(MPCTEMP) int32_t Temperature::mpc_e_position; // = 0 #endif @@ -711,16 +710,14 @@ volatile bool Temperature::raw_temps_ready = false; TERN_(DWIN_LCD_PROUI, DWIN_PidTuning(isbed ? PIDTEMPBED_START : PIDTEMP_START)); if (target > GHV(CHAMBER_MAX_TARGET, BED_MAX_TARGET, temp_range[heater_id].maxtemp - (HOTEND_OVERSHOOT))) { - SERIAL_ECHOPGM(STR_PID_AUTOTUNE); - SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); + SERIAL_ECHOPGM(STR_PID_AUTOTUNE); SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH)); TERN_(DWIN_LCD_PROUI, DWIN_PidTuning(PID_TEMP_TOO_HIGH)); TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_PID_TEMP_TOO_HIGH))); return; } - SERIAL_ECHOPGM(STR_PID_AUTOTUNE); - SERIAL_ECHOLNPGM(STR_PID_AUTOTUNE_START); + SERIAL_ECHOPGM(STR_PID_AUTOTUNE); SERIAL_ECHOLNPGM(STR_PID_AUTOTUNE_START); disable_all_heaters(); TERN_(AUTO_POWER_CONTROL, powerManager.power_on()); @@ -805,8 +802,7 @@ volatile bool Temperature::raw_temps_ready = false; #define MAX_OVERSHOOT_PID_AUTOTUNE 30 #endif if (current_temp > target + MAX_OVERSHOOT_PID_AUTOTUNE) { - SERIAL_ECHOPGM(STR_PID_AUTOTUNE); - SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); + SERIAL_ECHOPGM(STR_PID_AUTOTUNE); SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TEMP_TOO_HIGH)); TERN_(DWIN_LCD_PROUI, DWIN_PidTuning(PID_TEMP_TOO_HIGH)); TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_PID_TEMP_TOO_HIGH))); @@ -848,14 +844,12 @@ volatile bool Temperature::raw_temps_ready = false; TERN_(DWIN_LCD_PROUI, DWIN_PidTuning(PID_TUNING_TIMEOUT)); TERN_(EXTENSIBLE_UI, ExtUI::onPidTuning(ExtUI::result_t::PID_TUNING_TIMEOUT)); TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_PID_TIMEOUT))); - SERIAL_ECHOPGM(STR_PID_AUTOTUNE); - SERIAL_ECHOLNPGM(STR_PID_TIMEOUT); + SERIAL_ECHOPGM(STR_PID_AUTOTUNE); SERIAL_ECHOLNPGM(STR_PID_TIMEOUT); break; } if (cycles > ncycles && cycles > 2) { - SERIAL_ECHOPGM(STR_PID_AUTOTUNE); - SERIAL_ECHOLNPGM(STR_PID_AUTOTUNE_FINISHED); + SERIAL_ECHOPGM(STR_PID_AUTOTUNE); SERIAL_ECHOLNPGM(STR_PID_AUTOTUNE_FINISHED); TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_PID_AUTOTUNE_DONE))); #if ANY(PIDTEMPBED, PIDTEMPCHAMBER) @@ -1828,7 +1822,7 @@ void Temperature::mintemp_error(const heater_id_t heater_id) { if (degCooler() > watch_cooler.target) // Failed to decrease enough? _temp_error(H_COOLER, GET_TEXT_F(MSG_COOLING_FAILED), GET_TEXT_F(MSG_COOLING_FAILED)); else - start_watching_cooler(); // Start again if the target is still far off + start_watching_cooler(); // Start again if the target is still far off } #endif @@ -1909,20 +1903,20 @@ void Temperature::task() { #if DISABLED(IGNORE_THERMOCOUPLE_ERRORS) #if TEMP_SENSOR_IS_MAX_TC(0) - if (degHotend(0) > _MIN(HEATER_0_MAXTEMP, TEMP_SENSOR_0_MAX_TC_TMAX - 1.0)) maxtemp_error(H_E0); - if (degHotend(0) < _MAX(HEATER_0_MINTEMP, TEMP_SENSOR_0_MAX_TC_TMIN + .01)) mintemp_error(H_E0); + if (degHotend(0) > _MIN(HEATER_0_MAXTEMP, TEMP_SENSOR_0_MAX_TC_TMAX - 1.00f)) maxtemp_error(H_E0); + if (degHotend(0) < _MAX(HEATER_0_MINTEMP, TEMP_SENSOR_0_MAX_TC_TMIN + 0.01f)) mintemp_error(H_E0); #endif #if TEMP_SENSOR_IS_MAX_TC(1) - if (degHotend(1) > _MIN(HEATER_1_MAXTEMP, TEMP_SENSOR_1_MAX_TC_TMAX - 1.0)) maxtemp_error(H_E1); - if (degHotend(1) < _MAX(HEATER_1_MINTEMP, TEMP_SENSOR_1_MAX_TC_TMIN + .01)) mintemp_error(H_E1); + if (degHotend(1) > _MIN(HEATER_1_MAXTEMP, TEMP_SENSOR_1_MAX_TC_TMAX - 1.00f)) maxtemp_error(H_E1); + if (degHotend(1) < _MAX(HEATER_1_MINTEMP, TEMP_SENSOR_1_MAX_TC_TMIN + 0.01f)) mintemp_error(H_E1); #endif #if TEMP_SENSOR_IS_MAX_TC(2) - if (degHotend(2) > _MIN(HEATER_2_MAXTEMP, TEMP_SENSOR_2_MAX_TC_TMAX - 1.0)) maxtemp_error(H_E2); - if (degHotend(2) < _MAX(HEATER_2_MINTEMP, TEMP_SENSOR_2_MAX_TC_TMIN + .01)) mintemp_error(H_E2); + if (degHotend(2) > _MIN(HEATER_2_MAXTEMP, TEMP_SENSOR_2_MAX_TC_TMAX - 1.00f)) maxtemp_error(H_E2); + if (degHotend(2) < _MAX(HEATER_2_MINTEMP, TEMP_SENSOR_2_MAX_TC_TMIN + 0.01f)) mintemp_error(H_E2); #endif #if TEMP_SENSOR_IS_MAX_TC(REDUNDANT) - if (degRedundant() > TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - 1.0) maxtemp_error(H_REDUNDANT); - if (degRedundant() < TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + .01) mintemp_error(H_REDUNDANT); + if (degRedundant() > TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - 1.00f) maxtemp_error(H_REDUNDANT); + if (degRedundant() < TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + 0.01f) mintemp_error(H_REDUNDANT); #endif #else #warning "Safety Alert! Disable IGNORE_THERMOCOUPLE_ERRORS for the final build!" @@ -2135,7 +2129,7 @@ void Temperature::task() { max31865_0.temperature(MAX31865_SENSOR_OHMS_0, MAX31865_CALIBRATION_OHMS_0) ); #else - return (int16_t)raw * 0.25; + return (int16_t)raw * 0.25f; #endif #elif TEMP_SENSOR_0_IS_AD595 return TEMP_AD595(raw); @@ -2154,7 +2148,7 @@ void Temperature::task() { max31865_1.temperature(MAX31865_SENSOR_OHMS_1, MAX31865_CALIBRATION_OHMS_1) ); #else - return (int16_t)raw * 0.25; + return (int16_t)raw * 0.25f; #endif #elif TEMP_SENSOR_1_IS_AD595 return TEMP_AD595(raw); @@ -2173,7 +2167,7 @@ void Temperature::task() { max31865_2.temperature(MAX31865_SENSOR_OHMS_2, MAX31865_CALIBRATION_OHMS_2) ); #else - return (int16_t)raw * 0.25; + return (int16_t)raw * 0.25f; #endif #elif TEMP_SENSOR_2_IS_AD595 return TEMP_AD595(raw); @@ -2341,11 +2335,11 @@ void Temperature::task() { #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM return user_thermistor_to_deg_c(CTI_REDUNDANT, raw); #elif TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E0) - return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_0.temperature(raw), (int16_t)raw * 0.25); + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_0.temperature(raw), (int16_t)raw * 0.25f); #elif TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E1) - return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_1.temperature(raw), (int16_t)raw * 0.25); + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_1.temperature(raw), (int16_t)raw * 0.25f); #elif TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E2) - return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_2.temperature(raw), (int16_t)raw * 0.25); + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_2.temperature(raw), (int16_t)raw * 0.25f); #elif TEMP_SENSOR_REDUNDANT_IS_THERMISTOR SCAN_THERMISTOR_TABLE(TEMPTABLE_REDUNDANT, TEMPTABLE_REDUNDANT_LEN); #elif TEMP_SENSOR_REDUNDANT_IS_AD595 @@ -2500,7 +2494,6 @@ void Temperature::init() { TERN_(PROBING_HEATERS_OFF, paused_for_probing = false); - // Init (and disable) SPI thermocouples #if TEMP_SENSOR_IS_ANY_MAX_TC(0) && PIN_EXISTS(TEMP_0_CS) OUT_WRITE(TEMP_0_CS_PIN, HIGH); @@ -3185,12 +3178,10 @@ void Temperature::disable_all_heaters() { MAX6675 &max6675ref = THERMO_SEL(max6675_0, max6675_1, max6675_2); max_tc_temp = max6675ref.readRaw16(); #endif - #if HAS_MAX31855_LIBRARY MAX31855 &max855ref = THERMO_SEL(max31855_0, max31855_1, max31855_2); max_tc_temp = max855ref.readRaw32(); #endif - #if HAS_MAX31865 MAX31865 &max865ref = THERMO_SEL(max31865_0, max31865_1, max31865_2); max_tc_temp = TERN(LIB_INTERNAL_MAX31865, max865ref.readRaw(), max865ref.readRTD_with_Fault()); @@ -3207,30 +3198,21 @@ void Temperature::disable_all_heaters() { SERIAL_ECHOPGM("Temp measurement error! "); #if HAS_MAX31855 SERIAL_ECHOPGM("MAX31855 Fault: (", max_tc_temp & 0x7, ") >> "); - if (max_tc_temp & 0x1) - SERIAL_ECHOLNPGM("Open Circuit"); - else if (max_tc_temp & 0x2) - SERIAL_ECHOLNPGM("Short to GND"); - else if (max_tc_temp & 0x4) - SERIAL_ECHOLNPGM("Short to VCC"); + if (max_tc_temp & 0x1) SERIAL_ECHOLNPGM("Open Circuit"); + else if (max_tc_temp & 0x2) SERIAL_ECHOLNPGM("Short to GND"); + else if (max_tc_temp & 0x4) SERIAL_ECHOLNPGM("Short to VCC"); #elif HAS_MAX31865 const uint8_t fault_31865 = max865ref.readFault(); max865ref.clearFault(); if (fault_31865) { SERIAL_EOL(); SERIAL_ECHOLNPGM("\nMAX31865 Fault: (", fault_31865, ") >>"); - if (fault_31865 & MAX31865_FAULT_HIGHTHRESH) - SERIAL_ECHOLNPGM("RTD High Threshold"); - if (fault_31865 & MAX31865_FAULT_LOWTHRESH) - SERIAL_ECHOLNPGM("RTD Low Threshold"); - if (fault_31865 & MAX31865_FAULT_REFINLOW) - SERIAL_ECHOLNPGM("REFIN- > 0.85 x V bias"); - if (fault_31865 & MAX31865_FAULT_REFINHIGH) - SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); - if (fault_31865 & MAX31865_FAULT_RTDINLOW) - SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); - if (fault_31865 & MAX31865_FAULT_OVUV) - SERIAL_ECHOLNPGM("Under/Over voltage"); + if (fault_31865 & MAX31865_FAULT_HIGHTHRESH) SERIAL_ECHOLNPGM("RTD High Threshold"); + if (fault_31865 & MAX31865_FAULT_LOWTHRESH) SERIAL_ECHOLNPGM("RTD Low Threshold"); + if (fault_31865 & MAX31865_FAULT_REFINLOW) SERIAL_ECHOLNPGM("REFIN- > 0.85 x V bias"); + if (fault_31865 & MAX31865_FAULT_REFINHIGH) SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); + if (fault_31865 & MAX31865_FAULT_RTDINLOW) SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); + if (fault_31865 & MAX31865_FAULT_OVUV) SERIAL_ECHOLNPGM("Under/Over voltage"); } #else // MAX6675 SERIAL_ECHOLNPGM("MAX6675 Fault: Open Circuit"); @@ -4167,6 +4149,7 @@ void Temperature::isr() { } while (wait_for_heatup && TEMP_CONDITIONS); + // If wait_for_heatup is set, temperature was reached, no cancel if (wait_for_heatup) { wait_for_heatup = false; #if HAS_DWIN_E3V2_BASIC @@ -4305,6 +4288,7 @@ void Temperature::isr() { } while (wait_for_heatup && TEMP_BED_CONDITIONS); + // If wait_for_heatup is set, temperature was reached, no cancel if (wait_for_heatup) { wait_for_heatup = false; ui.reset_status(); @@ -4383,6 +4367,7 @@ void Temperature::isr() { } } + // If wait_for_heatup is set, temperature was reached, no cancel if (wait_for_heatup) { wait_for_heatup = false; ui.reset_status(); @@ -4482,6 +4467,7 @@ void Temperature::isr() { } } while (wait_for_heatup && TEMP_CHAMBER_CONDITIONS); + // If wait_for_heatup is set, temperature was reached, no cancel if (wait_for_heatup) { wait_for_heatup = false; ui.reset_status(); @@ -4568,6 +4554,7 @@ void Temperature::isr() { first_loop = false; #endif // TEMP_COOLER_RESIDENCY_TIME > 0 + // Prevent a wait-forever situation if R is misused i.e. M191 R0 if (wants_to_cool) { // Break after MIN_COOLING_SLOPE_TIME_CHAMBER seconds // if the temperature did not drop at least MIN_COOLING_SLOPE_DEG_CHAMBER @@ -4580,7 +4567,7 @@ void Temperature::isr() { } while (wait_for_heatup && TEMP_COOLER_CONDITIONS); - // Prevent a wait-forever situation if R is misused i.e. M191 R0 + // If wait_for_heatup is set, temperature was reached, no cancel if (wait_for_heatup) { wait_for_heatup = false; ui.reset_status(); diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 6425b5b3fb..270f70ff28 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -146,7 +146,7 @@ typedef struct { float p, i, d, c, f; } raw_pidcf_t; #if HAS_PID_HEATING - #define PID_K2 (1-float(PID_K1)) + #define PID_K2 (1.0f - float(PID_K1)) #define PID_dT ((OVERSAMPLENR * float(ACTUAL_ADC_SAMPLES)) / (TEMP_TIMER_FREQUENCY)) // Apply the scale factors to the PID values @@ -162,125 +162,125 @@ typedef struct { float p, i, d, c, f; } raw_pidcf_t; /// PID classes that implement these features are expected to override these methods /// Since the finally used PID class is typedef-d, there is no need to use virtual functions template - struct PID_t{ - protected: - bool pid_reset = true; - float temp_iState = 0.0f, temp_dState = 0.0f; - float work_p = 0, work_i = 0, work_d = 0; + struct PID_t { + protected: + bool pid_reset = true; + float temp_iState = 0.0f, temp_dState = 0.0f; + float work_p = 0, work_i = 0, work_d = 0; - public: - float Kp = 0, Ki = 0, Kd = 0; - float p() const { return Kp; } - float i() const { return unscalePID_i(Ki); } - float d() const { return unscalePID_d(Kd); } - float c() const { return 1; } - float f() const { return 0; } - float pTerm() const { return work_p; } - float iTerm() const { return work_i; } - float dTerm() const { return work_d; } - float cTerm() const { return 0; } - float fTerm() const { return 0; } - void set_Kp(float p) { Kp = p; } - void set_Ki(float i) { Ki = scalePID_i(i); } - void set_Kd(float d) { Kd = scalePID_d(d); } - void set_Kc(float) {} - void set_Kf(float) {} - int low() const { return MIN_POW; } - int high() const { return MAX_POW; } - void reset() { pid_reset = true; } - void set(float p, float i, float d, float c=1, float f=0) { set_Kp(p); set_Ki(i); set_Kd(d); set_Kc(c); set_Kf(f); } - void set(const raw_pid_t &raw) { set(raw.p, raw.i, raw.d); } - void set(const raw_pidcf_t &raw) { set(raw.p, raw.i, raw.d, raw.c, raw.f); } + public: + float Kp = 0, Ki = 0, Kd = 0; + float p() const { return Kp; } + float i() const { return unscalePID_i(Ki); } + float d() const { return unscalePID_d(Kd); } + float c() const { return 1; } + float f() const { return 0; } + float pTerm() const { return work_p; } + float iTerm() const { return work_i; } + float dTerm() const { return work_d; } + float cTerm() const { return 0; } + float fTerm() const { return 0; } + void set_Kp(float p) { Kp = p; } + void set_Ki(float i) { Ki = scalePID_i(i); } + void set_Kd(float d) { Kd = scalePID_d(d); } + void set_Kc(float) {} + void set_Kf(float) {} + int low() const { return MIN_POW; } + int high() const { return MAX_POW; } + void reset() { pid_reset = true; } + void set(float p, float i, float d, float c=1, float f=0) { set_Kp(p); set_Ki(i); set_Kd(d); set_Kc(c); set_Kf(f); } + void set(const raw_pid_t &raw) { set(raw.p, raw.i, raw.d); } + void set(const raw_pidcf_t &raw) { set(raw.p, raw.i, raw.d, raw.c, raw.f); } - float get_fan_scale_output(const uint8_t) { return 0; } + float get_fan_scale_output(const uint8_t) { return 0; } - float get_extrusion_scale_output(const bool, const int32_t, const float, const int16_t) { return 0; } + float get_extrusion_scale_output(const bool, const int32_t, const float, const int16_t) { return 0; } - float get_pid_output(const float target, const float current) { - const float pid_error = target - current; - if (!target || pid_error < -(PID_FUNCTIONAL_RANGE)) { - pid_reset = true; - return 0; + float get_pid_output(const float target, const float current) { + const float pid_error = target - current; + if (!target || pid_error < -(PID_FUNCTIONAL_RANGE)) { + pid_reset = true; + return 0; + } + else if (pid_error > PID_FUNCTIONAL_RANGE) { + pid_reset = true; + return MAX_POW; + } + + if (pid_reset) { + pid_reset = false; + temp_iState = 0.0; + work_d = 0.0; + } + + const float max_power_over_i_gain = float(MAX_POW) / Ki - float(MIN_POW); + temp_iState = constrain(temp_iState + pid_error, 0, max_power_over_i_gain); + + work_p = Kp * pid_error; + work_i = Ki * temp_iState; + work_d = work_d + PID_K2 * (Kd * (temp_dState - current) - work_d); + + temp_dState = current; + + return constrain(work_p + work_i + work_d + float(MIN_POW), 0, MAX_POW); } - else if (pid_error > PID_FUNCTIONAL_RANGE) { - pid_reset = true; - return MAX_POW; - } - - if (pid_reset) { - pid_reset = false; - temp_iState = 0.0; - work_d = 0.0; - } - - const float max_power_over_i_gain = float(MAX_POW) / Ki - float(MIN_POW); - temp_iState = constrain(temp_iState + pid_error, 0, max_power_over_i_gain); - - work_p = Kp * pid_error; - work_i = Ki * temp_iState; - work_d = work_d + PID_K2 * (Kd * (temp_dState - current) - work_d); - - temp_dState = current; - - return constrain(work_p + work_i + work_d + float(MIN_POW), 0, MAX_POW); - } }; -#endif +#endif // HAS_PID_HEATING #if ENABLED(PIDTEMP) /// @brief Extrusion scaled PID class template struct PIDC_t : public PID_t { - private: - using base = PID_t; - float work_c = 0; - float prev_e_pos = 0; - int32_t lpq[LPQ_ARR_SZ] = {}; - int16_t lpq_ptr = 0; - public: - float Kc = 0; - float c() const { return Kc; } - void set_Kc(float c) { Kc = c; } - float cTerm() const { return work_c; } - void set(float p, float i, float d, float c=1, float f=0) { - base::set_Kp(p); - base::set_Ki(i); - base::set_Kd(d); - set_Kc(c); - base::set_Kf(f); - } - void set(const raw_pid_t &raw) { set(raw.p, raw.i, raw.d); } - void set(const raw_pidcf_t &raw) { set(raw.p, raw.i, raw.d, raw.c, raw.f); } - void reset() { - base::reset(); - prev_e_pos = 0; - lpq_ptr = 0; - for (uint8_t i = 0; i < LPQ_ARR_SZ; ++i) lpq[i] = 0; - } - - float get_extrusion_scale_output(const bool is_active, const int32_t e_position, const float e_mm_per_step, const int16_t lpq_len) { - work_c = 0; - if (!is_active) return work_c; - - if (e_position > prev_e_pos) { - lpq[lpq_ptr] = e_position - prev_e_pos; - prev_e_pos = e_position; + private: + using base = PID_t; + float work_c = 0; + float prev_e_pos = 0; + int32_t lpq[LPQ_ARR_SZ] = {}; + int16_t lpq_ptr = 0; + public: + float Kc = 0; + float c() const { return Kc; } + void set_Kc(float c) { Kc = c; } + float cTerm() const { return work_c; } + void set(float p, float i, float d, float c=1, float f=0) { + base::set_Kp(p); + base::set_Ki(i); + base::set_Kd(d); + set_Kc(c); + base::set_Kf(f); } - else - lpq[lpq_ptr] = 0; - - ++lpq_ptr; - - if (lpq_ptr >= LPQ_ARR_SZ || lpq_ptr >= lpq_len) + void set(const raw_pid_t &raw) { set(raw.p, raw.i, raw.d); } + void set(const raw_pidcf_t &raw) { set(raw.p, raw.i, raw.d, raw.c, raw.f); } + void reset() { + base::reset(); + prev_e_pos = 0; lpq_ptr = 0; + for (uint8_t i = 0; i < LPQ_ARR_SZ; ++i) lpq[i] = 0; + } - work_c = (lpq[lpq_ptr] * e_mm_per_step) * Kc; + float get_extrusion_scale_output(const bool is_active, const int32_t e_position, const float e_mm_per_step, const int16_t lpq_len) { + work_c = 0; + if (!is_active) return work_c; - return work_c; - } + if (e_position > prev_e_pos) { + lpq[lpq_ptr] = e_position - prev_e_pos; + prev_e_pos = e_position; + } + else + lpq[lpq_ptr] = 0; + + ++lpq_ptr; + + if (lpq_ptr >= LPQ_ARR_SZ || lpq_ptr >= lpq_len) + lpq_ptr = 0; + + work_c = (lpq[lpq_ptr] * e_mm_per_step) * Kc; + + return work_c; + } }; /// @brief Fan scaled PID, this class implements the get_fan_scale_output() method @@ -290,67 +290,67 @@ typedef struct { float p, i, d, c, f; } raw_pidcf_t; /// @tparam SCALE_LIN_FACTOR parameter from Configuration_adv.h template struct PIDF_t : public PID_t { - private: - using base = PID_t; - float work_f = 0; - public: - float Kf = 0; - float f() const { return Kf; } - void set_Kf(float f) { Kf = f; } - float fTerm() const { return work_f; } - void set(float p, float i, float d, float c=1, float f=0) { - base::set_Kp(p); - base::set_Ki(i); - base::set_Kd(d); - base::set_Kc(c); - set_Kf(f); - } - void set(const raw_pid_t &raw) { set(raw.p, raw.i, raw.d); } - void set(const raw_pidcf_t &raw) { set(raw.p, raw.i, raw.d, raw.c, raw.f); } + private: + using base = PID_t; + float work_f = 0; + public: + float Kf = 0; + float f() const { return Kf; } + void set_Kf(float f) { Kf = f; } + float fTerm() const { return work_f; } + void set(float p, float i, float d, float c=1, float f=0) { + base::set_Kp(p); + base::set_Ki(i); + base::set_Kd(d); + base::set_Kc(c); + set_Kf(f); + } + void set(const raw_pid_t &raw) { set(raw.p, raw.i, raw.d); } + void set(const raw_pidcf_t &raw) { set(raw.p, raw.i, raw.d, raw.c, raw.f); } - float get_fan_scale_output(const uint8_t fan_speed) { - work_f = 0; - if (fan_speed > SCALE_MIN_SPEED) - work_f = Kf + (SCALE_LIN_FACTOR) * fan_speed; + float get_fan_scale_output(const uint8_t fan_speed) { + work_f = 0; + if (fan_speed > SCALE_MIN_SPEED) + work_f = Kf + (SCALE_LIN_FACTOR) * fan_speed; - return work_f; - } + return work_f; + } }; /// @brief Inherits PID and PIDC - can't use proper diamond inheritance w/o virtual template struct PIDCF_t : public PIDC_t { - private: - using base = PID_t; - using cPID = PIDC_t; - float work_f = 0; - public: - float Kf = 0; - float c() const { return cPID::c(); } - float f() const { return Kf; } - void set_Kc(float c) { cPID::set_Kc(c); } - void set_Kf(float f) { Kf = f; } - float cTerm() const { return cPID::cTerm(); } - float fTerm() const { return work_f; } - void set(float p, float i, float d, float c=1, float f=0) { - base::set_Kp(p); - base::set_Ki(i); - base::set_Kd(d); - cPID::set_Kc(c); - set_Kf(f); - } - void set(const raw_pid_t &raw) { set(raw.p, raw.i, raw.d); } - void set(const raw_pidcf_t &raw) { set(raw.p, raw.i, raw.d, raw.c, raw.f); } + private: + using base = PID_t; + using cPID = PIDC_t; + float work_f = 0; + public: + float Kf = 0; + float c() const { return cPID::c(); } + float f() const { return Kf; } + void set_Kc(float c) { cPID::set_Kc(c); } + void set_Kf(float f) { Kf = f; } + float cTerm() const { return cPID::cTerm(); } + float fTerm() const { return work_f; } + void set(float p, float i, float d, float c=1, float f=0) { + base::set_Kp(p); + base::set_Ki(i); + base::set_Kd(d); + cPID::set_Kc(c); + set_Kf(f); + } + void set(const raw_pid_t &raw) { set(raw.p, raw.i, raw.d); } + void set(const raw_pidcf_t &raw) { set(raw.p, raw.i, raw.d, raw.c, raw.f); } - void reset() { cPID::reset(); } + void reset() { cPID::reset(); } - float get_fan_scale_output(const uint8_t fan_speed) { - work_f = fan_speed > (SCALE_MIN_SPEED) ? Kf + (SCALE_LIN_FACTOR) * fan_speed : 0; - return work_f; - } - float get_extrusion_scale_output(const bool is_active, const int32_t e_position, const float e_mm_per_step, const int16_t lpq_len) { - return cPID::get_extrusion_scale_output(is_active, e_position, e_mm_per_step, lpq_len); - } + float get_fan_scale_output(const uint8_t fan_speed) { + work_f = fan_speed > (SCALE_MIN_SPEED) ? Kf + (SCALE_LIN_FACTOR) * fan_speed : 0; + return work_f; + } + float get_extrusion_scale_output(const bool is_active, const int32_t e_position, const float e_mm_per_step, const int16_t lpq_len) { + return cPID::get_extrusion_scale_output(is_active, e_position, e_mm_per_step, lpq_len); + } }; typedef @@ -394,16 +394,16 @@ typedef struct { float p, i, d, c, f; } raw_pidcf_t; // A temperature sensor typedef struct TempInfo { -private: - raw_adc_t acc; - raw_adc_t raw; -public: - celsius_float_t celsius; - inline void reset() { acc = 0; } - inline void sample(const raw_adc_t s) { acc += s; } - inline void update() { raw = acc; } - void setraw(const raw_adc_t r) { raw = r; } - raw_adc_t getraw() const { return raw; } + private: + raw_adc_t acc; + raw_adc_t raw; + public: + celsius_float_t celsius; + inline void reset() { acc = 0; } + inline void sample(const raw_adc_t s) { acc += s; } + inline void update() { raw = acc; } + void setraw(const raw_adc_t r) { raw = r; } + raw_adc_t getraw() const { return raw; } } temp_info_t; #if HAS_TEMP_REDUNDANT @@ -740,7 +740,7 @@ class Temperature { static raw_adc_t mintemp_raw_COOLER, maxtemp_raw_COOLER; #endif - #if HAS_TEMP_BOARD && ENABLED(THERMAL_PROTECTION_BOARD) + #if ALL(HAS_TEMP_BOARD, THERMAL_PROTECTION_BOARD) static raw_adc_t mintemp_raw_BOARD, maxtemp_raw_BOARD; #endif @@ -1164,7 +1164,7 @@ class Temperature { } #endif - #endif + #endif // HAS_PID_HEATING #if ENABLED(MPCTEMP) void MPC_autotune(); diff --git a/Marlin/src/module/thermistor/thermistor_666.h b/Marlin/src/module/thermistor/thermistor_666.h index bba3e606fc..14a03c23b5 100644 --- a/Marlin/src/module/thermistor/thermistor_666.h +++ b/Marlin/src/module/thermistor/thermistor_666.h @@ -27,7 +27,7 @@ */ //#include "output_table.h" -/* +/** * Parameters: * A: -0.000480634 * B: 0.00031362 diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 194f7c555a..9c7ba0ee47 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -441,7 +441,6 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. } } - #endif // TOOL_SENSOR #if ENABLED(SWITCHING_TOOLHEAD) @@ -964,7 +963,6 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. * If cooling fan is enabled, calls filament_swap_cooling(); */ void extruder_prime() { - if (too_cold(active_extruder)) { FS_DEBUG("Priming Aborted - Nozzle Too Cold!"); return; // Extruder too cold to prime @@ -1017,7 +1015,6 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. // Cool down with fan filament_swap_cooling(); - } /** @@ -1223,7 +1220,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #endif #endif - #if DISABLED(TOOLCHANGE_ZRAISE_BEFORE_RETRACT) && DISABLED(SWITCHING_NOZZLE) + #if NONE(TOOLCHANGE_ZRAISE_BEFORE_RETRACT, SWITCHING_NOZZLE) if (can_move_away && TERN1(TOOLCHANGE_PARK, toolchange_settings.enable_park)) { // Do a small lift to avoid the workpiece in the move back (below) current_position.z += toolchange_settings.z_raise; @@ -1517,6 +1514,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { planner.synchronize(); planner.set_e_position_mm(current_position.e); // New extruder primed and ready + DEBUG_ECHOLNPGM("Migration Complete"); return true; } diff --git a/Marlin/src/module/tool_change.h b/Marlin/src/module/tool_change.h index ff456485e2..3cb8b4a637 100644 --- a/Marlin/src/module/tool_change.h +++ b/Marlin/src/module/tool_change.h @@ -34,8 +34,8 @@ float extra_resume; // M217 B int16_t prime_speed; // M217 P int16_t wipe_retract; // M217 G - int16_t retract_speed; // M217 R - int16_t unretract_speed; // M217 U + int16_t retract_speed; // M217 R (mm/min) + int16_t unretract_speed; // M217 U (mm/min) uint8_t fan_speed; // M217 F uint8_t fan_time; // M217 D #endif diff --git a/Marlin/src/pins/esp32/pins_E4D.h b/Marlin/src/pins/esp32/pins_E4D.h index 15b697a85b..06e46e3c4c 100644 --- a/Marlin/src/pins/esp32/pins_E4D.h +++ b/Marlin/src/pins/esp32/pins_E4D.h @@ -30,9 +30,7 @@ #include "env_validate.h" -#if EXTRUDERS > 1 || E_STEPPERS > 1 - #error "E4d@box only supports 1 E stepper." -#elif HAS_MULTI_HOTEND +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 #error "E4d@box only supports 1 hotend / E stepper." #endif diff --git a/Marlin/src/pins/esp32/pins_FYSETC_E4.h b/Marlin/src/pins/esp32/pins_FYSETC_E4.h index 7dc59979c8..4bcffb545e 100644 --- a/Marlin/src/pins/esp32/pins_FYSETC_E4.h +++ b/Marlin/src/pins/esp32/pins_FYSETC_E4.h @@ -30,9 +30,7 @@ #include "env_validate.h" -#if EXTRUDERS > 1 || E_STEPPERS > 1 - #error "FYSETC E4 only supports 1 E stepper." -#elif HAS_MULTI_HOTEND +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 #error "FYSETC E4 only supports 1 hotend / E stepper." #endif diff --git a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h index 03a233c6d8..60ed800ba6 100644 --- a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h +++ b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h @@ -22,10 +22,8 @@ #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. + * MKS TinyBee pin assignments + * https://github.com/makerbase-mks/MKS-TinyBee */ #include "env_validate.h" diff --git a/Marlin/src/pins/esp32/pins_MRR_ESPA.h b/Marlin/src/pins/esp32/pins_MRR_ESPA.h index e9e3db5758..ba5f6cbe35 100644 --- a/Marlin/src/pins/esp32/pins_MRR_ESPA.h +++ b/Marlin/src/pins/esp32/pins_MRR_ESPA.h @@ -30,9 +30,7 @@ #include "env_validate.h" -#if EXTRUDERS > 1 || E_STEPPERS > 1 - #error "MRR ESPA only supports 1 E stepper." -#elif HAS_MULTI_HOTEND +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 #error "MRR ESPA only supports 1 hotend / E stepper." #endif diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index 1258f399e7..6ec4864a7c 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -221,12 +221,12 @@ // #if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // Prefer the servo connector - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_DIR_PIN 5 #elif HAS_FREE_AUX2_PINS // try to use AUX 2 - #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! #define SPINDLE_DIR_PIN 65 #endif #endif @@ -379,12 +379,12 @@ #if ANY(TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI) - #define TFT_A0_PIN 43 #define TFT_CS_PIN 49 #define TFT_DC_PIN 43 + #define TFT_A0_PIN TFT_DC_PIN #define TFT_SCK_PIN SD_SCK_PIN - #define TFT_MOSI_PIN SD_MOSI_PIN #define TFT_MISO_PIN SD_MISO_PIN + #define TFT_MOSI_PIN SD_MOSI_PIN #define LCD_USE_DMA_SPI #define BTN_EN1 40 @@ -398,12 +398,12 @@ #define SPI_FLASH #if ENABLED(SPI_FLASH) - #define SPI_DEVICE 1 + #define SPI_DEVICE 1 // Maple #define SPI_FLASH_SIZE 0x1000000 // 16MB #define SPI_FLASH_CS_PIN 31 - #define SPI_FLASH_MOSI_PIN SD_MOSI_PIN - #define SPI_FLASH_MISO_PIN SD_MISO_PIN #define SPI_FLASH_SCK_PIN SD_SCK_PIN + #define SPI_FLASH_MISO_PIN SD_MISO_PIN + #define SPI_FLASH_MOSI_PIN SD_MOSI_PIN #endif #define TFT_BUFFER_SIZE 0xFFFF diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h index da262e087b..008fc3d4a0 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -58,7 +58,6 @@ #define E0_DIR_PIN P2_13 #define E0_ENABLE_PIN P2_12 - /** ------ ------ * 1.30 | 1 2 | 2.11 0.17 | 1 2 | 0.15 * 0.18 | 3 4 | 0.16 3.26 | 3 4 | 1.23 @@ -203,7 +202,7 @@ #undef E1_ENABLE_PIN #endif - #else // !SOFTWARE_DRIVER_ENABLE + #else // !SOFTWARE_DRIVER_ENABLE // A chip-select pin is needed for each driver. diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 28fc9710b7..a198af6884 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -291,7 +291,7 @@ #define DOGLCD_A0 EXP1_06_PIN #define DOGLCD_SCK EXP1_04_PIN #define DOGLCD_MOSI EXP1_01_PIN - #define LCD_BACKLIGHT_PIN -1 + #define LCD_BACKLIGHT_PIN -1 #elif ENABLED(CR10_STOCKDISPLAY) @@ -379,7 +379,7 @@ #define SD_DETECT_PIN EXP2_07_PIN - #else // !CR10_STOCKDISPLAY + #else // !CR10_STOCKDISPLAY #define LCD_PINS_RS EXP1_04_PIN @@ -420,7 +420,7 @@ #define NEOPIXEL_PIN EXP1_06_PIN #endif - #else // !FYSETC_MINI_12864 + #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index 99234884da..e7744b221a 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -463,7 +463,7 @@ #define NEOPIXEL_PIN EXP1_06_PIN #endif - #else // !FYSETC_MINI_12864 + #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) #define DOGLCD_CS EXP1_06_PIN diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index db1d0d0513..e6f306c9ac 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -294,8 +294,8 @@ #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI #define TFT_CS_PIN EXP1_07_PIN - #define TFT_A0_PIN EXP1_08_PIN #define TFT_DC_PIN EXP1_08_PIN + #define TFT_A0_PIN TFT_DC_PIN #define TFT_MISO_PIN EXP2_01_PIN #define TFT_BACKLIGHT_PIN EXP1_03_PIN #define TFT_RESET_PIN EXP1_04_PIN @@ -349,7 +349,7 @@ #define LCD_PINS_D7 EXP1_08_PIN #define KILL_PIN -1 // NC - #else // !MKS_12864OLED_SSD1306 + #else // !MKS_12864OLED_SSD1306 #define LCD_PINS_RS EXP1_04_PIN @@ -384,7 +384,7 @@ #define NEOPIXEL_PIN EXP1_06_PIN #endif - #else // !FYSETC_MINI_12864 + #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) #define DOGLCD_CS EXP1_06_PIN diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index 0985e0da10..e7dade8844 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -121,7 +121,6 @@ * If undefined software serial is used according to the pins below */ - // P2_08 E1-Step // P2_13 E1-Dir @@ -252,8 +251,8 @@ #error "LASER_FEATURE requires 3 free servo pins." #endif #endif - #define SPINDLE_LASER_ENA_PIN SERVO1_PIN // (6) Pin should have a pullup/pulldown! #define SPINDLE_LASER_PWM_PIN SERVO3_PIN // (4) MUST BE HARDWARE PWM + #define SPINDLE_LASER_ENA_PIN SERVO1_PIN // (6) Pin should have a pullup/pulldown! #define SPINDLE_DIR_PIN SERVO2_PIN // (5) #endif diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h index f164cfec28..5f5e2ddc3a 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h @@ -155,8 +155,8 @@ #undef HEATER_0_PIN #undef HEATER_BED_PIN #undef FAN0_PIN - #define SPINDLE_LASER_ENA_PIN P2_07 // FET 1 #define SPINDLE_LASER_PWM_PIN P2_05 // Bed FET + #define SPINDLE_LASER_ENA_PIN P2_07 // FET 1 #define SPINDLE_DIR_PIN P2_06 // FET 4 #endif diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index fc57eb3b78..ec43bde621 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -344,7 +344,7 @@ #define TFT_CS_PIN EXP1_07_PIN #define TFT_DC_PIN EXP1_08_PIN - #define TFT_A0_PIN TFT_DC_PIN + #define TFT_A0_PIN TFT_DC_PIN #define TFT_MISO_PIN EXP2_01_PIN #define TFT_BACKLIGHT_PIN EXP1_03_PIN #define TFT_RESET_PIN EXP1_04_PIN @@ -367,7 +367,7 @@ #define TFT_QUEUE_SIZE 6144 #endif - #else // !MKS_12864OLED_SSD1306 + #else // !MKS_12864OLED_SSD1306 #define LCD_PINS_RS EXP1_04_PIN @@ -402,7 +402,7 @@ #define NEOPIXEL_PIN EXP1_06_PIN #endif - #else // !FYSETC_MINI_12864 + #else // !FYSETC_MINI_12864 #if ENABLED(MKS_MINI_12864) #define DOGLCD_CS EXP1_06_PIN diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_A.h b/Marlin/src/pins/mega/pins_GT2560_REV_A.h index 61c61f94ff..cf07091826 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_A.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_A.h @@ -147,7 +147,7 @@ #define BTN_ENC 19 #define SD_DETECT_PIN 38 - #else // !IS_NEWPANEL + #else // !IS_NEWPANEL #define SHIFT_CLK_PIN 38 #define SHIFT_LD_PIN 42 diff --git a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h index 79eef14366..512da02834 100644 --- a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h +++ b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h @@ -114,9 +114,9 @@ // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER - #define SPINDLE_DIR_PIN 16 - #define SPINDLE_LASER_ENA_PIN 17 // Pin should have a pullup! #define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 17 // Pin should have a pullup! + #define SPINDLE_DIR_PIN 16 #endif // diff --git a/Marlin/src/pins/mega/pins_MINITRONICS.h b/Marlin/src/pins/mega/pins_MINITRONICS.h index 6d0309c4c1..c8828faea7 100644 --- a/Marlin/src/pins/mega/pins_MINITRONICS.h +++ b/Marlin/src/pins/mega/pins_MINITRONICS.h @@ -141,7 +141,7 @@ #define HEATER_BED_PIN 4 // won't compile #define TEMP_BED_PIN 50 #define TEMP_0_PIN 51 - #define SPINDLE_LASER_ENA_PIN 52 // using A6 because it already has a pullup #define SPINDLE_LASER_PWM_PIN 3 // WARNING - LED & resistor pull up to +12/+24V stepper voltage + #define SPINDLE_LASER_ENA_PIN 52 // using A6 because it already has a pullup #define SPINDLE_DIR_PIN 53 #endif diff --git a/Marlin/src/pins/mega/pins_PICAOLD.h b/Marlin/src/pins/mega/pins_PICAOLD.h index e15b4637b7..3654a45d3f 100644 --- a/Marlin/src/pins/mega/pins_PICAOLD.h +++ b/Marlin/src/pins/mega/pins_PICAOLD.h @@ -25,9 +25,9 @@ // Origin: https://github.com/mjrice/PICA/blob/97ab9e7771a8e5eef97788f3adcc17a9fa9de9b9/pica_schematic.pdf // ATmega2560 -#define HEATER_0_PIN 9 // E0 -#define HEATER_1_PIN 10 // E1 -#define FAN0_PIN 11 -#define FAN2_PIN 12 +#define HEATER_0_PIN 9 // E0 +#define HEATER_1_PIN 10 // E1 +#define FAN0_PIN 11 +#define FAN2_PIN 12 #include "pins_PICA.h" diff --git a/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h b/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h index 18e2c0f647..962fddc192 100644 --- a/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h +++ b/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h @@ -54,16 +54,16 @@ #define Y_STEP_PIN 3 #define Y_DIR_PIN 6 -#define Y_ENABLE_PIN X_ENABLE_PIN +#define Y_ENABLE_PIN X_ENABLE_PIN #define Z_STEP_PIN 4 #define Z_DIR_PIN 7 -#define Z_ENABLE_PIN X_ENABLE_PIN +#define Z_ENABLE_PIN X_ENABLE_PIN // Designated with letter "A" on BOARD #define E0_STEP_PIN 12 #define E0_DIR_PIN 13 -#define E0_ENABLE_PIN X_ENABLE_PIN +#define E0_ENABLE_PIN X_ENABLE_PIN // // Temperature sensors - These could be any analog output not hidden by board diff --git a/Marlin/src/pins/mega/pins_SILVER_GATE.h b/Marlin/src/pins/mega/pins_SILVER_GATE.h index c871f7e32f..d739157aaf 100644 --- a/Marlin/src/pins/mega/pins_SILVER_GATE.h +++ b/Marlin/src/pins/mega/pins_SILVER_GATE.h @@ -75,7 +75,7 @@ #define TEMP_BED_PIN 6 #if HAS_WIRED_LCD - #if IS_U8GLIB_ST7920 // SPI GLCD 12864 ST7920 + #if IS_U8GLIB_ST7920 // SPI GLCD 12864 ST7920 #define LCD_PINS_RS 30 #define LCD_PINS_EN 20 #define LCD_PINS_D4 25 diff --git a/Marlin/src/pins/pinsDebug.h b/Marlin/src/pins/pinsDebug.h index d36e38b0d9..8ab5fedabf 100644 --- a/Marlin/src/pins/pinsDebug.h +++ b/Marlin/src/pins/pinsDebug.h @@ -81,7 +81,6 @@ #define REPORT_NAME_DIGITAL(COUNTER, NAME) _ADD_PIN(NAME, COUNTER, true) #define REPORT_NAME_ANALOG(COUNTER, NAME) _ADD_PIN(analogInputToDigitalPin(NAME), COUNTER, false) - typedef struct { PGM_P const name; pin_t pin; diff --git a/Marlin/src/pins/rambo/pins_MINIRAMBO.h b/Marlin/src/pins/rambo/pins_MINIRAMBO.h index 6e1a460838..e2ad4e3815 100644 --- a/Marlin/src/pins/rambo/pins_MINIRAMBO.h +++ b/Marlin/src/pins/rambo/pins_MINIRAMBO.h @@ -170,7 +170,7 @@ #define SD_DETECT_PIN 72 - #else // !MINIRAMBO_10A + #else // !MINIRAMBO_10A // AUX-4 #define BEEPER_PIN 84 diff --git a/Marlin/src/pins/rambo/pins_RAMBO.h b/Marlin/src/pins/rambo/pins_RAMBO.h index 3714f1ee83..9127e2360d 100644 --- a/Marlin/src/pins/rambo/pins_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_RAMBO.h @@ -230,7 +230,7 @@ #define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 - #else // !VIKI2 && !miniVIKI + #else // !VIKI2 && !miniVIKI #define BEEPER_PIN 79 // AUX-4 @@ -251,7 +251,7 @@ #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder #endif - #else // !IS_NEWPANEL - old style panel with shift register + #else // !IS_NEWPANEL - old style panel with shift register // No Beeper added #define BEEPER_PIN 33 diff --git a/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h b/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h index 6155e9842a..aab66f0fea 100644 --- a/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h +++ b/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h @@ -35,7 +35,6 @@ // // Heaters / Fans // -// Power outputs BEEF or BEFF -#define MOSFET_D_PIN 7 +#define MOSFET_D_PIN 7 #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h index cd3ada25bf..4a96d58fd9 100644 --- a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h +++ b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h @@ -121,7 +121,7 @@ #include "pins_RAMPS_13.h" // ... RAMPS // -// Used by the Hephestos 2 heated bed upgrade kit +// Hephestos 2 heated bed upgrade kit uses pin 8 // #if ENABLED(HEPHESTOS2_HEATED_BED_KIT) #undef HEATER_BED_PIN diff --git a/Marlin/src/pins/ramps/pins_FELIX2.h b/Marlin/src/pins/ramps/pins_FELIX2.h index 48ef896e96..34bd29d19f 100644 --- a/Marlin/src/pins/ramps/pins_FELIX2.h +++ b/Marlin/src/pins/ramps/pins_FELIX2.h @@ -35,24 +35,23 @@ // // Heaters / Fans // -// Power outputs EFBF or EFBE -#define MOSFET_D_PIN 7 +#define MOSFET_D_PIN 7 #include "pins_RAMPS.h" // // Misc. Functions // -#define SDPOWER_PIN 1 +#define SDPOWER_PIN 1 -#define PS_ON_PIN 12 +#define PS_ON_PIN 12 // // LCD / Controller // #if HAS_WIRED_LCD && IS_NEWPANEL - #define SD_DETECT_PIN 6 + #define SD_DETECT_PIN 6 #endif diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h index d79eb8041c..65828fd4fb 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h @@ -44,12 +44,12 @@ // #if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) #if !NUM_SERVOS // Try to use servo connector first - #define SPINDLE_LASER_ENA_PIN 6 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 6 // Pullup or pulldown! #define SPINDLE_DIR_PIN 5 #elif !GREEDY_PANEL // Try to use AUX2 - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_DIR_PIN 65 #endif #endif diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index 179bad04a5..fad3cc0f9d 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -141,8 +141,8 @@ // #define SDSS 53 #ifndef LED_PIN - #define LED_PIN 13 // The Formbot v 1 board has almost no unassigned pins on it. The Board's LED -#endif // is a good place to get a signal to control the Max7219 LED Matrix. + #define LED_PIN 13 // The Formbot v 1 board has almost no unassigned pins. +#endif // The Board's LED is a good place to connect the Max7219 Matrix. // Use the RAMPS 1.4 Analog input 5 on the AUX2 connector #define FILWIDTH_PIN 5 // Analog Input diff --git a/Marlin/src/pins/ramps/pins_K8400.h b/Marlin/src/pins/ramps/pins_K8400.h index bcb145825b..04ee8740ae 100644 --- a/Marlin/src/pins/ramps/pins_K8400.h +++ b/Marlin/src/pins/ramps/pins_K8400.h @@ -60,7 +60,7 @@ #include "pins_3DRAG.h" // ... RAMPS // -// Heaters / Fans +// Heaters // #undef HEATER_1_PIN #define HEATER_1_PIN 11 diff --git a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h index fc94daf8bd..cb28762adc 100644 --- a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h +++ b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h @@ -128,14 +128,14 @@ // ------------------ ---------------- --------------- ------------- #if ALL(CR10_STOCKDISPLAY, LONGER_LK5) - /** CR-10 Stock Display - * ------ - * GND | 9 10 | 5V - * LCD_PINS_RS D5 | 7 8 | D4 LCD_PINS_EN - * BTN_EN2 D19 | 5 6 D6 LCD_PINS_D4 - * BTN_EN1 D18 | 3 4 | GND - * BEEPER_PIN D11 | 1 2 | D15 BTN_ENC - * ------ + /** CR-10 Stock Display + * ------ + * BEEPER D11 | 1 2 | D15 ENC + * EN1 D18 | 3 4 | GND + * EN2 D19 5 6 | D6 LCD_D4 + * LCD_RS D5 | 7 8 | D4 LCD_ENABLE + * GND | 9 10 | 5V + * ------ * Connected via provided custom cable to: * Aux-1, J21, J17 and Y-Max. */ diff --git a/Marlin/src/pins/ramps/pins_MAKEBOARD_MINI.h b/Marlin/src/pins/ramps/pins_MAKEBOARD_MINI.h index 2ab463d681..6a837a8fb8 100644 --- a/Marlin/src/pins/ramps/pins_MAKEBOARD_MINI.h +++ b/Marlin/src/pins/ramps/pins_MAKEBOARD_MINI.h @@ -28,8 +28,8 @@ // // Only 3 Limit Switch plugs on Micromake C1 // -#define X_STOP_PIN 2 -#define Y_STOP_PIN 15 -#define Z_STOP_PIN 19 +#define X_STOP_PIN 2 +#define Y_STOP_PIN 15 +#define Z_STOP_PIN 19 #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_16.h b/Marlin/src/pins/ramps/pins_MKS_BASE_16.h index 765a601fd0..bb6def5ca4 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_16.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_16.h @@ -38,7 +38,7 @@ // // Servos // -#define SERVO1_PIN 12 // Digital 12 / Pin 25 +#define SERVO1_PIN 12 // // Omitted RAMPS pins diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_common.h b/Marlin/src/pins/ramps/pins_MKS_BASE_common.h index 7608745a4b..2b1b9fe047 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_common.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_common.h @@ -50,12 +50,9 @@ #define CASE_LIGHT_PIN 2 #endif -#endif - -// -// Microstepping pins -// -#if MKS_BASE_VERSION >= 14 // |===== 1.4 =====|===== 1.5+ =====| + // + // Microstepping pins + // |===== 1.4 =====|===== 1.5+ =====| #define X_MS1_PIN 5 // PE3 | Pin 5 | PWM5 | | D3 | SERVO2_PIN #define X_MS2_PIN 6 // PH3 | Pin 15 | PWM6 | Pin 14 | D6 | SERVO1_PIN #define Y_MS1_PIN 59 // PF5 | Pin 92 | A5 | | | diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h index e7cff25e24..9afdc62a53 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h @@ -42,8 +42,6 @@ // // Heaters / Fans // -// Power outputs EFBF or EFBE -// #define MOSFET_B_PIN 7 #define FAN0_PIN 9 diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_L.h b/Marlin/src/pins/ramps/pins_MKS_GEN_L.h index d36789a017..50b7eb395f 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_L.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_L.h @@ -52,11 +52,11 @@ // #ifndef X_CS_PIN - #define X_CS_PIN 59 + #define X_CS_PIN 59 #endif #ifndef Y_CS_PIN - #define Y_CS_PIN 63 + #define Y_CS_PIN 63 #endif #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 9abade9c66..2dc77b0469 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -309,8 +309,8 @@ #endif #define SPINDLE_DIR_PIN 5 #elif HAS_FREE_AUX2_PINS - #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! #define SPINDLE_DIR_PIN 65 #else #error "No auto-assignable Spindle/Laser pins available." @@ -339,8 +339,9 @@ * Hardware serial communication ports. * If undefined software serial is used according to the pins below * - * Serial2 -- AUX-4 Pin 18 (D16 TX2) and AUX-4 Pin 17 (D17 RX2) - * Serial1 -- Pins D18 and D19 are used for Z-MIN and Z-MAX + * Serial1 -- TX1 = D18 RX1 = D19 (Z-MIN and Z-MAX on RAMPS) + * Serial2 -- TX2 = D16 RX2 = D17 (AUX4-18 and AUX4-17) + * Serial3 -- TX3 = D14 RX3 = D15 (Available on some RAMPS-like boards) */ //#define X_HARDWARE_SERIAL Serial1 //#define X2_HARDWARE_SERIAL Serial1 @@ -881,7 +882,7 @@ #define BEEPER_PIN EXP2_05_PIN #endif - #if ENABLED(PANEL_ONE) // Buttons connect directly to AUX-2 + #if ENABLED(PANEL_ONE) // Buttons connect directly to AUX-2 #define BTN_EN1 AUX2_03_PIN #define BTN_EN2 AUX2_04_PIN #define BTN_ENC AUX3_02_PIN diff --git a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h index a5aba31f6b..8c65b2e0b4 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h @@ -32,7 +32,7 @@ // // Heaters / Fans // -#define MOSFET_B_PIN 7 // For HEATER_1_PIN ("EEF" or "EEB") +#define MOSFET_B_PIN 7 #define FAN0_PIN 9 #define FIL_RUNOUT_PIN 2 diff --git a/Marlin/src/pins/ramps/pins_RAMPS_OLD.h b/Marlin/src/pins/ramps/pins_RAMPS_OLD.h index 19b048ec81..1296305706 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_OLD.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_OLD.h @@ -91,7 +91,7 @@ #ifndef FAN0_PIN #define FAN0_PIN 11 #endif -#else // RAMPS_V_1_1 or RAMPS_V_1_2 +#else // RAMPS_V_1_1 or RAMPS_V_1_2 #define HEATER_0_PIN 10 #define HEATER_BED_PIN 8 #ifndef FAN0_PIN diff --git a/Marlin/src/pins/ramps/pins_RAMPS_S_12.h b/Marlin/src/pins/ramps/pins_RAMPS_S_12.h index 870c3bf133..7dad472a4e 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_S_12.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_S_12.h @@ -211,8 +211,8 @@ // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER && !defined(SPINDLE_LASER_ENA_PIN) - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_DIR_PIN 5 #endif diff --git a/Marlin/src/pins/ramps/pins_RUMBA_RAISE3D.h b/Marlin/src/pins/ramps/pins_RUMBA_RAISE3D.h index 57ee32ab29..cc3ce76ac3 100644 --- a/Marlin/src/pins/ramps/pins_RUMBA_RAISE3D.h +++ b/Marlin/src/pins/ramps/pins_RUMBA_RAISE3D.h @@ -27,7 +27,7 @@ #define DEFAULT_MACHINE_NAME "Raise3D N Series" // Raise3D uses thermocouples on the standard input pins -#define TEMP_0_PIN 15 // Analog Input -#define TEMP_1_PIN 14 // Analog Input +#define TEMP_0_PIN 15 // Analog Input +#define TEMP_1_PIN 14 // Analog Input #include "pins_RUMBA.h" diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h index a286c13a30..83dac111cb 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h @@ -28,17 +28,17 @@ #define BOARD_INFO_NAME "Anycubic RAMPS 1.3" -#define MOSFET_B_PIN 44 +#define MOSFET_B_PIN 44 -#define E1_STEP_PIN -1 -#define E1_DIR_PIN -1 -#define E1_ENABLE_PIN -1 -#define E1_CS_PIN -1 +#define E1_STEP_PIN -1 +#define E1_DIR_PIN -1 +#define E1_ENABLE_PIN -1 +#define E1_CS_PIN -1 -#define FAN2_PIN 9 +#define FAN2_PIN 9 #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN 9 + #define E0_AUTO_FAN_PIN 9 #endif #include "pins_RAMPS_13.h" // ... RAMPS diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h index af7a31de4c..e31696f06f 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h @@ -69,6 +69,7 @@ * IIC : 12V GND D21 D20 GND 5V * (SCL SDA) * + * TX2 RX2 RX3 TX3 * END STOPS : D19 D18 D15 D14 D2 D3 * GND GND GND GND GND GND * 5V 5V 5V 5V 5V 5V diff --git a/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h b/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h index 0104dadf7f..17b9f24711 100644 --- a/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h +++ b/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h @@ -38,7 +38,7 @@ // // Servos // -#define SERVO1_PIN 12 // 2560 PIN 25/PB6 +#define SERVO1_PIN 12 // 2560 PIN 25/PB6 // // Import RAMPS 1.4 pins diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index a4f1806c99..2eca360dec 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -230,12 +230,12 @@ // #if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) #if !NUM_SERVOS // Prefer the servo connector - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_DIR_PIN 5 #elif HAS_FREE_AUX2_PINS // Try to use AUX 2 - #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! #define SPINDLE_DIR_PIN 65 #endif #endif diff --git a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h index dc06963289..049e8bc5d8 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h @@ -151,9 +151,9 @@ // #if HAS_CUTTER // use the LED_PIN for spindle speed control or case light #undef LED_PIN - #define SPINDLE_DIR_PIN 16 - #define SPINDLE_LASER_ENA_PIN 17 // Pullup! #define SPINDLE_LASER_PWM_PIN 8 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 17 // Pullup! + #define SPINDLE_DIR_PIN 16 #else #undef LED_PIN #define CASE_LIGHT_PIN 8 diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER.h b/Marlin/src/pins/ramps/pins_ULTIMAKER.h index c822a62faf..0f87e1fd10 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER.h @@ -138,7 +138,7 @@ #define SD_DETECT_PIN 38 - #else // !IS_NEWPANEL - Old style panel with shift register + #else // !IS_NEWPANEL - Old style panel with shift register // Buttons attached to a shift register #define SHIFT_CLK_PIN 38 diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h index cb6e85fbb7..01fc6b416d 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h @@ -195,7 +195,7 @@ #define SD_DETECT_PIN 38 - #else // !IS_NEWPANEL - Old style panel with shift register + #else // !IS_NEWPANEL - Old style panel with shift register // Buttons attached to a shift register #define SHIFT_CLK_PIN 38 @@ -226,9 +226,9 @@ // #if HAS_CUTTER #if ANY(BOARD_REV_1_0, BOARD_REV_1_5) // Use the last three SW positions - #define SPINDLE_DIR_PIN 10 // 1.0: SW4 1.5: EXP3-6 ("10") #define SPINDLE_LASER_PWM_PIN 9 // 1.0: SW5 1.5: EXP3-7 ( "9") .. MUST BE HARDWARE PWM #define SPINDLE_LASER_ENA_PIN 8 // 1.0: SW6 1.5: EXP3-8 ( "8") .. Pin should have a pullup! + #define SPINDLE_DIR_PIN 10 // 1.0: SW4 1.5: EXP3-6 ("10") #elif ENABLED(BOARD_REV_1_1_TO_1_3) /** * Only four hardware PWMs physically connected to anything on these boards: @@ -242,14 +242,14 @@ * They have an LED and resistor pullup to +24V which could damage 3.3V-5V ICs. */ #if EXTRUDERS == 1 - #define SPINDLE_DIR_PIN 43 #define SPINDLE_LASER_PWM_PIN 45 // Hardware PWM #define SPINDLE_LASER_ENA_PIN 41 // Pullup! + #define SPINDLE_DIR_PIN 43 #elif TEMP_SENSOR_BED == 0 // Can't use E0 so see if HEATER_BED_PIN is available #undef HEATER_BED_PIN - #define SPINDLE_DIR_PIN 38 // Probably pin 4 on 10 pin connector closest to the E0 socket #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM - Special precautions usually needed. #define SPINDLE_LASER_ENA_PIN 40 // Pullup! (Probably pin 6 on the 10-pin + #define SPINDLE_DIR_PIN 38 // Probably pin 4 on 10 pin connector closest to the E0 socket // connector closest to the E0 socket) #endif #endif diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V53.h b/Marlin/src/pins/ramps/pins_ZRIB_V53.h index 01375c4bf8..fc8c9055b6 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V53.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V53.h @@ -374,7 +374,7 @@ #define KILL_PIN -1 #if ANY(OLED_HW_IIC, OLED_HW_SPI) #error "Oops! You must choose SW SPI for ZRIB V53 board and connect the OLED screen to EXP1 connector." - #else // SW_SPI + #else // SW_SPI #define DOGLCD_A0 LCD_PINS_DC #define DOGLCD_MOSI 35 // SDA #define DOGLCD_SCK 37 // SCK diff --git a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h index e6d330a35d..6db4661bd8 100644 --- a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h +++ b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h @@ -170,12 +170,12 @@ // #if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // Prefer the servo connector - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_DIR_PIN 5 #elif HAS_FREE_AUX2_PINS - #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! #define SPINDLE_DIR_PIN 65 #endif #endif diff --git a/Marlin/src/pins/sam/pins_RAMPS4DUE.h b/Marlin/src/pins/sam/pins_RAMPS4DUE.h index 6d9d06a175..408242e065 100644 --- a/Marlin/src/pins/sam/pins_RAMPS4DUE.h +++ b/Marlin/src/pins/sam/pins_RAMPS4DUE.h @@ -45,8 +45,8 @@ // // Temperature Sensors // -#define TEMP_0_PIN 9 // Analog Input -#define TEMP_1_PIN -1 // Analog Input -#define TEMP_BED_PIN 10 // Analog Input +#define TEMP_0_PIN 9 // Analog Input +#define TEMP_1_PIN -1 // Analog Input +#define TEMP_BED_PIN 10 // Analog Input #include "../ramps/pins_RAMPS.h" diff --git a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h index 4974acc858..9c17be136b 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h +++ b/Marlin/src/pins/sam/pins_RAMPS_FD_V1.h @@ -168,9 +168,11 @@ // ramps-fd lcd adaptor #define BEEPER_PIN EXP1_01_PIN - #define BTN_EN1 EXP2_05_PIN - #define BTN_EN2 EXP2_03_PIN + #define BTN_ENC EXP1_02_PIN + #define BTN_EN2 EXP2_03_PIN + #define BTN_EN1 EXP2_05_PIN + #define SD_DETECT_PIN EXP2_07_PIN #if IS_NEWPANEL @@ -258,7 +260,7 @@ // M3/M4/M5 - Spindle/Laser Control // #if HOTENDS < 3 && HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) - #define SPINDLE_LASER_ENA_PIN 45 // Use E2 ENA #define SPINDLE_LASER_PWM_PIN 12 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 45 // Use E2 ENA #define SPINDLE_DIR_PIN 47 // Use E2 DIR #endif diff --git a/Marlin/src/pins/sam/pins_RAMPS_FD_V2.h b/Marlin/src/pins/sam/pins_RAMPS_FD_V2.h index 55a42b2a47..57c7732de8 100644 --- a/Marlin/src/pins/sam/pins_RAMPS_FD_V2.h +++ b/Marlin/src/pins/sam/pins_RAMPS_FD_V2.h @@ -31,7 +31,7 @@ #define BOARD_INFO_NAME "RAMPS-FD v2" #ifndef E0_CS_PIN - #define E0_CS_PIN 69 // moved from A13 to A15 on v2.2, if not earlier + #define E0_CS_PIN 69 // moved from A13 to A15 on v2.2, if not earlier #endif #include "pins_RAMPS_FD_V1.h" @@ -44,9 +44,9 @@ #define MARLIN_EEPROM_SIZE 0x10000 // 64K in a 24C512 #ifndef PS_ON_PIN - #define PS_ON_PIN 12 + #define PS_ON_PIN 12 #endif #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 5 // Analog Input on AUX2 + #define FILWIDTH_PIN 5 // Analog Input on AUX2 #endif diff --git a/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h b/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h index 1a3e3196a2..6f41bd6848 100644 --- a/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h +++ b/Marlin/src/pins/samd/pins_BRICOLEMON_LITE_V1_0.h @@ -130,25 +130,25 @@ * 5B | . . | 5V * ------ * - *- Special mapping of EXP1 to EXP3 to work with Ender displays. + *- Special mapping of EXP1 to work with Ender displays. * - * Enable CR10_STOCKDISPLAY in Configuration.h and connect EXP1 to the display EXP3 with this mapping. * ------ - * VCC | 1 2 | GND - * LCDDE | 3 4 | LCDRS - * LCDD4 | 5 6 BTN_EN2 - * RESET | 7 8 | BTN_EN1 - * BTN_ENCODER | 9 10 | BEEPER + * BEEPER | 1 2 | ENC + * EN1 | 3 4 | RESET + * EN2 5 6 | LCD_D4 + * LCD_RS | 7 8 | LCD_EN + * GND | 9 10 | 5V * ------ + * EXP1 * *- Digital pinout reference of the Bricolemon for advanced users/configurations. * * ------ ------ - * VCC | 1 2 | GND D49 | 1 2 | GND - * D39 | 3 4 | D38 RST | 3 4 | D44 - * D37 | 5 6 D36 D51 | 5 6 D42 - * D34 | 7 8 | D35 D53 | 7 8 | D43 - * D40 | 9 10 | D41 D52 | 9 10 | D50 + * D41 | 1 2 | D40 D50 | 1 2 | D52 + * D35 | 3 4 | D34 D43 | 3 4 | D53 + * D36 5 6 | D37 D42 5 6 | D51 + * D38 | 7 8 | D39 D44 | 7 8 | RST + * GND | 9 10 | VCC GND | 9 10 | D49 * ------ ------ * EXP1 EXP2 * @@ -284,7 +284,6 @@ //#define DOGLCD_SCK 23 //#define DOGLCD_A0 LCD_PINS_DC - #else // Definitions for any standard Display #define LCD_PINS_RS EXP1_04_PIN diff --git a/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h b/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h index bed9776cdd..699f10ed48 100644 --- a/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h +++ b/Marlin/src/pins/samd/pins_BRICOLEMON_V1_0.h @@ -182,25 +182,25 @@ * 5B | . . | 5V * ------ * - *- Special mapping of EXP1 to EXP3 to work with Ender displays. + *- Special mapping of EXP1 to work with Ender displays. * - * Enable CR10_STOCKDISPLAY in Configuration.h and connect EXP1 to the display EXP3 with this mapping. * ------ - * VCC | 1 2 | GND - * LCDDE | 3 4 | LCDRS - * LCDD4 | 5 6 BTN_EN2 - * RESET | 7 8 | BTN_EN1 - * BTN_ENCODER | 9 10 | BEEPER + * BEEPER | 1 2 | ENC + * EN1 | 3 4 | RESET + * EN2 5 6 | LCD_D4 + * LCD_RS | 7 8 | LCD_EN + * GND | 9 10 | 5V * ------ + * EXP1 * *- Digital pinout reference of the Bricolemon for advanced users/configurations. * * ------ ------ - * VCC | 1 2 | GND D49 | 1 2 | GND - * D39 | 3 4 | D38 RST | 3 4 | D44 - * D37 | 5 6 D36 D51 | 5 6 D42 - * D34 | 7 8 | D35 D53 | 7 8 | D43 - * D40 | 9 10 | D41 D52 | 9 10 | D50 + * D41 | 1 2 | D40 D50 | 1 2 | D52 + * D35 | 3 4 | D34 D43 | 3 4 | D53 + * D36 5 6 | D37 D42 5 6 | D51 + * D38 | 7 8 | D39 D44 | 7 8 | RST + * GND | 9 10 | VCC GND | 9 10 | D49 * ------ ------ * EXP1 EXP2 * diff --git a/Marlin/src/pins/samd/pins_MINITRONICS20.h b/Marlin/src/pins/samd/pins_MINITRONICS20.h index 3311d77693..2a450698d1 100644 --- a/Marlin/src/pins/samd/pins_MINITRONICS20.h +++ b/Marlin/src/pins/samd/pins_MINITRONICS20.h @@ -60,8 +60,9 @@ #define Z_STOP_PIN 4 /** - * NOTE: Useful if extra TMC2209 are to be used as independent axes. - * We need to configure the new digital PIN, for this we could configure on the board the extra pin of this stepper, for example as a MIN_PIN/MAX_PIN. This pin is the D14. + * NOTE: For extra TMC2209 used as independent axes a new digital PIN is needed. + * We can configure on the board the extra pin of this stepper, + * e.g., as a MIN_PIN/MAX_PIN. This pin is D14. */ //#define Z2_STOP_PIN 14 //#define X2_STOP_PIN 14 @@ -105,7 +106,7 @@ // This board have the option to use an extra TMC2209 stepper, one of the use could be as a second extruder. #if EXTRUDERS < 2 - // TODO: Corregir aquí que cuando tenemos dos extrusores o lo que sea, utiliza los endstop que le sobran, osea los max, no hay Z2_endstop + // TODO: Correct here that when we have two extruders (or whatever), use the extra endstops. i.e., The max, there is no Z2_endstop. #if NUM_Z_STEPPERS > 1 #define Z2_STOP_PIN 14 #endif @@ -117,8 +118,8 @@ #undef Z3_DRIVER_TYPE #undef Z4_DRIVER_TYPE - // Si tenemos más de un extrusor lo que hacemos es definir el nuevo extrusor así como sus pines - // Acordarse de definir el #define TEMP_SENSOR_1, ya que este contiene el tipo de sonda del extrusor E1 + // For more than one extruder define the new extruder and its pins. + // Remember to #define TEMP_SENSOR_1, since this contains the E1 sensor type. #define FIL_RUNOUT2_PIN 14 @@ -166,13 +167,9 @@ #define EXP3_08_PIN EXP1_08_PIN #endif -/************************************/ -/***** Configurations Section ******/ -/************************************/ - /** - * This sections starts with the pins_RAMPS_144.h as example, after if you need any new - * display, you could use normal duponts and connect it with with the scheme showed before. + * This section is based on pins_RAMPS_144.h. To use a new display, you + * could use normal duponts and connect with the scheme shown before. * Tested: * - Ender-3 Old display (Character LCD) * - Ender-3 New Serial DWING Display @@ -212,9 +209,9 @@ #if ENABLED(CR10_STOCKDISPLAY) // TO TEST - //#define LCD_PINS_RS EXP3_04_PIN - //#define LCD_PINS_EN EXP3_03_PIN - //#define LCD_PINS_D4 EXP3_05_PIN + //#define LCD_PINS_RS EXP3_04_PIN + //#define LCD_PINS_EN EXP3_03_PIN + //#define LCD_PINS_D4 EXP3_05_PIN #if !IS_NEWPANEL // TO TEST @@ -278,7 +275,7 @@ #if IS_RRD_SC - //#define BEEPER_PIN EXP1_01_PIN + //#define BEEPER_PIN EXP1_01_PIN #if ENABLED(CR10_STOCKDISPLAY) // TO TEST @@ -297,7 +294,7 @@ #ifndef SD_DETECT_PIN #define SD_DETECT_PIN EXP2_07_PIN #endif - //#define KILL_PIN EXP2_10_PIN + //#define KILL_PIN EXP2_10_PIN #if ENABLED(BQ_LCD_SMART_CONTROLLER) //#define LCD_BACKLIGHT_PIN EXP1_08_PIN // TO TEST @@ -427,7 +424,7 @@ // TO TEST //#define BEEPER_PIN EXP2_05_PIN // not connected to a pin - //#define LCD_BACKLIGHT_PIN 57 // backlight LED on A11/D? (Mega/Due:65 - AGCM4:57) + //#define LCD_BACKLIGHT_PIN 57 // Backlight LED on A11/D? (Mega/Due:65 - AGCM4:57) //#define DOGLCD_A0 EXP2_07_PIN //#define DOGLCD_CS 58 // Mega/Due:66 - AGCM4:58 @@ -502,8 +499,8 @@ #if HAS_TMC_UART /** - * Address for the UART Configuration of the TMC2209. Override in Configuration files. - * To test TMC2209 Steppers enable TMC_DEBUG in Configuration_adv.h and test the M122 command with voltage on the steppers. + * TMC2209 UART Address. Override in Configuration files. + * To test TMC2209 Steppers enable TMC_DEBUG and test M122 with voltage on the steppers. */ #ifndef X_SLAVE_ADDRESS #define X_SLAVE_ADDRESS 0b00 @@ -523,8 +520,8 @@ /** * TMC2208/TMC2209 stepper drivers - * It seems to work perfectly fine on Software Serial, if an advanced user wants to test, you could use the SAMD51 Serial1 and Serial 2. Be careful with the Sercom configurations. - * Steppers 1,2,3,4 (X,Y,Z,E0) are on the Serial1, Sercom (RX = 0, TX = 1), extra stepper 5 (E1 or any axis you want) is on Serial2, Sercom (RX = 17, TX = 16) + * Seems to work fine with Software Serial. If you want to test, use SAMD51 Serial1 and Serial2. Be careful with the Sercom configurations. + * Steppers 1,2,3,4 (X,Y,Z,E0) are on Serial1, Sercom (RX=0, TX=1), extra stepper 5 (E1 or any axis you want) is on Serial2, Sercom (RX=17, TX=16) */ //#define X_HARDWARE_SERIAL Serial1 diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index 453a3578c3..8c5884b6a1 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -155,8 +155,8 @@ // #if HAS_CUTTER && !defined(SPINDLE_LASER_ENA_PIN) #if !NUM_SERVOS // Use servo connector if possible - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! #define SPINDLE_DIR_PIN 5 #else #error "No auto-assignable Spindle/Laser pins available." diff --git a/Marlin/src/pins/sanguino/pins_ANET_10.h b/Marlin/src/pins/sanguino/pins_ANET_10.h index 29b1a9fee4..b80031186f 100644 --- a/Marlin/src/pins/sanguino/pins_ANET_10.h +++ b/Marlin/src/pins/sanguino/pins_ANET_10.h @@ -233,11 +233,11 @@ * published by oderwat on Thingiverse at https://www.thingiverse.com/thing:2103748. * * Using that adapter requires changing the pin definition as follows: - * #define SERVO0_PIN 27 // free for BLTouch/3D-Touch - * #define BEEPER_PIN 28 - * #define LCD_PINS_RS 30 - * #define LCD_PINS_EN 29 - * #define LCD_PINS_D4 17 + * #define SERVO0_PIN 27 // free for BLTouch/3D-Touch + * #define BEEPER_PIN 28 + * #define LCD_PINS_RS 30 + * #define LCD_PINS_EN 29 + * #define LCD_PINS_D4 17 * * The BLTouch pin becomes LCD:3 */ diff --git a/Marlin/src/pins/sanguino/pins_AZTEEG_X1.h b/Marlin/src/pins/sanguino/pins_AZTEEG_X1.h index 5767bc993b..1cbafab432 100644 --- a/Marlin/src/pins/sanguino/pins_AZTEEG_X1.h +++ b/Marlin/src/pins/sanguino/pins_AZTEEG_X1.h @@ -29,6 +29,6 @@ #define BOARD_INFO_NAME "Azteeg X1" -#define FAN0_PIN 4 +#define FAN0_PIN 4 #include "pins_SANGUINOLOLU_12.h" // ... SANGUINOLOLU_11 diff --git a/Marlin/src/pins/sanguino/pins_GEN6_DELUXE.h b/Marlin/src/pins/sanguino/pins_GEN6_DELUXE.h index 9c63570620..476375203c 100644 --- a/Marlin/src/pins/sanguino/pins_GEN6_DELUXE.h +++ b/Marlin/src/pins/sanguino/pins_GEN6_DELUXE.h @@ -48,7 +48,6 @@ * Once installed select the SANGUINO board and then select the CPU. */ - #define BOARD_INFO_NAME "Gen6 Deluxe" #include "pins_GEN6.h" diff --git a/Marlin/src/pins/sanguino/pins_GEN7_12.h b/Marlin/src/pins/sanguino/pins_GEN7_12.h index f6356d7ef7..0bf65c37cd 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_12.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_12.h @@ -117,7 +117,7 @@ #define HEATER_0_PIN 4 #define HEATER_BED_PIN 3 -#if !defined(FAN0_PIN) && GEN7_VERSION < 13 // Gen7 v1.3 removed the fan pin +#if !defined(FAN0_PIN) && GEN7_VERSION < 13 // Gen7 v1.3 removed the fan pin #define FAN0_PIN 31 #endif diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h index 6e8a066eef..05c3022994 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h @@ -163,7 +163,7 @@ #define KILL_PIN 10 #define BEEPER_PIN 27 - #elif IS_U8GLIB_ST7920 // SPI GLCD 12864 ST7920 ( like [www.digole.com] ) For Melzi V2.0 + #elif IS_U8GLIB_ST7920 // SPI GLCD 12864 ST7920 ( like [www.digole.com] ) For Melzi V2.0 #if IS_MELZI #define LCD_PINS_RS 30 // CS chip select /SS chip slave select @@ -173,7 +173,7 @@ // Marlin so this can be used for BEEPER_PIN. You can use this pin // with M42 instead of BEEPER_PIN. #define BEEPER_PIN 27 - #else // Sanguinololu >=1.3 + #else // Sanguinololu >=1.3 #define LCD_PINS_RS 4 #define LCD_PINS_EN 17 #define LCD_PINS_D4 30 @@ -197,7 +197,7 @@ #define BEEPER_PIN 27 #define DOGLCD_CS 28 - #else // !MAKRPANEL + #else // !MAKRPANEL #define DOGLCD_CS 29 @@ -250,7 +250,7 @@ #define BTN_ENC 30 #endif - #else // !LCD_FOR_MELZI && !ZONESTAR_LCD && !LCD_I2C_PANELOLU2 + #else // !LCD_FOR_MELZI && !ZONESTAR_LCD && !LCD_I2C_PANELOLU2 #define BTN_ENC 16 #ifndef LCD_SDSS @@ -272,8 +272,8 @@ #if HAS_CUTTER #if !MB(AZTEEG_X1) && ENABLED(SANGUINOLOLU_V_1_2) && !ALL(HAS_WIRED_LCD, IS_NEWPANEL) // try to use IO Header - #define SPINDLE_LASER_ENA_PIN 10 // Pullup or pulldown! #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN 10 // Pullup or pulldown! #define SPINDLE_DIR_PIN 11 #elif !MB(MELZI) // use X stepper motor socket diff --git a/Marlin/src/pins/stm32f1/pins_BEAST.h b/Marlin/src/pins/stm32f1/pins_BEAST.h index b136ca52cd..cf64ff1c6a 100644 --- a/Marlin/src/pins/stm32f1/pins_BEAST.h +++ b/Marlin/src/pins/stm32f1/pins_BEAST.h @@ -24,7 +24,7 @@ #include "env_validate.h" /** - * 21017 Victor Perez Marlin for stm32f1 test + * 2017 Victor Perez Marlin for stm32f1 test */ #define BOARD_INFO_NAME "Beast STM32" diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h index cdbbbdafa5..42c950d09f 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h @@ -114,15 +114,15 @@ #define USB_CONNECT_INVERTING false /** - * SKR Mini E3 V1.0, V1.2 - * ------ - * (BEEPER) PB5 | 1 2 | PB6 (BTN_ENC) - * (BTN_EN1) PA9 | 3 4 | RESET - * (BTN_EN2) PA10 5 6 | PB9 (LCD_D4) - * (LCD_RS) PB8 | 7 8 | PB7 (LCD_EN) - * GND | 9 10 | 5V - * ------ - * EXP1 + * SKR Mini E3 V1.0, V1.2 SKR Mini E3 V2.0 + * ------ ------ + * (BEEPER) PB5 | 1 2 | PB6 (BTN_ENC) (BEEPER) PB5 | 1 2 | PA15 (BTN_ENC) + * (BTN_EN1) PA9 | 3 4 | RESET (BTN_EN1) PA9 | 3 4 | RESET + * (BTN_EN2) PA10 5 6 | PB9 (LCD_D4) (BTN_EN2) PA10 5 6 | PB9 (LCD_D4) + * (LCD_RS) PB8 | 7 8 | PB7 (LCD_EN) (LCD_RS) PB8 | 7 8 | PB15 (LCD_EN) + * GND | 9 10 | 5V GND | 9 10 | 5V + * ------ ------ + * EXP1 EXP1 */ #ifndef EXP1_02_PIN #define EXP1_02_PIN PB6 @@ -242,15 +242,15 @@ /** * TFTGLCD_PANEL_SPI display pinout * - * Board Display - * ------ ------ - * (SD_DET) PB5 | 1 2 | PB6 (BEEPER) 5V |10 9 | GND - * (MOD_RESET) PA9 | 3 4 | RESET -- | 8 7 | (SD_DET) - * (SD_CS) PA10 5 6 | PB9 (MOSI) | 6 5 | -- - * (LCD_CS) PB8 | 7 8 | PB7 (SD_CS) | 4 3 | (LCD_CS) - * GND | 9 10 | 5V (SCK) | 2 1 | (MISO) - * ------ ------ - * EXP1 EXP1 + * Board Display + * ------ ------ + * (SD_DET) PB5 | 1 2 | PB6 or PA15 (BEEPER) 5V |10 9 | GND + * (MOD_RESET) PA9 | 3 4 | RESET -- | 8 7 | (SD_DET) + * (SD_CS) PA10 5 6 | PB9 (MOSI) | 6 5 | -- + * (LCD_CS) PB8 | 7 8 | PB7 or PB15 (SD_CS) | 4 3 | (LCD_CS) + * GND | 9 10 | 5V (SCK) | 2 1 | (MISO) + * ------ ------ + * EXP1 EXP1 * * Needs custom cable: * @@ -281,24 +281,24 @@ /** * FYSETC_MINI_12864_2_1 / MKS_MINI_12864_V3 / BTT_MINI_12864 display pinout * - * Board Display - * ------ ------ - * PB5 | 1 2 | PA15 (BEEP) |10 9 | BTN_ENC - * PA9 | 3 4 | RESET LCD_CS | 8 7 | LCD A0 - * PA10 | 5 6 | PB9 LCD_RST | 6 5 | RED - * PB8 | 7 8 | PB15 (GREEN) | 4 3 | (BLUE) - * GND | 9 10 | 5V GND | 2 1 | 5V - * ------ ------ - * EXP1 EXP1 + * Board Display + * ------ ------ + * PB5 | 1 2 | PB6 or PA15 (BEEP) |10 9 | BTN_ENC + * PA9 | 3 4 | RESET LCD_CS | 8 7 | LCD A0 + * PA10 | 5 6 | PB9 LCD_RST | 6 5 | RED + * PB8 | 7 8 | PB7 or PB15 (GREEN) | 4 3 | (BLUE) + * GND | 9 10 | 5V GND | 2 1 | 5V + * ------ ------ + * EXP1 EXP1 * - * --- ------ - * RST | 1 | (MISO) |10 9 | SCK - * (RX2) PA3 | 2 | BTN_EN1 | 8 7 | (SS) - * (TX2) PA2 | 3 | BTN_EN2 | 6 5 | MOSI - * GND | 4 | (CD) | 4 3 | (RST) - * 5V | 5 | (GND) | 2 1 | (KILL) - * --- ------ - * TFT EXP2 + * --- ------ + * RST | 1 | (MISO) |10 9 | SCK + * (RX2) PA3 | 2 | BTN_EN1 | 8 7 | (SS) + * (TX2) PA2 | 3 | BTN_EN2 | 6 5 | MOSI + * GND | 4 | (CD) | 4 3 | (RST) + * 5V | 5 | (GND) | 2 1 | (KILL) + * --- ------ + * TFT EXP2 * * Needs custom cable: * @@ -351,15 +351,15 @@ /** * FYSETC TFT TFT81050 display pinout * - * Board Display - * ------ ------ - * (SD_DET) PB5 | 1 2 | PB6 (BEEPER) 5V |10 9 | GND - * (MOD_RESET) PA9 | 3 4 | RESET (RESET) | 8 7 | (SD_DET) - * (SD_CS) PA10 5 6 | PB9 (MOSI) | 6 5 | (LCD_CS) - * (LCD_CS) PB8 | 7 8 | PB7 (SD_CS) | 4 3 | (MOD_RESET) - * GND | 9 10 | 5V (SCK) | 2 1 | (MISO) - * ------ ------ - * EXP1 EXP1 + * Board Display + * ------ ------ + * (SD_DET) PB5 | 1 2 | PB6 or PA15 (BEEPER) 5V |10 9 | GND + * (MOD_RESET) PA9 | 3 4 | RESET (RESET) | 8 7 | (SD_DET) + * (SD_CS) PA10 5 6 | PB9 (MOSI) | 6 5 | (LCD_CS) + * (LCD_CS) PB8 | 7 8 | PB7 or PB15 (SD_CS) | 4 3 | (MOD_RESET) + * GND | 9 10 | 5V (SCK) | 2 1 | (MISO) + * ------ ------ + * EXP1 EXP1 * * Needs custom cable: * diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index fb890a14cf..c46e87662e 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -81,17 +81,17 @@ #endif #if HAS_TMC_UART // Shared with EXP1 - #define X_SERIAL_TX_PIN PC10 - #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN + #define X_SERIAL_TX_PIN PC10 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN PC11 - #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN + #define Y_SERIAL_TX_PIN PC11 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN PC12 - #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN + #define Z_SERIAL_TX_PIN PC12 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN PC14 - #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN + #define E0_SERIAL_TX_PIN PC14 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 @@ -215,7 +215,7 @@ #define FORCE_SOFT_SPI // SPI MODE3 - #define LED_PIN EXP1_06_PIN // red pwm + #define LED_PIN EXP1_06_PIN // red pwm //#define LED_PIN EXP1_07_PIN // green //#define LED_PIN EXP1_08_PIN // blue @@ -233,7 +233,7 @@ // #define NEOPIXEL_PIN EXP1_06_PIN //#endif - #else // !FYSETC_MINI_12864 + #else // !FYSETC_MINI_12864 #define LCD_PINS_D4 EXP1_05_PIN #if IS_ULTIPANEL @@ -271,7 +271,7 @@ #endif #if SD_CONNECTION_IS(LCD) - #define SPI_DEVICE 3 + #define SPI_DEVICE 3 // Maple #define SD_DETECT_PIN EXP2_07_PIN #define SD_SCK_PIN EXP2_02_PIN #define SD_MISO_PIN EXP2_01_PIN @@ -287,4 +287,4 @@ #define ONBOARD_SPI_DEVICE 1 // SPI1 #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card -#define SDSS SD_SS_PIN +#define SDSS SD_SS_PIN diff --git a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h index 9f6a8c4107..930b7cae6a 100644 --- a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h +++ b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h @@ -134,7 +134,7 @@ #define EXP1_01_PIN PB5 #define EXP1_02_PIN PB6 #define EXP1_03_PIN PA2 -#define EXP1_04_PIN -1 // RESET +#define EXP1_04_PIN -1 // RESET #define EXP1_05_PIN PA3 #define EXP1_06_PIN PB8 #define EXP1_07_PIN PB7 diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h index 02daab3e63..18c8e22dff 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h @@ -39,7 +39,7 @@ #include "pins_CHITU3D_common.h" -/* +/** * Circuit diagram https://github.com/MarlinFirmware/Marlin/files/3401484/x5sa-main_board-2.pdf * * Details on the 30 pin ribbon pins. From: https://3dtoday.ru/blogs/artem-sr/tronxy-x5sa-pro-ustanovka-bfp-touch-na-board-chitu3d-v6-cxy-v6-191017 diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h index 9f8de25ff1..dcc5a5ac1c 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_common.h @@ -113,7 +113,9 @@ #define FIL_RUNOUT_PIN PA15 // MT_DET #endif -// SPI Flash +// +// SPI Flash (SPI 2) +// #define SPI_FLASH #if ENABLED(SPI_FLASH) #define SPI_FLASH_SIZE 0x200000 // 2MB @@ -162,7 +164,7 @@ // SPI1(PA7)=LCD & SPI3(PB5)=STUFF, are not available // so SPI2 is required. -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple #define SD_SCK_PIN PB13 #define SD_MISO_PIN PB14 #define SD_MOSI_PIN PB15 diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h index 7e066dccb2..d42ee738ee 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V24S1_301.h @@ -85,8 +85,8 @@ //#define HEATER_0_PIN -1 //#define HEATER_BED_PIN -1 #define FAN0_PIN -1 - #define SPINDLE_LASER_ENA_PIN PC0 // FET 1 #define SPINDLE_LASER_PWM_PIN PC0 // Bed FET + #define SPINDLE_LASER_ENA_PIN PC0 // FET 1 #define SPINDLE_DIR_PIN PC0 // FET 4 #define LASER_SOFT_PWM_PIN PC0 #endif diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V25S1.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V25S1.h index b848698d12..cd232dcfbf 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V25S1.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V25S1.h @@ -49,11 +49,11 @@ #endif #if ENABLED(IIC_BL24CXX_EEPROM) - #define IIC_EEPROM_SDA PA11 - #define IIC_EEPROM_SCL PA12 - #define MARLIN_EEPROM_SIZE 0x800 // 2K (24C16) + #define IIC_EEPROM_SDA PA11 + #define IIC_EEPROM_SCL PA12 + #define MARLIN_EEPROM_SIZE 0x800 // 2K (24C16) #elif ANY(SDCARD_EEPROM_EMULATION, FLASH_EEPROM_EMULATION) - #define MARLIN_EEPROM_SIZE 0x800 // 2K + #define MARLIN_EEPROM_SIZE 0x800 // 2K #endif // diff --git a/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h b/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h index 7bdc76833c..5a4c4caa8d 100644 --- a/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_ERYONE_ERY32_MINI.h @@ -148,16 +148,17 @@ #define E0_SLAVE_ADDRESS 0 #endif #endif + // // Temperature Sensors // -#define TEMP_BED_PIN PC2 //TB -#define TEMP_0_PIN PC1 //TH1 -//#define TEMP_1_PIN PC3 //TH2 #define TEMP_BOARD_PIN PC3 #ifndef TEMP_SENSOR_BOARD #define TEMP_SENSOR_BOARD 13 #endif +#define TEMP_BED_PIN PC2 // TB +#define TEMP_0_PIN PC1 // TH1 +//#define TEMP_1_PIN PC3 // TH2 #define FIL_RUNOUT_PIN PA10 // MT_DET // diff --git a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h index c02498c6cb..6572a84b04 100644 --- a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h +++ b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h @@ -60,22 +60,26 @@ // // SPI -// Note: FLSun Hispeed (clone MKS_Robin_miniV2) board is using SPI2 interface. +// +#define SPI_DEVICE 2 // Maple + +// +// SD Card SPI // #define SD_SCK_PIN PB13 // SPI2 #define SD_MISO_PIN PB14 // SPI2 #define SD_MOSI_PIN PB15 // SPI2 -#define SPI_DEVICE 2 +// // SPI Flash +// #define SPI_FLASH #if ENABLED(SPI_FLASH) - // SPI 2 - #define SPI_FLASH_CS_PIN PB12 // SPI2_NSS / Flash chip-select - #define SPI_FLASH_MOSI_PIN PB15 - #define SPI_FLASH_MISO_PIN PB14 - #define SPI_FLASH_SCK_PIN PB13 #define SPI_FLASH_SIZE 0x1000000 // 16MB + #define SPI_FLASH_CS_PIN PB12 // SPI2_NSS / Flash chip-select + #define SPI_FLASH_SCK_PIN PB13 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_MOSI_PIN PB15 #endif // @@ -304,7 +308,7 @@ #define TFT_CS_PIN FSMC_CS_PIN #define TFT_RS_PIN FSMC_RS_PIN - #ifdef TFT_CLASSIC_UI + #if ENABLED(TFT_CLASSIC_UI) #define TFT_MARLINBG_COLOR 0x3186 // Grey #define TFT_MARLINUI_COLOR 0xC7B6 // Green #define TFT_BTARROWS_COLOR 0xDEE6 // Yellow diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h index 11074ef832..1dffc97282 100644 --- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h @@ -131,30 +131,30 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_01_PIN PC14 -#define EXP1_02_PIN PC13 -#define EXP1_03_PIN PB9 -#define EXP1_04_PIN PB8 -#define EXP1_05_PIN PB7 -#define EXP1_06_PIN PB6 -#define EXP1_07_PIN PB5 -#define EXP1_08_PIN PB4 +#define EXP1_01_PIN PC14 +#define EXP1_02_PIN PC13 +#define EXP1_03_PIN PB9 +#define EXP1_04_PIN PB8 +#define EXP1_05_PIN PB7 +#define EXP1_06_PIN PB6 +#define EXP1_07_PIN PB5 +#define EXP1_08_PIN PB4 -#define EXP2_01_PIN PB14 -#define EXP2_02_PIN PB13 -#define EXP2_03_PIN PB3 -#define EXP2_04_PIN PB12 -#define EXP2_05_PIN PD2 -#define EXP2_06_PIN PB15 -#define EXP2_07_PIN PB11 -#define EXP2_08_PIN -1 // RESET +#define EXP2_01_PIN PB14 +#define EXP2_02_PIN PB13 +#define EXP2_03_PIN PB3 +#define EXP2_04_PIN PB12 +#define EXP2_05_PIN PD2 +#define EXP2_06_PIN PB15 +#define EXP2_07_PIN PB11 +#define EXP2_08_PIN -1 // RESET // // LCD / Controller // #if HAS_WIRED_LCD - #define SPI_DEVICE 2 + #define SPI_DEVICE 2 // Maple #define SD_SS_PIN EXP2_04_PIN #define SD_SCK_PIN EXP2_02_PIN #define SD_MISO_PIN EXP2_01_PIN diff --git a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h index bd39632cc5..a1ebd86e86 100644 --- a/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h +++ b/Marlin/src/pins/stm32f1/pins_LONGER3D_LK.h @@ -35,18 +35,18 @@ #define BOARD_NO_NATIVE_USB -//#define DISABLE_DEBUG // We still want to debug with STLINK... -#define DISABLE_JTAG // We free the jtag pins (PA15) but keep STLINK - // Release PB4 (STEP_X_PIN) from JTAG NRST role. +//#define DISABLE_DEBUG // Allow debug with STLINK... +#define DISABLE_JTAG // We free the JTAG pins (PA15) but keep STLINK + // Release PB4 (STEP_X_PIN) from JTAG NRST role. // // Limit Switches // -#define X_MIN_PIN PC1 // pin 16 -#define X_MAX_PIN PC0 // pin 15 (Filament sensor on Alfawise setup) -#define Y_MIN_PIN PC15 // pin 9 -#define Y_MAX_PIN PC14 // pin 8 (Unused in stock Alfawise setup) -#define Z_MIN_PIN PE6 // pin 5 Standard Endstop or Z_Probe endstop function -#define Z_MAX_PIN PE5 // pin 4 (Unused in stock Alfawise setup) +#define X_MIN_PIN PC1 +#define X_MAX_PIN PC0 // (Filament sensor on Alfawise setup) +#define Y_MIN_PIN PC15 +#define Y_MAX_PIN PC14 // (Unused in stock Alfawise setup) +#define Z_MIN_PIN PE6 // Standard Endstop or Z_Probe endstop function +#define Z_MAX_PIN PE5 // (Unused in stock Alfawise setup) // May be used for BLTouch Servo function on older variants (<= V08) #define ONBOARD_ENDSTOPPULLUPS @@ -60,35 +60,35 @@ // // Steppers // -#define X_ENABLE_PIN PB5 // pin 91 -#define X_STEP_PIN PB4 // pin 90 -#define X_DIR_PIN PB3 // pin 89 +#define X_ENABLE_PIN PB5 +#define X_STEP_PIN PB4 +#define X_DIR_PIN PB3 -#define Y_ENABLE_PIN PB8 // pin 95 -#define Y_STEP_PIN PB7 // pin 93 -#define Y_DIR_PIN PB6 // pin 92 +#define Y_ENABLE_PIN PB8 +#define Y_STEP_PIN PB7 +#define Y_DIR_PIN PB6 -#define Z_ENABLE_PIN PE1 // pin 98 -#define Z_STEP_PIN PE0 // pin 97 -#define Z_DIR_PIN PB9 // pin 96 +#define Z_ENABLE_PIN PE1 +#define Z_STEP_PIN PE0 +#define Z_DIR_PIN PB9 -#define E0_ENABLE_PIN PE4 // pin 3 -#define E0_STEP_PIN PE3 // pin 2 -#define E0_DIR_PIN PE2 // pin 1 +#define E0_ENABLE_PIN PE4 +#define E0_STEP_PIN PE3 +#define E0_DIR_PIN PE2 // // Temperature Sensors // -#define TEMP_0_PIN PA0 // pin 23 (Nozzle 100K/3950 thermistor) -#define TEMP_BED_PIN PA1 // pin 24 (Hot Bed 100K/3950 thermistor) +#define TEMP_0_PIN PA0 // (Nozzle 100K/3950 thermistor) +#define TEMP_BED_PIN PA1 // (Hot Bed 100K/3950 thermistor) // // Heaters / Fans // -#define HEATER_0_PIN PD3 // pin 84 (Nozzle Heat Mosfet) -#define HEATER_BED_PIN PA8 // pin 67 (Hot Bed Mosfet) +#define HEATER_0_PIN PD3 // (Nozzle Heat Mosfet) +#define HEATER_BED_PIN PA8 // (Hot Bed Mosfet) -#define FAN0_PIN PA15 // pin 77 (4cm Fan) +#define FAN0_PIN PA15 // (4cm Fan) #if TERN(MAPLE_STM32F1, ENABLED(FAN_SOFT_PWM), ENABLED(FAST_PWM_FAN)) && FAN_MIN_PWM < 5 // Required to avoid issues with heating or STLink #error "FAN_MIN_PWM must be 5 or higher." // Fan will not start in 1-30 range @@ -104,10 +104,10 @@ #endif #endif -//#define BEEPER_PIN PD13 // pin 60 (Servo PWM output 5V/GND on Board V0G+) made for BL-Touch sensor +//#define BEEPER_PIN PD13 // (Servo PWM output 5V/GND on Board V0G+) made for BL-Touch sensor // Can drive a PC Buzzer, if connected between PWM and 5V pins -#define LED_PIN PC2 // pin 17 +#define LED_PIN PC2 // Longer3D board mosfets are passing by default // Avoid nozzle heat and fan start before serial init @@ -136,16 +136,16 @@ // #if HAS_FSMC_TFT #define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT - #define FSMC_CS_PIN PD7 // pin 88 = FSMC_NE1 - #define FSMC_RS_PIN PD11 // pin 58 A16 Register. Only one address needed #define FSMC_DMA_DEV DMA2 #define FSMC_DMA_CHANNEL DMA_CH5 + #define FSMC_CS_PIN PD7 // FSMC_NE1 + #define FSMC_RS_PIN PD11 // A16 Register. Only one address needed #define TFT_CS_PIN FSMC_CS_PIN #define TFT_RS_PIN FSMC_RS_PIN - #define TFT_RESET_PIN PC4 // pin 33 - #define TFT_BACKLIGHT_PIN PD12 // pin 59 + #define TFT_RESET_PIN PC4 + #define TFT_BACKLIGHT_PIN PD12 #define TFT_BACKLIGHT_PWM 150 // Brightness with alt. TIM4 chan 1 (1-255) #define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h @@ -170,11 +170,11 @@ * declared below. */ #if NEED_TOUCH_PINS - #define TOUCH_CS_PIN PB12 // pin 51 SPI2_NSS - #define TOUCH_SCK_PIN PB13 // pin 52 - #define TOUCH_MOSI_PIN PB14 // pin 53 (Inverted MOSI/MISO = No HW SPI2) - #define TOUCH_MISO_PIN PB15 // pin 54 - #define TOUCH_INT_PIN PC6 // pin 63 (PenIRQ coming from ADS7843) + #define TOUCH_CS_PIN PB12 // SPI2_NSS + #define TOUCH_SCK_PIN PB13 + #define TOUCH_MISO_PIN PB15 // (Swapped MOSI/MISO = No HW SPI2) + #define TOUCH_MOSI_PIN PB14 + #define TOUCH_INT_PIN PC6 // (PenIRQ coming from ADS7843) #endif // @@ -183,25 +183,25 @@ // #if NO_EEPROM_SELECTED //#define SPI_EEPROM - //#define SPI_FLASH // need MARLIN_DEV_MODE for M993/M994 EEPROM backup tests + //#define SPI_FLASH // Use MARLIN_DEV_MODE for M993/M994 EEPROM backup tests #define FLASH_EEPROM_EMULATION #endif #if ENABLED(SPI_EEPROM) // SPI1 EEPROM Winbond W25Q64 (8MB/64Mbits) #define SPI_CHAN_EEPROM1 1 - #define SPI_EEPROM1_CS_PIN PC5 // pin 34 - #define EEPROM_SCK_PIN BOARD_SPI1_SCK_PIN // PA5 pin 30 - #define EEPROM_MISO_PIN BOARD_SPI1_MISO_PIN // PA6 pin 31 - #define EEPROM_MOSI_PIN BOARD_SPI1_MOSI_PIN // PA7 pin 32 + #define SPI_EEPROM1_CS_PIN PC5 + #define EEPROM_SCK_PIN BOARD_SPI1_SCK_PIN // PA5 + #define EEPROM_MISO_PIN BOARD_SPI1_MISO_PIN // PA6 + #define EEPROM_MOSI_PIN BOARD_SPI1_MOSI_PIN // PA7 #define EEPROM_PAGE_SIZE 0x1000U // 4K (from datasheet) - #define MARLIN_EEPROM_SIZE 16UL * (EEPROM_PAGE_SIZE) // Limit to 64K for now... + #define MARLIN_EEPROM_SIZE 16UL * (EEPROM_PAGE_SIZE) // Limit to 64K for now... #elif ENABLED(SPI_FLASH) - #define SPI_FLASH_SIZE 0x40000U // limit to 256K (M993 will reboot with 512) + #define SPI_FLASH_SIZE 0x40000U // Limit to 256K (M993 will reboot with 512) #define SPI_FLASH_CS_PIN PC5 - #define SPI_FLASH_MOSI_PIN PA7 - #define SPI_FLASH_MISO_PIN PA6 #define SPI_FLASH_SCK_PIN PA5 + #define SPI_FLASH_MISO_PIN PA6 + #define SPI_FLASH_MOSI_PIN PA7 #elif ENABLED(FLASH_EEPROM_EMULATION) // SoC Flash (framework-arduinoststm32-maple/STM32F1/libraries/EEPROM/EEPROM.h) #define EEPROM_PAGE_SIZE (0x800U) // 2K diff --git a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h index c27202ab10..bff8abddad 100644 --- a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h @@ -58,15 +58,15 @@ #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple // // Limit Switches // #define X_MIN_PIN PD6 -#define X_MAX_PIN PG15 // To double check +#define X_MAX_PIN PG15 // To double check #define Y_MIN_PIN PG9 -#define Y_MAX_PIN PG14 // To double check +#define Y_MAX_PIN PG14 // To double check #define Z_MIN_PIN PG10 #define Z_MAX_PIN PG13 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h index 25b372a889..2230cf8ad7 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h @@ -197,7 +197,7 @@ // SPI2 is shared by LCD touch driver and flash // SPI1(PA7) & SPI3(PB5) not available -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple #define SDIO_SUPPORT #define SDIO_CLOCK 4500000 @@ -276,7 +276,7 @@ #if ENABLED(SPI_FLASH) #define SPI_FLASH_SIZE 0x800000 // 8MB #define SPI_FLASH_CS_PIN PG9 - #define SPI_FLASH_MOSI_PIN PB15 - #define SPI_FLASH_MISO_PIN PB14 #define SPI_FLASH_SCK_PIN PB13 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_MOSI_PIN PB15 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 078b327b65..6111c8e7f8 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -58,9 +58,9 @@ #endif // -// Note: MKS Robin board is using SPI2 interface. +// SPI // -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple // // Servos @@ -355,7 +355,7 @@ #endif //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 - #else // !MKS_MINI_12864 + #else // !MKS_MINI_12864 #define LCD_PINS_D4 EXP1_05_PIN #if IS_ULTIPANEL @@ -381,9 +381,9 @@ #if ENABLED(SPI_FLASH) #define SPI_FLASH_SIZE 0x1000000 // 16MB #define SPI_FLASH_CS_PIN PB12 - #define SPI_FLASH_MOSI_PIN PB15 - #define SPI_FLASH_MISO_PIN PB14 #define SPI_FLASH_SCK_PIN PB13 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_MOSI_PIN PB15 #endif #ifndef BEEPER_PIN diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h index 31e034e025..9fa5ec6b31 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h @@ -34,6 +34,6 @@ #define Z_STEP_PIN PC14 #define Z_DIR_PIN PC15 -#define BTN_ENC_EN -1 +#define BTN_ENC_EN -1 #include "pins_MKS_ROBIN_E3_common.h" 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 676a23bdb2..ebf3d44a83 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -165,13 +165,13 @@ #define EXP2_05_PIN PB0 #define EXP2_06_PIN PB15 #define EXP2_07_PIN PC10 -#define EXP2_08_PIN -1 // RESET +#define EXP2_08_PIN -1 // RESET // "Ender-3 EXP1" #define EXP3_01_PIN PC1 #define EXP3_02_PIN PC3 #define EXP3_03_PIN PB11 -#define EXP3_04_PIN -1 // RESET +#define EXP3_04_PIN -1 // RESET #define EXP3_05_PIN PB0 #define EXP3_06_PIN PA6 #define EXP3_07_PIN PA5 @@ -250,7 +250,7 @@ // SD Card // #define SDCARD_CONNECTION ONBOARD -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple #define ONBOARD_SPI_DEVICE 2 #define SDSS SD_SS_PIN #define ONBOARD_SD_CS_PIN SD_SS_PIN diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h index af4e121100..10ddc76a01 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE.h @@ -121,7 +121,7 @@ #define DOGLCD_SCK PB13 #define DOGLCD_MOSI PB15 - #else // !MKS_MINI_12864 + #else // !MKS_MINI_12864 #define LCD_PINS_D4 EXP3_06_PIN #if IS_ULTIPANEL @@ -156,7 +156,7 @@ // // SPI // -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple #define SD_SCK_PIN PB13 #define SD_MISO_PIN PB14 #define SD_MOSI_PIN PB15 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h index 6835ec3b56..03be44bba6 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_LITE3.h @@ -122,7 +122,7 @@ #define TFTGLCD_CS PB11 #endif - #else // !MKS_MINI_12864 + #else // !MKS_MINI_12864 #define LCD_PINS_D4 PA6 #if IS_ULTIPANEL @@ -152,7 +152,7 @@ // // SPI // -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple #define SD_SCK_PIN PB13 #define SD_MISO_PIN PB14 #define SD_MOSI_PIN PB15 diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h index 19d71f8bd3..858b7a387b 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_MINI.h @@ -50,7 +50,7 @@ #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple // // Servos @@ -200,7 +200,7 @@ #if ENABLED(SPI_FLASH) #define SPI_FLASH_SIZE 0x1000000 // 16MB #define SPI_FLASH_CS_PIN PB12 // Flash chip-select - #define SPI_FLASH_MOSI_PIN PB15 - #define SPI_FLASH_MISO_PIN PB14 #define SPI_FLASH_SCK_PIN PB13 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_MOSI_PIN PB15 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index 25b0291b7c..55ceac4c80 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -60,9 +60,9 @@ #endif // -// Note: MKS Robin board is using SPI2 interface. +// SPI // -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple // // Servos @@ -355,7 +355,7 @@ #endif //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 - #else // !MKS_MINI_12864 + #else // !MKS_MINI_12864 #define LCD_PINS_D4 PE14 #if IS_ULTIPANEL @@ -383,9 +383,9 @@ #if ENABLED(SPI_FLASH) #define SPI_FLASH_SIZE 0x1000000 // 16MB #define SPI_FLASH_CS_PIN PB12 - #define SPI_FLASH_MOSI_PIN PB15 - #define SPI_FLASH_MISO_PIN PB14 #define SPI_FLASH_SCK_PIN PB13 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_MOSI_PIN PB15 #endif #ifndef BEEPER_PIN diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h index b68203cd41..b2a301381d 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h @@ -49,7 +49,7 @@ #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE // 2K #endif -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple // // Servos @@ -212,7 +212,7 @@ #if ENABLED(SPI_FLASH) #define SPI_FLASH_SIZE 0x1000000 // 16MB #define SPI_FLASH_CS_PIN PB12 - #define SPI_FLASH_MOSI_PIN PB15 - #define SPI_FLASH_MISO_PIN PB14 #define SPI_FLASH_SCK_PIN PB13 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_MOSI_PIN PB15 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index 501a5c9f17..82737a9ee8 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -41,9 +41,9 @@ #define DISABLE_DEBUG // -// Note: MKS Robin board is using SPI2 interface. +// SPI // -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple // // Servos @@ -169,9 +169,9 @@ #define HEATER_BED_PIN PA0 // +HOT-BED- #define FAN0_PIN PB1 // +FAN- -/** - * Note: MKS Robin Pro board is using SPI2 interface. Make sure your stm32duino library is configured accordingly - */ +// +// Note: Using SPI2 interface. Make sure stm32duino is configured accordingly +// //#define TEMP_0_CS_PIN PE5 // TC1 - CS1 //#define TEMP_0_CS_PIN PF11 // TC2 - CS2 @@ -283,7 +283,7 @@ #define DOGLCD_SCK PB13 #define DOGLCD_MOSI PB15 - #else // !MKS_MINI_12864 && !ENDER2_STOCKDISPLAY + #else // !MKS_MINI_12864 && !ENDER2_STOCKDISPLAY #define LCD_PINS_D4 PF14 #if IS_ULTIPANEL @@ -312,7 +312,7 @@ #if ENABLED(SPI_FLASH) #define SPI_FLASH_SIZE 0x1000000 // 16MB #define SPI_FLASH_CS_PIN PB12 // Flash chip-select - #define SPI_FLASH_MOSI_PIN PB15 - #define SPI_FLASH_MISO_PIN PB14 #define SPI_FLASH_SCK_PIN PB13 + #define SPI_FLASH_MISO_PIN PB14 + #define SPI_FLASH_MOSI_PIN PB15 #endif diff --git a/Marlin/src/pins/stm32f1/pins_STM32F1R.h b/Marlin/src/pins/stm32f1/pins_STM32F1R.h index a2efa632f8..9cbc69149c 100644 --- a/Marlin/src/pins/stm32f1/pins_STM32F1R.h +++ b/Marlin/src/pins/stm32f1/pins_STM32F1R.h @@ -24,7 +24,7 @@ #include "env_validate.h" /** - * 21017 Victor Perez Marlin for stm32f1 test + * 2017 Victor Perez Marlin for stm32f1 test */ #define BOARD_INFO_NAME "Misc. STM32F1R" diff --git a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h index b4cf21ee7f..e5b16460f0 100644 --- a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h @@ -24,7 +24,7 @@ #include "env_validate.h" /** - * 10 Dec 2017 Victor Perez Marlin for stm32f1 test + * 2017 Victor Perez Marlin for stm32f1 test */ #define BOARD_INFO_NAME "STM3R Mini" diff --git a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h index 410e39bccf..174458f1b0 100644 --- a/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_TRIGORILLA_PRO.h @@ -186,7 +186,7 @@ #endif // SPI1(PA7) & SPI3(PB5) not available -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 // Maple #if ENABLED(SDIO_SUPPORT) #define SD_SCK_PIN PB13 // SPI2 ok diff --git a/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h b/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h index 128d1dfd56..02ad9bb4ad 100644 --- a/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h +++ b/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h @@ -23,7 +23,7 @@ #include "env_validate.h" -#if HOTENDS > 1 || E_STEPPERS > 1 +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 #error "Artillery Ruby only supports 1 hotend / E stepper." #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index 641130fae4..b9c4cb07da 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -197,16 +197,14 @@ #endif /** - * ---------------------------------BTT002 V1.0--------------------------------- - * ------ ------ | - * (BEEPER) PE7 | 1 2 | PB1 (BTN_ENC) (MISO) PA6 | 1 2 | PA5 (SCK) | - * (LCD_EN) PE9 | 3 4 | PE8 (LCD_RS) (BTN_EN1) PC5 | 3 4 | PA4 (SD_SS) | - * (LCD_D4) PE10 5 6 | PE11 (LCD_D5) (BTN_EN2) PB0 5 6 | PA7 (MOSI) | - * (LCD_D6) PE12 | 7 8 | PE13 (LCD_D7) (SD_DET) PC4 | 7 8 | RESET | - * GND | 9 10 | 5V GND | 9 10 | PA3 | - * ------ ------ | - * EXP1 EXP2 | - * ------------------------------------------------------------------------------ + * ------ ------ + * (BEEPER) PE7 | 1 2 | PB1 (BTN_ENC) (MISO) PA6 | 1 2 | PA5 (SCK) + * (LCD_EN) PE9 | 3 4 | PE8 (LCD_RS) (BTN_EN1) PC5 | 3 4 | PA4 (SD_SS) + * (LCD_D4) PE10 5 6 | PE11 (LCD_D5) (BTN_EN2) PB0 5 6 | PA7 (MOSI) + * (LCD_D6) PE12 | 7 8 | PE13 (LCD_D7) (SD_DET) PC4 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | PA3 + * ------ ------ + * EXP1 EXP2 */ #define EXP1_01_PIN PE7 #define EXP1_02_PIN PB1 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index 9c47e72338..2832ee473b 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -304,9 +304,9 @@ //#define TEMP_0_MOSI_PIN ... // For MAX31865 #define TEMP_1_CS_PIN PH2 // M5 K-TEMP -#define TEMP_1_SCK_PIN TEMP_0_SCK_PIN -#define TEMP_1_MISO_PIN TEMP_0_MISO_PIN -//#define TEMP_1_MOSI_PIN TEMP_0_MOSI_PIN +#define TEMP_1_SCK_PIN TEMP_0_SCK_PIN +#define TEMP_1_MISO_PIN TEMP_0_MISO_PIN +//#define TEMP_1_MOSI_PIN TEMP_0_MOSI_PIN // // Heaters / Fans diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index 3f588cd15b..ce3177cd51 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -61,13 +61,6 @@ #define E2_DIAG_PIN PG14 // E2DET #define E3_DIAG_PIN PG15 // E3DET -// -// Z Probe (when not Z_MIN_PIN) -// -#ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PB7 -#endif - // // Check for additional used endstop pins // @@ -142,6 +135,13 @@ #define Z_STOP_PIN Z_DIAG_PIN // Z-STOP #endif +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PB7 +#endif + // // Filament Runout Sensor // @@ -510,7 +510,7 @@ #endif #endif -#endif // HAS_WIRED_LCD +#endif // HAS_WIRED_LCD // Alter timing for graphical display #if IS_U8GLIB_ST7920 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h index 3875371d20..64ab2dd6c9 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_MINI_E3_V3_0_1.h @@ -25,7 +25,7 @@ #include "env_validate.h" -#if HOTENDS > 1 || E_STEPPERS > 1 +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 #error "BTT SKR Mini E3 V3.0.1 supports up to 1 hotend / E stepper." #endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index 85b1b06a3b..a2f445476b 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -487,7 +487,7 @@ #define DOGLCD_A0 EXP1_06_PIN #define DOGLCD_SCK EXP1_04_PIN #define DOGLCD_MOSI EXP1_02_PIN - #define LCD_BACKLIGHT_PIN -1 + #define LCD_BACKLIGHT_PIN -1 #else 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 be2baf17aa..0ffe5f6218 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 @@ -137,10 +137,8 @@ // // Probe enable // -#if ENABLED(PROBE_ENABLE_DISABLE) - #ifndef PROBE_ENABLE_PIN - #define PROBE_ENABLE_PIN SERVO0_PIN - #endif +#if ENABLED(PROBE_ENABLE_DISABLE) && !defined(PROBE_ENABLE_PIN) + #define PROBE_ENABLE_PIN SERVO0_PIN #endif // diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h index 13881ed550..3cc8c5554e 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_CHEETAH_V20.h @@ -43,14 +43,14 @@ #define FLASH_ADDRESS_START 0x8004000 #endif -#define SERVO0_PIN PB1 // BL-TOUCH/PWM +#define SERVO0_PIN PB1 // BL-TOUCH/PWM // // Limit Switches // -#define X_STOP_PIN PB4 // X-MIN -#define Y_STOP_PIN PC8 // Y-MIN -#define Z_STOP_PIN PA0 // Z-MIN +#define X_STOP_PIN PB4 // X-MIN +#define Y_STOP_PIN PC8 // Y-MIN +#define Z_STOP_PIN PA0 // Z-MIN // // Z Probe @@ -59,7 +59,7 @@ #error "You need to set jumper to 5V for BLTouch, then comment out this line to proceed." #endif #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PB1 // BL-TOUCH/PWM repurposed + #define Z_MIN_PROBE_PIN PB1 // BL-TOUCH/PWM repurposed #endif // @@ -149,17 +149,15 @@ * GND | 9 10 | 5V GND | 9 10 | 5V * ------ ------ * EXP2 EXP1 - */ - -/** - * ------ - * 5V | 1 2 | GND - * (LCD_EN/MOSI) PB15 | 3 4 | PB12 (LCD_RS) - * (LCD_D4/SCK) PB13 5 6 | PC11 (BTN_EN2) - * (LCD_D5/MISO) PB14 | 7 8 | PC10 (BTN_EN1) - * (BTN_ENC) PC12 | 9 10 | PC9 (BEEPER) - * ------ - * EXP3 + * + * ------ + * (BEEPER) PC9 | 1 2 | PC12 (BTN_ENC) + * (BTN_EN1) PC10 | 3 4 | PB14 (LCD_D5/MISO) + * (BTN_EN2) PC11 5 6 | PB13 (LCD_D4/SCK) + * (LCD_RS) PB12 | 7 8 | PB15 (LCD_EN/MOSI) + * GND | 9 10 | 5V + * ------ + * EXP3 */ #define EXP1_01_PIN PC9 diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h index 4eb6137532..5471613679 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_K.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_K.h @@ -154,10 +154,10 @@ #ifndef EX_SERIAL_RX_PIN #define EX_SERIAL_RX_PIN EX_SERIAL_TX_PIN #endif - //#define Z2_SERIAL_RX_PIN EX_SERIAL_RX_PIN - //#define Z2_SERIAL_TX_PIN EX_SERIAL_TX_PIN - //#define E2_SERIAL_RX_PIN EX_SERIAL_RX_PIN - //#define E2_SERIAL_TX_PIN EX_SERIAL_TX_PIN + //#define Z2_SERIAL_RX_PIN EX_SERIAL_RX_PIN + //#define Z2_SERIAL_TX_PIN EX_SERIAL_TX_PIN + //#define E2_SERIAL_RX_PIN EX_SERIAL_RX_PIN + //#define E2_SERIAL_TX_PIN EX_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 #endif diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V1.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V1.h index 50fe790dc3..7d6ea8e039 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V1.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V1.h @@ -39,7 +39,7 @@ // // Misc. Functions // -#define PW_DET PC5 // Y+ +#define PW_DET PC5 // Y+ #define PW_OFF PB12 // Z+ #define MT_DET_1_PIN PW_DET #define MT_DET_2_PIN PW_OFF 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 6eec8c2b1c..f2da2d5356 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 @@ -210,8 +210,8 @@ // // Onboard SD card +// Detect pin doesn't work when ONBOARD and NO_SD_HOST_DRIVE disabled // -// detect pin doesn't work when ONBOARD and NO_SD_HOST_DRIVE disabled #if SD_CONNECTION_IS(ONBOARD) #define ENABLE_SPI3 #define SD_SS_PIN -1 @@ -342,7 +342,6 @@ // Required for MKS_MINI_12864 with this board //#define MKS_LCD12864B - //#undef SHOW_BOOTSCREEN #elif ENABLED(FYSETC_MINI_12864_2_1) #define LCD_PINS_DC EXP1_04_PIN @@ -358,7 +357,7 @@ #endif //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 - #else // !MKS_MINI_12864 + #else // !MKS_MINI_12864 #define LCD_PINS_D4 EXP1_05_PIN #if IS_ULTIPANEL diff --git a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h index 15f77f37f7..faf6fc1ef1 100644 --- a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h +++ b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h @@ -24,7 +24,7 @@ #define ALLOW_STM32DUINO #include "env_validate.h" -#if HOTENDS > 1 || E_STEPPERS > 1 +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 #error "TH3D EZBoard only supports 1 hotend / E stepper." #endif diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h index 50fa0814b9..01a2c28f15 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_E3_EZ_V1_0.h @@ -53,10 +53,8 @@ // // Probe enable // -#if ENABLED(PROBE_ENABLE_DISABLE) - #ifndef PROBE_ENABLE_PIN - #define PROBE_ENABLE_PIN SERVO0_PIN - #endif +#if ENABLED(PROBE_ENABLE_DISABLE) && !defined(PROBE_ENABLE_PIN) + #define PROBE_ENABLE_PIN SERVO0_PIN #endif // diff --git a/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h index fc8664dfe7..a516768462 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_SKR_MINI_E3_V3_0.h @@ -196,7 +196,7 @@ * CS | 3 4 | SCK (EN1) PA10 | 3 4 | -- * MOSI | 5 6 | MISO (EN2) PA9 5 6 | MOSI * 3V3 | 7 8 | GND -- | 7 8 | -- - * ------ GND | 9 10| RESET (Kill) + * ------ GND | 9 10 | RESET (Kill) * SPI ------ * EXP2 * @@ -205,7 +205,7 @@ * PA9 | 3 4 | RESET (LCD CS) PB8 | 3 4 | PD6 (LCD_A0) * PA10 5 6 | PB9 (RESET) PB9 5 6 | PA15 (DIN) * PB8 | 7 8 | PD6 -- | 7 8 | -- - * GND | 9 10| 5V GND | 9 10| 5V + * GND | 9 10 | 5V GND | 9 10 | 5V * ------ ------ * EXP1 EXP1 */ @@ -322,7 +322,7 @@ * ------ ------ * (EN2) PB5 | 1 2 | PA15(BTN_ENC) 5V |10 9 | GND * (LCD_CS) PA9 | 3 4 | RST (RESET) -- | 8 7 | -- - * (LCD_A0) PA10 5 6 | PB9 (EN1) (DIN) | 6 5 (RESET) + * (LCD_A0) PA10 5 6 | PB9 (EN1) (DIN) | 6 5 (RESET) LCD_RESET * (LCD_SCK)PB8 | 7 8 | PD6 (MOSI) (LCD_A0) | 4 3 | (LCD_CS) * GND | 9 10 | 5V (BTN_ENC) | 2 1 | -- * ------ ------ @@ -330,7 +330,7 @@ * * ------ * -- |10 9 | -- - * --- (RESET) | 8 7 | -- + * --- RESET_BUTTON (RESET) | 8 7 | -- * | 3 | (MOSI) | 6 5 (EN2) * | 2 | (DIN) -- | 4 3 | (EN1) * | 1 | (LCD_SCK)| 2 1 | -- @@ -338,6 +338,7 @@ * Neopixel EXP2 * * Needs custom cable. Connect EN2-EN2, LCD_CS-LCD_CS and so on. + * Note: The RESET line is connected to 3 pins. * * Check the index/notch position twice!!! * On BTT boards pins from IDC10 connector are numbered in unusual order. diff --git a/Marlin/src/pins/teensy2/env_validate.h b/Marlin/src/pins/teensy2/env_validate.h index 5f0ea4f3b6..8fd6fba319 100644 --- a/Marlin/src/pins/teensy2/env_validate.h +++ b/Marlin/src/pins/teensy2/env_validate.h @@ -19,10 +19,13 @@ * along with this program. If not, see . * */ -#pragma once +#ifndef ENV_VALIDATE_H +#define ENV_VALIDATE_H #if NOT_TARGET(__AVR_AT90USB1286__) && (DISABLED(ALLOW_AT90USB1286P) || NOT_TARGET(__AVR_AT90USB1286P__)) #error "Oops! Select 'Teensy++ 2.0' or 'Printrboard' in 'Tools > Board.'" #endif #undef ALLOW_AT90USB1286P + +#endif diff --git a/Marlin/src/pins/teensy2/pins_SAV_MKI.h b/Marlin/src/pins/teensy2/pins_SAV_MKI.h index 28b0aebe42..9f590cbbb4 100644 --- a/Marlin/src/pins/teensy2/pins_SAV_MKI.h +++ b/Marlin/src/pins/teensy2/pins_SAV_MKI.h @@ -172,7 +172,7 @@ #define KILL_PIN EXT_AUX_A2_IO #define HOME_PIN EXT_AUX_A4_IO -#else // Use the expansion header for spindle control +#else // Use the expansion header for spindle control // // M3/M4/M5 - Spindle/Laser Control diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index 7deebd4776..cba8510d01 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -317,6 +317,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi goto FAIL; } } + // If SD2 read OCR register to check for SDHC card if (type() == SD_CARD_TYPE_SD2) { if (cardCommand(CMD58, 0)) { @@ -327,6 +328,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi // Discard rest of ocr - contains allowed voltage range for (uint8_t i = 0; i < 3; ++i) spiRec(); } + chipDeselect(); ready = true; diff --git a/Marlin/src/sd/Sd2Card.h b/Marlin/src/sd/Sd2Card.h index 71e31ac614..49569af512 100644 --- a/Marlin/src/sd/Sd2Card.h +++ b/Marlin/src/sd/Sd2Card.h @@ -70,7 +70,7 @@ typedef enum : uint8_t { SD_CARD_ERROR_WRITE_PROGRAMMING = 0x16, // Card returned an error to a CMD13 status check after a write SD_CARD_ERROR_WRITE_TIMEOUT = 0x17, // Timeout occurred during write programming SD_CARD_ERROR_SCK_RATE = 0x18, // Incorrect rate selected - SD_CARD_ERROR_INIT_NOT_CALLED = 0x19, // Init() not called + SD_CARD_ERROR_INIT_NOT_CALLED = 0x19, // init() not called // 0x1A is unused now, it was: card returned an error for CMD59 (CRC_ON_OFF) SD_CARD_ERROR_READ_CRC = 0x1B // Invalid read CRC } sd_error_code_t; diff --git a/Marlin/src/sd/SdBaseFile.cpp b/Marlin/src/sd/SdBaseFile.cpp index 778aadd021..b87ad81429 100644 --- a/Marlin/src/sd/SdBaseFile.cpp +++ b/Marlin/src/sd/SdBaseFile.cpp @@ -322,12 +322,12 @@ void SdBaseFile::getpos(filepos_t * const pos) { * \param[in] indent Amount of space before file name. Used for recursive * list to indicate subdirectory level. */ -void SdBaseFile::ls(uint8_t flags, uint8_t indent) { +void SdBaseFile::ls(const uint8_t flags/*=0*/, const uint8_t indent/*=0*/) { rewind(); int8_t status; while ((status = lsPrintNext(flags, indent))) { if (status > 1 && (flags & LS_R)) { - uint16_t index = curPosition() / 32 - 1; + const uint16_t index = curPosition() / 32 - 1; SdBaseFile s; if (s.open(this, index, O_READ)) s.ls(flags, indent + 2); seekSet(32 * (index + 1)); @@ -1002,7 +1002,8 @@ bool SdBaseFile::openNext(SdBaseFile *dirFile, const uint8_t oflag) { bool SdBaseFile::isDirLFN(const dir_t* dir) { if (DIR_IS_LONG_NAME(dir)) { vfat_t *VFAT = (vfat_t*)dir; - // Sanity-check the VFAT entry. The first cluster is always set to zero. And the sequence number should be higher than 0 + // Sanity-check the VFAT entry. The first cluster is always set to zero. + // The sequence number should be higher than 0 and lower than maximum allowed by VFAT spec if ((VFAT->firstClusterLow == 0) && WITHIN((VFAT->sequenceNumber & 0x1F), 1, MAX_VFAT_ENTRIES)) return true; } return false; @@ -1294,7 +1295,6 @@ static void print2u(const uint8_t v) { * \param[in] fatDate The date field from a directory entry. */ - /** * %Print a directory date field. * @@ -1311,7 +1311,6 @@ void SdBaseFile::printFatDate(const uint16_t fatDate) { print2u(FAT_DAY(fatDate)); } - /** * %Print a directory time field. * @@ -1421,11 +1420,13 @@ int16_t SdBaseFile::read(void * const buf, uint16_t nbyte) { * * \param[out] dir The dir_t struct that will receive the data. * - * \return For success readDir() returns the number of bytes read. - * A value of zero will be returned if end of file is reached. - * If an error occurs, readDir() returns -1. Possible errors include - * readDir() called before a directory has been opened, this is not - * a directory file or an I/O error occurred. + * \return For success return a non-zero value (number of bytes read). + * A value of zero will be returned if end of dir is reached. + * If an error occurs, readDir() returns -1. Possible errors: + * - readDir() called on unopened dir + * - not a directory file + * - bad dir entry + * - I/O error */ int8_t SdBaseFile::readDir(dir_t * const dir, char * const longFilename) { int16_t n; @@ -1487,7 +1488,7 @@ int8_t SdBaseFile::readDir(dir_t * const dir, char * const longFilename) { longFilename[idx] = utf16_ch & 0xFF; longFilename[idx + 1] = (utf16_ch >> 8) & 0xFF; #else - // Replace all multibyte characters to '_' + // Replace multibyte character with '_' longFilename[n + i] = (utf16_ch > 0xFF) ? '_' : (utf16_ch & 0xFF); #endif } diff --git a/Marlin/src/sd/SdBaseFile.h b/Marlin/src/sd/SdBaseFile.h index 3ac23138b1..dc31e8492d 100644 --- a/Marlin/src/sd/SdBaseFile.h +++ b/Marlin/src/sd/SdBaseFile.h @@ -67,7 +67,6 @@ uint8_t const LS_DATE = 1, // ls() flag to print modify date LS_SIZE = 2, // ls() flag to print file size LS_R = 4; // ls() flag for recursive list of subdirectories - // flags for timestamp uint8_t const T_ACCESS = 1, // Set the file's last access date T_CREATE = 2, // Set the file's creation date and time @@ -283,7 +282,7 @@ class SdBaseFile { bool isRoot() const { return type_ == FAT_FILE_TYPE_ROOT_FIXED || type_ == FAT_FILE_TYPE_ROOT32; } bool getDosName(char * const name); - void ls(uint8_t flags=0, uint8_t indent=0); + void ls(const uint8_t flags=0, const uint8_t indent=0); bool mkdir(SdBaseFile *parent, const char *path, const bool pFlag=true); bool open(SdBaseFile * const dirFile, uint16_t index, const uint8_t oflag); diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 139cf7076e..43f0996eaa 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -354,7 +354,7 @@ void CardReader::printListing(MediaFile parent, const char * const prepend, cons // // List all files on the SD card // -void CardReader::ls(const uint8_t lsflags) { +void CardReader::ls(const uint8_t lsflags/*=0*/) { if (flag.mounted) { root.rewind(); printListing(root, nullptr, lsflags); @@ -1129,9 +1129,9 @@ void CardReader::cdroot() { // Folder sorting needs 1 bit per entry for flags. #if HAS_FOLDER_SORTING #if ENABLED(SDSORT_DYNAMIC_RAM) - isDir = new uint8_t[(fileCnt + 7) >> 3]; + isDir = new uint8_t[(fileCnt + 7) >> 3]; // Allocate space with 'new' #elif ENABLED(SDSORT_USES_STACK) - uint8_t isDir[(fileCnt + 7) >> 3]; + uint8_t isDir[(fileCnt + 7) >> 3]; // Use stack in this scope #endif #endif diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 3aa8a7e6ec..a8018061ba 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -113,8 +113,6 @@ public: #endif #endif - // // // Methods // // // - CardReader(); static void changeMedia(DiskIODriver *_driver) { driver = _driver; } @@ -212,7 +210,7 @@ public: FORCE_INLINE static void getfilename_sorted(const uint16_t nr) { selectFileByIndex(nr); } #endif - static void ls(const uint8_t lsflags); + static void ls(const uint8_t lsflags=0); #if ENABLED(POWER_LOSS_RECOVERY) static bool jobRecoverFileExists(); @@ -279,7 +277,7 @@ private: //static bool sort_reverse; // Flag to enable / disable reverse sorting #endif - // By default the sort index is static + // By default the sort index is statically allocated #if ENABLED(SDSORT_DYNAMIC_RAM) static uint8_t *sort_order; #else diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp index 75421f4482..016500d2d6 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp @@ -201,7 +201,7 @@ uint8_t USB::ctrlReq(uint8_t addr, uint8_t ep, uint8_t bmReqType, uint8_t bReque * Keep sending INs and writes data to memory area pointed by 'data' * rcode 0 if no errors. rcode 01-0f is relayed from dispatchPkt(). Rcode f0 means RCVDAVIRQ error, fe = USB xfer timeout */ -uint8_t USB::inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t *data, uint8_t bInterval /*= 0*/) { +uint8_t USB::inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t *data, uint8_t bInterval/*=0*/) { EpInfo *pep = nullptr; uint16_t nak_limit = 0; @@ -215,7 +215,7 @@ uint8_t USB::inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t * return InTransfer(pep, nak_limit, nbytesptr, data, bInterval); } -uint8_t USB::InTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t *nbytesptr, uint8_t *data, uint8_t bInterval /*= 0*/) { +uint8_t USB::InTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t *nbytesptr, uint8_t *data, uint8_t bInterval/*=0*/) { uint8_t rcode = 0; uint8_t pktsize; diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/UsbCore.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/UsbCore.h index 2b6e1be522..16b8c092cc 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/UsbCore.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/UsbCore.h @@ -201,8 +201,6 @@ typedef struct { uint16_t wLength; // 6 Depends on bRequest } __attribute__((packed)) SETUP_PKT, *PSETUP_PKT; - - // Base class for incoming data parser class USBReadParser { diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp index 1aeef1703f..551fb274d7 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp @@ -796,7 +796,6 @@ uint8_t BulkOnly::RequestSense(uint8_t lun, uint16_t size, uint8_t *buf) { return Transaction(&cbw, size, buf); } - //////////////////////////////////////////////////////////////////////////////// // USB code //////////////////////////////////////////////////////////////////////////////// @@ -1148,7 +1147,6 @@ uint8_t BulkOnly::HandleSCSIError(uint8_t status) { } // switch } - //////////////////////////////////////////////////////////////////////////////// // Debugging code //////////////////////////////////////////////////////////////////////////////// diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h index aafb91624b..fa56b68573 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h @@ -22,7 +22,6 @@ * Web : https://www.circuitsathome.com * e-mail : support@circuitsathome.com */ - #pragma once // Cruft removal, makes driver smaller, faster. diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/parsetools.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/parsetools.h index 403766da8f..21c6cd4951 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/parsetools.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/parsetools.h @@ -141,5 +141,5 @@ public: theParser.Initialize(p); } - bool Parse(uint8_t **pp, uint16_t *pcntdn, PTP_ARRAY_EL_FUNC pf, const void *me = nullptr); + bool Parse(uint8_t **pp, uint16_t *pcntdn, PTP_ARRAY_EL_FUNC pf, const void *me=nullptr); }; diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h index 268c0e1d1d..1d46dc69b3 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h @@ -22,7 +22,6 @@ * Web : https://www.circuitsathome.com * e-mail : support@circuitsathome.com */ - #pragma once #include "../../../inc/MarlinConfig.h" diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usb_ch9.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usb_ch9.h index 99c628f888..f4d2af5176 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usb_ch9.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usb_ch9.h @@ -79,7 +79,6 @@ #define HID_DESCRIPTOR_HID 0x21 - /* OTG SET FEATURE Constants */ #define OTG_FEATURE_B_HNP_ENABLE 3 // SET FEATURE OTG - Enable B device to perform HNP #define OTG_FEATURE_A_HNP_SUPPORT 4 // SET FEATURE OTG - A device supports HNP @@ -92,7 +91,6 @@ #define USB_TRANSFER_TYPE_INTERRUPT 0x03 // Endpoint is an interrupt endpoint. #define bmUSB_TRANSFER_TYPE 0x03 // bit mask to separate transfer type from ISO attributes - /* Standard Feature Selectors for CLEAR_FEATURE Requests */ #define USB_FEATURE_ENDPOINT_STALL 0 // Endpoint recipient #define USB_FEATURE_DEVICE_REMOTE_WAKEUP 1 // Device recipient diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/README.txt b/Marlin/src/sd/usb_flashdrive/lib-uhs3/README.txt index 378786f940..f543bbaa64 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/README.txt +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/README.txt @@ -5,14 +5,12 @@ The lib-uhs3/ folder contains a subset of the files from the USB Host Shield https://github.com/felis/UHS30 - ==== LICENSE SUMMARY ==== Source Path: Repository: License: ------------ ----------- -------- usb_flashdrive/lib github.com/felis/UHS30 GPLv2 or later - ==== MARLIN INTEGRATION WORK ==== All additional work done to integrate USB into Marlin was performed by diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE.h index b35e53686e..c94e7ab990 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE.h @@ -27,7 +27,6 @@ e-mail : support@circuitsathome.com #ifndef __UHS_BULK_STORAGE_H__ #define __UHS_BULK_STORAGE_H__ - //////////////////////////////////////////////////////////////////////////////// // Define any of these options at the top of your sketch to override // the defaults contained herewith. Do NOT do modifications here. @@ -201,7 +200,6 @@ public: uint8_t SCSITransaction6(SCSI_CDB6_t *cdb, uint16_t buf_size, void *buf, uint8_t dir); uint8_t SCSITransaction10(SCSI_CDB10_t *cdb, uint16_t buf_size, void *buf, uint8_t dir); - // Configure and internal methods, these should never be called by a user's sketch. uint8_t Start(); bool OKtoEnumerate(ENUMERATION_INFO *ei); @@ -211,12 +209,10 @@ public: return bAddress; }; - void Poll(); void DriverDefaults(); - private: void Reset(); void CheckMedia(); diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE_INLINE.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE_INLINE.h index 37ba681c5c..06deb7a0ae 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE_INLINE.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_BULK_STORAGE/UHS_BULK_STORAGE_INLINE.h @@ -41,9 +41,7 @@ e-mail : support@circuitsathome.com #endif //////////////////////////////////////////////////////////////////////////////// - // Interface code - //////////////////////////////////////////////////////////////////////////////// /** @@ -298,9 +296,7 @@ again: // Only developer serviceable parts below! //////////////////////////////////////////////////////////////////////////////// - // Main driver code - //////////////////////////////////////////////////////////////////////////////// UHS_NI UHS_Bulk_Storage::UHS_Bulk_Storage(UHS_USB_HOST_BASE *p) { @@ -637,11 +633,7 @@ void UHS_NI UHS_Bulk_Storage::Poll() { } //////////////////////////////////////////////////////////////////////////////// - - // SCSI code - - //////////////////////////////////////////////////////////////////////////////// /** @@ -794,13 +786,8 @@ uint8_t UHS_NI UHS_Bulk_Storage::RequestSense(uint8_t lun, uint16_t size, uint8_ return v; } - //////////////////////////////////////////////////////////////////////////////// - - // USB code - - //////////////////////////////////////////////////////////////////////////////// /** @@ -954,7 +941,6 @@ uint8_t UHS_NI UHS_Bulk_Storage::HandleUsbError(uint8_t error, uint8_t index) { if(index != epDataInIndex) return UHS_BULK_ERR_WRITE_STALL; return UHS_BULK_ERR_STALL; - case UHS_HOST_ERROR_TOGERR: // Handle a very super rare corner case, where toggles become de-synched. // I have only ran into one device that has this firmware bug, and this is @@ -1171,13 +1157,8 @@ uint8_t UHS_NI UHS_Bulk_Storage::HandleSCSIError(uint8_t status) { } // switch } - //////////////////////////////////////////////////////////////////////////////// - - // Debugging code - - //////////////////////////////////////////////////////////////////////////////// /** diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_UsbCore.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_UsbCore.h index 58d7ba200c..9ec18fbf41 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_UsbCore.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_UsbCore.h @@ -59,7 +59,6 @@ e-mail : support@circuitsathome.com // D6-5 Type (0- standard, 1 - class, 2 - vendor, 3 - reserved) // D4-0 Recipient (0 - device, 1 - interface, 2 - endpoint, 3 - other, 4..31 - reserved) - // TO-DO: Use the python script to generate these. // TO-DO: Add _all_ subclasses here. // USB Device Classes, Subclasses and Protocols @@ -165,7 +164,6 @@ e-mail : support@circuitsathome.com //////////////////////////////////////////////////////////////////////////////// - /* USB state machine states */ #define UHS_USB_HOST_STATE_MASK 0xF0U @@ -324,7 +322,6 @@ typedef struct { // 8 bytes total } __attribute__((packed)) SETUP_PKT, *PSETUP_PKT; - // little endian :-) 8 8 8 8 16 16 #define mkSETUP_PKT8(bmReqType, bRequest, wValLo, wValHi, wInd, total) ((uint64_t)(((uint64_t)(bmReqType)))|(((uint64_t)(bRequest))<<8)|(((uint64_t)(wValLo))<<16)|(((uint64_t)(wValHi))<<24)|(((uint64_t)(wInd))<<32)|(((uint64_t)(total)<<48))) #define mkSETUP_PKT16(bmReqType, bRequest, wVal, wInd, total) ((uint64_t)(((uint64_t)(bmReqType)))|(((uint64_t)(bRequest))<<8)|(((uint64_t)(wVal ))<<16) |(((uint64_t)(wInd))<<32)|(((uint64_t)(total)<<48))) diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_address.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_address.h index 4d9d35bd6d..3b47bbd892 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_address.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_address.h @@ -29,8 +29,6 @@ e-mail : support@circuitsathome.com #else #define __ADDRESS_H__ - - /* NAK powers. To save space in endpoint data structure, amount of retries before giving up and returning 0x4 is stored in */ /* bmNakPower as a power of 2. The actual nak_limit is then calculated as nak_limit = ( 2^bmNakPower - 1) */ #define UHS_USB_NAK_MAX_POWER 14 // NAK binary order maximum value @@ -192,7 +190,6 @@ public: return (!index) ? NULL : &thePool[index]; }; - // Allocates new address uint8_t UHS_NI AllocAddress(uint8_t parent, bool is_hub = false, uint8_t port = 1) { diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h index f78a3bb8f0..d87b40fea2 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_host_INLINE.h @@ -47,7 +47,6 @@ UHS_EpInfo* UHS_USB_HOST_BASE::getEpInfoEntry(uint8_t addr, uint8_t ep) { if(!p || !p->epinfo) return NULL; - UHS_EpInfo *pep; for(uint8_t j = 0; j < UHS_HOST_MAX_INTERFACE_DRIVERS; j++) { pep = (UHS_EpInfo *)(p->epinfo[j]); @@ -311,7 +310,6 @@ again: return rcode; } - #if UHS_DEVICE_WINDOWS_USB_SPEC_VIOLATION_DESCRIPTOR_DEVICE ei.address = addrPool.AllocAddress(parent, false, port); @@ -1111,7 +1109,6 @@ uint8_t UHS_USB_HOST_BASE::enumerateInterface(ENUMERATION_INFO *ei) { return devConfigIndex; }; - //////////////////////////////////////////////////////////////////////////////// // Vendor Specific Interface Class //////////////////////////////////////////////////////////////////////////////// @@ -1168,7 +1165,6 @@ uint8_t UHS_NI UHS_VSI::SetInterface(ENUMERATION_INFO *ei) { //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// - #if 0 /* TO-DO: Move this silliness to a NONE driver. diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_macros.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_macros.h index bb2a87cf03..6e9bb8b783 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_macros.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_macros.h @@ -31,7 +31,6 @@ e-mail : support@circuitsathome.com * Universal Arduino(tm) "IDE" fixups. */ - // Just in case... #ifndef SERIAL_PORT_MONITOR #define SERIAL_PORT_MONITOR Serial @@ -57,7 +56,6 @@ e-mail : support@circuitsathome.com #endif #endif - #ifndef UHS_DEVICE_WINDOWS_USB_SPEC_VIOLATION_DESCRIPTOR_DEVICE #ifndef UHS_BIG_FLASH @@ -160,7 +158,6 @@ e-mail : support@circuitsathome.com #define UHS_KIO_SETBIT_ATOMIC(r, m) (*(uint32_t *)UHS_KIO_BITBAND_ADDR((r), BITNR((m)))) = 1 #define UHS_KIO_CLRBIT_ATOMIC(r, m) (*(uint32_t *)UHS_KIO_BITBAND_ADDR((r), BITNR((m)))) = 0 - #define VALUE_BETWEEN(v,l,h) (((v)>(l)) && ((v)<(h))) #define VALUE_WITHIN(v,l,h) (((v)>=(l)) && ((v)<=(h))) #define output_pgm_message(wa,fp,mp,el) wa = &mp, fp((char *)pgm_read_pointer(wa), el) diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_printf_HELPER.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_printf_HELPER.h index 4fc9b94079..bb464d7adf 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_printf_HELPER.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_printf_HELPER.h @@ -167,8 +167,6 @@ extern "C" { #error no STDIO #endif // defined(ARDUINO_ARCH_PIC32) - - #ifdef __AVR__ // The only wierdo in the bunch... void UHS_AVR_printf_HELPER_init() { diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_printhex.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_printhex.h index edf673a4fb..af8917e14d 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_printhex.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_printhex.h @@ -91,6 +91,4 @@ template void D_PrintBin(NOTUSED(T val), NOTUSED(int lvl)) { #endif } - - #endif // __PRINTHEX_H__ diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_settings.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_settings.h index c516599d6b..03bf1c1c07 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_settings.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_settings.h @@ -55,7 +55,6 @@ e-mail : support@circuitsathome.com // //////////////////////////////////////////////////////////////////////////////// - //////////////////////////////////////////////////////////////////////////////// // DEBUGGING //////////////////////////////////////////////////////////////////////////////// diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_usb_ch9.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_usb_ch9.h index 6486482d96..013be2a9d4 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_usb_ch9.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/UHS_usb_ch9.h @@ -97,7 +97,6 @@ e-mail : support@circuitsathome.com #define USB_SETUP_RECIPIENT_PORT 0x04 // Wireless USB 1.0 #define USB_SETUP_RECIPIENT_RPIPE 0x05 // Wireless USB 1.0 - /* USB descriptors */ #define USB_DESCRIPTOR_DEVICE 0x01 // bDescriptorType for a Device Descriptor. #define USB_DESCRIPTOR_CONFIGURATION 0x02 // bDescriptorType for a Configuration Descriptor. @@ -123,7 +122,6 @@ e-mail : support@circuitsathome.com #define USB_HID_DESCRIPTOR 0x21 - // Conventional codes for class-specific descriptors. "Common Class" Spec (3.11) #define USB_DESCRIPTOR_CS_DEVICE 0x21 #define USB_DESCRIPTOR_CS_CONFIG 0x22 @@ -131,8 +129,6 @@ e-mail : support@circuitsathome.com #define USB_DESCRIPTOR_CS_INTERFACE 0x24 #define USB_DESCRIPTOR_CS_ENDPOINT 0x25 - - /* USB Endpoint Transfer Types */ #define USB_TRANSFER_TYPE_CONTROL 0x00 // Endpoint is a control endpoint. #define USB_TRANSFER_TYPE_ISOCHRONOUS 0x01 // Endpoint is an isochronous endpoint. diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD.h index 79c06a492b..eb4f35eb13 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD.h @@ -27,7 +27,6 @@ e-mail : support@circuitsathome.com #include "UHS_max3421e.h" #include - #ifndef SPI_HAS_TRANSACTION #error "Your SPI library installation is too old." #else @@ -58,8 +57,6 @@ e-mail : support@circuitsathome.com #define USB_HOST_SHIELD_USE_ISR 1 #endif - - #if !USB_HOST_SHIELD_USE_ISR #error NOISR Polled mode _NOT SUPPORTED YET_ @@ -180,8 +177,6 @@ e-mail : support@circuitsathome.com #endif #endif - - #ifdef NO_AUTO_SPEED // Ugly details section... // MAX3421E characteristics @@ -466,7 +461,6 @@ public: interrupts(); }; - int16_t UHS_NI Init(int16_t mseconds); int16_t UHS_NI Init() { diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD_INLINE.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD_INLINE.h index 57352a3518..f126a6fcef 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD_INLINE.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/USB_HOST_SHIELD/USB_HOST_SHIELD_INLINE.h @@ -28,7 +28,6 @@ #error digitalPinToInterrupt not defined, complain to your board maintainer. #endif - #if USB_HOST_SHIELD_USE_ISR // allow two slots. this makes the maximum allowed shield count TWO @@ -47,7 +46,6 @@ } #endif - void UHS_NI MAX3421E_HOST::resume_host() { // Used on MCU that lack control of IRQ priority (AVR). // Resumes ISRs. @@ -875,7 +873,6 @@ void UHS_NI MAX3421E_HOST::ISRbottom() { DDSB(); } - /* USB main task. Services the MAX3421e */ #if !USB_HOST_SHIELD_USE_ISR void UHS_NI MAX3421E_HOST::ISRTask() {} diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h index eeaa4f81d9..1318ea8b28 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/UHS_host/macro_logic.h @@ -126,12 +126,10 @@ AJK_IIF(AJK_BITAND(AJK_IS_COMPARABLE(x))(AJK_IS_COMPARABLE(y)) ) \ #define AJK_EQUAL(x, y) AJK_COMPL(AJK_NOT_EQUAL(x, y)) - #define AJK_COMMA() , #define AJK_COMMA_IF(n) AJK_IF(n)(AJK_COMMA, AJK_EAT)() - #define AJK_COMMA_VAR(AJK_count, AJK_v) AJK_COMMA_IF(AJK_count) AJK_v ## AJK_count #define AJK_MAKE_LIST(AJK_v, AJK_count) AJK_EVAL(AJK_REPEAT(AJK_count, AJK_COMMA_VAR, AJK_v)) diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/SWI_INLINE.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/SWI_INLINE.h index f86054cad8..f50b3bd4c1 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/SWI_INLINE.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/SWI_INLINE.h @@ -29,8 +29,6 @@ #define SWI_MAXIMUM_ALLOWED 4 #endif - - #if defined(__arm__) || defined(ARDUINO_ARCH_PIC32) static char dyn_SWI_initied = 0; static dyn_SWI* dyn_SWI_LIST[SWI_MAXIMUM_ALLOWED]; @@ -79,7 +77,6 @@ void softISR() { // TO-DO: Perhaps limit to 8, and inline this? // - // Make a working copy, while clearing the queue. noInterrupts(); #ifdef ARDUINO_ARCH_PIC32 @@ -117,7 +114,6 @@ void softISR() { #define DDSB() __DSB() #endif - #ifdef __arm__ #ifndef interruptsStatus #define interruptsStatus() __interruptsStatus() diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/dyn_SWI.h b/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/dyn_SWI.h index 07f4ae054d..652b43fd2e 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/dyn_SWI.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/dyn_SWI/dyn_SWI.h @@ -22,7 +22,6 @@ #ifndef DYN_SWI_H #define DYN_SWI_H - #if defined(__arm__) || defined(ARDUINO_ARCH_PIC32) #ifdef ARDUINO_ARCH_PIC32 #include @@ -135,7 +134,6 @@ extern "C" #error Do not know how to relocate IRQ vectors or perform SWI #endif // SWI_IRQ_NUM - #ifndef SWI_IRQ_NUM #error SWI_IRQ_NUM not defined #else diff --git a/docs/Cutter.md b/docs/Cutter.md index c78b0551a0..623beb21f4 100644 --- a/docs/Cutter.md +++ b/docs/Cutter.md @@ -4,7 +4,7 @@ With Marlin version 2.0.9.x or higher, Laser improvements were introduced that e ### Architecture -Laser selectable feature capability is defined through 4 global mode flags within gcode ,laser/spindle, planner and stepper routines. The default mode maintains the standard laser function. G-Codes are received, processed and parsed to determine what mode to set through M3, M4 and M5 commands. When the inline mode parameter set is detected, laser power processing will be driven through the planner and stepper routines. Handling of the initial power values and settings are performed by G-Code parsing and the laser/spindle routines. +Laser selectable feature capability is defined through 4 global mode flags within G-code ,laser/spindle, planner and stepper routines. The default mode maintains the standard laser function. G-Codes are received, processed and parsed to determine what mode to set through M3, M4 and M5 commands. When the inline mode parameter set is detected, laser power processing will be driven through the planner and stepper routines. Handling of the initial power values and settings are performed by G-Code parsing and the laser/spindle routines. Inline power feeds from the block->inline_power variable into the planner's laser.power when in continuous power mode. Further power adjustment will be applied if the laser power trap feature is active otherwise laser.power is used as set in the stepper for the entire block. When laser power trap is active the power levels are step incremented during acceleration and step decremented during deceleration. @@ -20,52 +20,52 @@ The following flow charts depict the flow control logic for spindle and laser op #### Spindle Mode Logic: - ┌──────────┐ ┌───────────┐ ┌───────────┐ - │M3 S-Value│ │Dir !same ?│ │Stepper │ - │Spindle │ │stop & wait│ │processes │ - ┌──┤Clockwise ├──┤ & start ├──┤moves │ - ┌─────┐ │ │ │ │spindle │ │ │ - │GCode│ │ └──────────┘ └───────────┘ └───────────┘ - │Send ├──┤ ┌──────────┐ ┌───────────┐ ┌───────────┐ - └─────┘ │ │M4 S-Value│ │Dir !same ?│ │Stepper │ - ├──┤Spindle ├──┤stop & wait├──┤processes │ - │ │Counter │ │& start │ │moves │ - │ │Clockwise │ │spindle │ │ │ - │ └──────────┘ └───────────┘ └───────────┘ - │ ┌──────────┐ ┌────────┐ - │ │M5 │ │Wait for│ - │ │Spindle ├──┤move & │ - └──┤Stop │ │disable │ - └──────────┘ └────────┘ - ┌──────────┐ ┌──────────┐ - Sensors─────┤Fault ├──┤Disable │ - └──────────┘ │power │ - └──────────┘ + ┌──────────┐ ┌───────────┐ ┌───────────┐ + │M3 S-Value│ │Dir !same ?│ │Stepper │ + │Spindle │ │stop & wait│ │processes │ + ┌──┤Clockwise ├──┤ & start ├──┤moves │ + ┌──────┐ │ │ │ │spindle │ │ │ + │G-Code│ │ └──────────┘ └───────────┘ └───────────┘ + │Send ├──┤ ┌──────────┐ ┌───────────┐ ┌───────────┐ + └──────┘ │ │M4 S-Value│ │Dir !same ?│ │Stepper │ + ├──┤Spindle ├──┤stop & wait├──┤processes │ + │ │Counter │ │& start │ │moves │ + │ │Clockwise │ │spindle │ │ │ + │ └──────────┘ └───────────┘ └───────────┘ + │ ┌──────────┐ ┌────────┐ + │ │M5 │ │Wait for│ + │ │Spindle ├──┤move & │ + └──┤Stop │ │disable │ + └──────────┘ └────────┘ + ┌──────────┐ ┌──────────┐ + Sensors─────┤Fault ├──┤Disable │ + └──────────┘ │power │ + └──────────┘ #### Laser Mode Logic: - ┌──────────┐ ┌─────────────┐ ┌───────────┐ - │M3,M4,M5 I│ │Set power │ │Stepper │ - ┌──┤Standard ├──┤Immediately &├──┤processes │ - │ │Default │ │wait for move│ │moves │ - │ │ │ │completion │ │ │ - │ └──────────┘ └─────────────┘ └───────────┘ - │ ┌──────────┐ ┌───────────┐ ┌───────────┐ ┌────────────┐ ┌────────────┐ ┌────────────┐ ┌───────────┐ - ┌─────┐ │ │M3 I │ │G0,G1,G2,G4│ │Planner │ │Planner │ │Planner fan │ │Planner │ │Stepper │ - │GCode│ │ │Continuous│ │M3 receive │ │sets block │ │sync power ?│ │sync power ?│ │trap power ?│ │uses block │ - │Send ├──┼──┤Inline ├──┤power from ├──┤power using├──┤process M3 ├──┤process fan ├──┤adjusts for ├──┤values to │ - └─────┘ │ │ │ │S-Value │ │Gx S-Value │ │power inline│ │power inline│ │accel/decel │ │apply power│ - │ └──────────┘ └───────────┘ └───────────┘ └────────────┘ └────────────┘ └────────────┘ └───────────┘ - │ ┌──────────┐ ┌───────────┐ ┌────────────────┐ ┌───────────┐ - │ │M4 I │ │Gx F-Value │ │Planner │ │Stepper │ - │ │Dynamic │ │set power │ │Calc & set block│ │uses block │ - └──┤Inline ├──┤or use ├──┤block power ├──┤values to │ - │ │ │default │ │using F-Value │ │apply power│ - └──────────┘ └───────────┘ └────────────────┘ └───────────┘ - ┌──────────┐ ┌──────────┐ - Sensors─────┤Fault ├──┤Disable │ - └──────────┘ │Power │ - └──────────┘ + ┌──────────┐ ┌─────────────┐ ┌───────────┐ + │M3,M4,M5 I│ │Set power │ │Stepper │ + ┌──┤Standard ├──┤Immediately &├──┤processes │ + │ │Default │ │wait for move│ │moves │ + │ │ │ │completion │ │ │ + │ └──────────┘ └─────────────┘ └───────────┘ + │ ┌──────────┐ ┌───────────┐ ┌───────────┐ ┌────────────┐ ┌────────────┐ ┌────────────┐ ┌───────────┐ + ┌──────┐ │ │M3 I │ │G0,G1,G2,G4│ │Planner │ │Planner │ │Planner fan │ │Planner │ │Stepper │ + │G-Code│ │ │Continuous│ │M3 receive │ │sets block │ │sync power ?│ │sync power ?│ │trap power ?│ │uses block │ + │Send ├──┼──┤Inline ├──┤power from ├──┤power using├──┤process M3 ├──┤process fan ├──┤adjusts for ├──┤values to │ + └──────┘ │ │ │ │S-Value │ │Gx S-Value │ │power inline│ │power inline│ │accel/decel │ │apply power│ + │ └──────────┘ └───────────┘ └───────────┘ └────────────┘ └────────────┘ └────────────┘ └───────────┘ + │ ┌──────────┐ ┌───────────┐ ┌────────────────┐ ┌───────────┐ + │ │M4 I │ │Gx F-Value │ │Planner │ │Stepper │ + │ │Dynamic │ │set power │ │Calc & set block│ │uses block │ + └──┤Inline ├──┤or use ├──┤block power ├──┤values to │ + │ │ │default │ │using F-Value │ │apply power│ + └──────────┘ └───────────┘ └────────────────┘ └───────────┘ + ┌──────────┐ ┌──────────┐ + Sensors─────┤Fault ├──┤Disable │ + └──────────┘ │Power │ + └──────────┘ diff --git a/docs/Queue.md b/docs/Queue.md index bce68b0551..6d4fb9d041 100644 --- a/docs/Queue.md +++ b/docs/Queue.md @@ -19,7 +19,7 @@ Here's a basic flowchart of Marlin command processing: | Host | | SerialState RingBuffer | | | | | Marlin | NUM_SERIAL BUF_SIZE | | Marlin | +--+---+ R/TX_BUFFER_SIZE | +---+ +------------------+ | | | - | +------------+ | | | | | | | GCode | + | +------------+ | | | | | | | G-Code | | | | | | | | MAX_CMD_SIZE +-+-----> processor | | | Platform | | | | On EOL | +--------------+ | r_pos | | +-------------> serial's +-----------> +--------> | G-code | | | +-----------+