diff --git a/Marlin/src/HAL/HAL_AVR/HAL_spi_AVR.cpp b/Marlin/src/HAL/HAL_AVR/HAL_spi_AVR.cpp index ef0dc8b1a2..a5e811c02a 100644 --- a/Marlin/src/HAL/HAL_AVR/HAL_spi_AVR.cpp +++ b/Marlin/src/HAL/HAL_AVR/HAL_spi_AVR.cpp @@ -95,8 +95,7 @@ void spiBegin (void) { SPSR = spiRate & 1 || spiRate == 6 ? 0 : _BV(SPI2X); } - - //------------------------------------------------------------------------------ + //------------------------------------------------------------------------------ /** SPI receive a byte */ uint8_t spiRec(void) { SPDR = 0xFF; @@ -157,7 +156,7 @@ void spiBegin (void) { // is 2 ^^ (clock_div + 1). If nothing is slow enough, we'll use the // slowest (128 == 2 ^^ 7, so clock_div = 6). uint8_t clockDiv; - + // When the clock is known at compiletime, use this if-then-else // cascade, which the compiler knows how to completely optimize // away. When clock is not known, use a loop instead, which generates @@ -196,10 +195,10 @@ void spiBegin (void) { SPCR = _BV(SPE) | _BV(MSTR) | ((bitOrder == SPI_LSBFIRST) ? _BV(DORD) : 0) | (dataMode << CPHA) | ((clockDiv >> 1) << SPR0); - SPSR = clockDiv | 0x01; + SPSR = clockDiv | 0x01; } - + //------------------------------------------------------------------------------ #else // SOFTWARE_SPI //------------------------------------------------------------------------------ @@ -216,7 +215,7 @@ void spiBegin (void) { void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { // nothing to do UNUSED(spiBeginTransaction); - } + } //------------------------------------------------------------------------------ /** Soft SPI receive byte */ @@ -280,7 +279,7 @@ void spiBegin (void) { spiSend(token); for (uint16_t i = 0; i < 512; i++) spiSend(buf[i]); - } + } #endif // SOFTWARE_SPI diff --git a/Marlin/src/HAL/HAL_DUE/HAL_spi_Due.cpp b/Marlin/src/HAL/HAL_DUE/HAL_spi_Due.cpp index 2b9ec80387..b35438f82b 100644 --- a/Marlin/src/HAL/HAL_DUE/HAL_spi_Due.cpp +++ b/Marlin/src/HAL/HAL_DUE/HAL_spi_Due.cpp @@ -574,9 +574,9 @@ /** Begin SPI transaction, set clock, bit order, data mode */ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { // TODO: to be implemented - - } - + + } + #pragma GCC reset_options #else @@ -777,9 +777,8 @@ /** Begin SPI transaction, set clock, bit order, data mode */ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { // TODO: to be implemented - - } - + } + #endif // ENABLED(SOFTWARE_SPI) #endif // ARDUINO_ARCH_SAM diff --git a/Marlin/src/HAL/HAL_DUE/u8g_com_HAL_DUE_st7920_sw_spi.cpp b/Marlin/src/HAL/HAL_DUE/u8g_com_HAL_DUE_st7920_sw_spi.cpp index 965b525bd8..192423d000 100644 --- a/Marlin/src/HAL/HAL_DUE/u8g_com_HAL_DUE_st7920_sw_spi.cpp +++ b/Marlin/src/HAL/HAL_DUE/u8g_com_HAL_DUE_st7920_sw_spi.cpp @@ -152,10 +152,10 @@ uint8_t u8g_com_HAL_DUE_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_va u8g_SetPIOutput_DUE(u8g, U8G_PI_SCK); u8g_SetPILevel_DUE(u8g, U8G_PI_MOSI, 0); u8g_SetPIOutput_DUE(u8g, U8G_PI_MOSI); - + SCK_pPio->PIO_CODR = SCK_dwMask; //SCK low - needed at power up but not after reset MOSI_pPio->PIO_CODR = MOSI_dwMask; //MOSI low - needed at power up but not after reset - + u8g_Delay(5); u8g->pin_list[U8G_PI_A0_STATE] = 0; /* inital RS state: command mode */ diff --git a/Marlin/src/HAL/HAL_DUE/usb/compiler.h b/Marlin/src/HAL/HAL_DUE/usb/compiler.h index fed704aace..fa705e218d 100644 --- a/Marlin/src/HAL/HAL_DUE/usb/compiler.h +++ b/Marlin/src/HAL/HAL_DUE/usb/compiler.h @@ -250,7 +250,7 @@ /* Define OPTIMIZE_HIGH attribute */ #if defined ( __CC_ARM ) /* Keil µVision 4 */ -# define OPTIMIZE_HIGH _Pragma("O3") +# define OPTIMIZE_HIGH _Pragma("O3") #elif defined ( __ICCARM__ ) /* IAR Ewarm 5.41+ */ # define OPTIMIZE_HIGH _Pragma("optimize=high") #elif defined ( __GNUC__ ) /* GCC CS3 2009q3-68 */ @@ -889,7 +889,7 @@ typedef struct #define LSB2W(u32) MSB1W(u32) //!< Least significant byte of 3rd rank of \a u32. #define LSB1W(u32) MSB2W(u32) //!< Least significant byte of 2nd rank of \a u32. #define LSB0W(u32) MSB3W(u32) //!< Least significant byte of 1st rank of \a u32. - + #define MSW(u64) (((U32 *)&(u64))[1]) //!< Most significant word of \a u64. #define LSW(u64) (((U32 *)&(u64))[0]) //!< Least significant word of \a u64. #define MSH0(u64) (((U16 *)&(u64))[3]) //!< Most significant half-word of 1st rank of \a u64. diff --git a/Marlin/src/HAL/HAL_DUE/usb/conf_access.h b/Marlin/src/HAL/HAL_DUE/usb/conf_access.h index d9f7ddb40e..553737ded5 100644 --- a/Marlin/src/HAL/HAL_DUE/usb/conf_access.h +++ b/Marlin/src/HAL/HAL_DUE/usb/conf_access.h @@ -59,14 +59,14 @@ #else #define LUN_0 DISABLE #endif -#define LUN_1 DISABLE -#define LUN_2 DISABLE -#define LUN_3 DISABLE +#define LUN_1 DISABLE +#define LUN_2 DISABLE +#define LUN_3 DISABLE #define LUN_4 DISABLE #define LUN_5 DISABLE #define LUN_6 DISABLE #define LUN_7 DISABLE -#define LUN_USB DISABLE +#define LUN_USB DISABLE //! @} /*! \name LUN 0 Definitions @@ -93,10 +93,10 @@ * \warning Be careful not to waste time in order not to disturb the functions. */ //! @{ -#define memory_start_read_action(nb_sectors) -#define memory_stop_read_action() -#define memory_start_write_action(nb_sectors) -#define memory_stop_write_action() +#define memory_start_read_action(nb_sectors) +#define memory_stop_read_action() +#define memory_start_write_action(nb_sectors) +#define memory_stop_write_action() //! @} /*! \name Activation of Interface Features diff --git a/Marlin/src/HAL/HAL_DUE/usb/osc.h b/Marlin/src/HAL/HAL_DUE/usb/osc.h index e6df402597..fe09d6fd3e 100644 --- a/Marlin/src/HAL/HAL_DUE/usb/osc.h +++ b/Marlin/src/HAL/HAL_DUE/usb/osc.h @@ -246,7 +246,7 @@ static inline void osc_wait_ready(uint8_t id) while (!osc_is_ready(id)) { /* Do nothing */ } -} +} //! @} diff --git a/Marlin/src/HAL/HAL_DUE/usb/pll.h b/Marlin/src/HAL/HAL_DUE/usb/pll.h index d9b946be26..88545eedf6 100644 --- a/Marlin/src/HAL/HAL_DUE/usb/pll.h +++ b/Marlin/src/HAL/HAL_DUE/usb/pll.h @@ -273,8 +273,8 @@ static inline int pll_wait_for_lock(unsigned int pll_id) } return 0; -} - +} + //! @} /// @cond 0 diff --git a/Marlin/src/HAL/HAL_DUE/usb/sd_mmc_spi_mem.h b/Marlin/src/HAL/HAL_DUE/usb/sd_mmc_spi_mem.h index ea177c9920..6df82c146b 100644 --- a/Marlin/src/HAL/HAL_DUE/usb/sd_mmc_spi_mem.h +++ b/Marlin/src/HAL/HAL_DUE/usb/sd_mmc_spi_mem.h @@ -113,7 +113,7 @@ extern Ctrl_status sd_mmc_spi_read_capacity(uint32_t *nb_sector); * * \return \c true if unload/load done success. */ -extern bool sd_mmc_spi_unload(bool unload); +extern bool sd_mmc_spi_unload(bool unload); //! //! @brief This function returns the write protected status of the memory. diff --git a/Marlin/src/HAL/HAL_DUE/usb/sysclk.c b/Marlin/src/HAL/HAL_DUE/usb/sysclk.c index 1190895012..2328a0853f 100644 --- a/Marlin/src/HAL/HAL_DUE/usb/sysclk.c +++ b/Marlin/src/HAL/HAL_DUE/usb/sysclk.c @@ -45,7 +45,7 @@ */ #ifdef ARDUINO_ARCH_SAM - + #include "sysclk.h" /// @cond 0 diff --git a/Marlin/src/HAL/HAL_DUE/usb/udc.c b/Marlin/src/HAL/HAL_DUE/usb/udc.c index 9f3c14aa24..6995d20b56 100644 --- a/Marlin/src/HAL/HAL_DUE/usb/udc.c +++ b/Marlin/src/HAL/HAL_DUE/usb/udc.c @@ -45,7 +45,7 @@ */ #ifdef ARDUINO_ARCH_SAM - + #include "conf_usb.h" #include "usb_protocol.h" #include "udd.h" diff --git a/Marlin/src/HAL/HAL_DUE/usb/udc.h b/Marlin/src/HAL/HAL_DUE/usb/udc.h index edfe70788b..885bdf04d6 100644 --- a/Marlin/src/HAL/HAL_DUE/usb/udc.h +++ b/Marlin/src/HAL/HAL_DUE/usb/udc.h @@ -143,7 +143,7 @@ extern "C" { * USB_DEVICE_ATTACH_AUTO_DISABLE: * \code #define USB_DEVICE_ATTACH_AUTO_DISABLE \endcode * User C file contains: - * \code + * \code // Authorize VBUS monitoring if (!udc_include_vbus_monitoring()) { // Implement custom VBUS monitoring via GPIO or other @@ -159,7 +159,7 @@ extern "C" { * USB_DEVICE_ATTACH_AUTO_DISABLE: * \code #define USB_DEVICE_ATTACH_AUTO_DISABLE \endcode * User C file contains: - * \code + * \code Event VBUS present() // VBUS interrupt or GPIO interrupt or .. { // Authorize battery charging, but wait key press to start USB. @@ -446,7 +446,7 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void); # 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. + // 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 diff --git a/Marlin/src/HAL/HAL_DUE/usb/udi_cdc.c b/Marlin/src/HAL/HAL_DUE/usb/udi_cdc.c index 7844c08920..f8ae82cf8b 100644 --- a/Marlin/src/HAL/HAL_DUE/usb/udi_cdc.c +++ b/Marlin/src/HAL/HAL_DUE/usb/udi_cdc.c @@ -977,7 +977,7 @@ static iram_size_t udi_cdc_multi_read_no_polling(uint8_t port, void* buf, iram_s if (!udi_cdc_data_running) { return 0; } - + //Get number of available data // Check available data flags = cpu_irq_save(); // to protect udi_cdc_rx_pos & udi_cdc_rx_buf_sel @@ -995,7 +995,7 @@ static iram_size_t udi_cdc_multi_read_no_polling(uint8_t port, void* buf, iram_s flags = cpu_irq_save(); // to protect udi_cdc_rx_pos udi_cdc_rx_pos[port] += size; cpu_irq_restore(flags); - + ptr_buf += size; udi_cdc_rx_start(port); } @@ -1036,7 +1036,7 @@ iram_size_t udi_cdc_multi_get_free_tx_buffer(uint8_t port) buf_sel_nb = 0; } } - retval = UDI_CDC_TX_BUFFERS - buf_sel_nb; + retval = UDI_CDC_TX_BUFFERS - buf_sel_nb; cpu_irq_restore(flags); return retval; } diff --git a/Marlin/src/HAL/HAL_DUE/usb/udi_composite_desc.c b/Marlin/src/HAL/HAL_DUE/usb/udi_composite_desc.c index 85f81999fd..6ba06afbf9 100644 --- a/Marlin/src/HAL/HAL_DUE/usb/udi_composite_desc.c +++ b/Marlin/src/HAL/HAL_DUE/usb/udi_composite_desc.c @@ -43,8 +43,8 @@ /* * Support and FAQ: visit Atmel Support */ - -#ifdef ARDUINO_ARCH_SAM + +#ifdef ARDUINO_ARCH_SAM #include "conf_usb.h" #include "udd.h" diff --git a/Marlin/src/HAL/HAL_DUE/usb/udi_msc.c b/Marlin/src/HAL/HAL_DUE/usb/udi_msc.c index f8f93a09c5..2dd9ad5353 100644 --- a/Marlin/src/HAL/HAL_DUE/usb/udi_msc.c +++ b/Marlin/src/HAL/HAL_DUE/usb/udi_msc.c @@ -43,8 +43,8 @@ /* * Support and FAQ: visit Atmel Support */ - -#ifdef ARDUINO_ARCH_SAM + +#ifdef ARDUINO_ARCH_SAM #include "conf_usb.h" #include "usb_protocol.h" diff --git a/Marlin/src/HAL/HAL_DUE/usb/udi_msc.h b/Marlin/src/HAL/HAL_DUE/usb/udi_msc.h index 7a76ad84fc..c632ee4aac 100644 --- a/Marlin/src/HAL/HAL_DUE/usb/udi_msc.h +++ b/Marlin/src/HAL/HAL_DUE/usb/udi_msc.h @@ -174,14 +174,14 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, /** * \page udi_msc_quickstart Quick start guide for USB device Mass Storage module (UDI MSC) * - * This is the quick start guide for the \ref udi_msc_group - * "USB device interface MSC module (UDI MSC)" with step-by-step instructions on + * This is the quick start guide for the \ref udi_msc_group + * "USB device interface MSC module (UDI MSC)" with step-by-step instructions on * how to configure and use the modules in a selection of use cases. * * The use cases contain several code fragments. The code fragments in the * steps for setup can be copied into a custom initialization function, while * the steps for usage can be copied into, e.g., the main application function. - * + * * \section udi_msc_basic_use_case Basic use case * In this basic use case, the "USB MSC (Single Interface Device)" module is used. * The "USB MSC (Composite Device)" module usage is described in \ref udi_msc_use_cases @@ -246,7 +246,7 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * - \code #define UDI_MSC_ENABLE_EXT() my_callback_msc_enable() 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 + * 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 * UDI_MSC_ENABLE_EXT() callback function is called and return true. * Thus, when this event is received, the tasks which call @@ -256,7 +256,7 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * \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(). - * -# The MSC is automatically linked with memory control access component + * -# The MSC is automatically linked with memory control access component * which provides the memories interfaces. However, the memory data transfers * must be done outside USB interrupt routine. This is done in the MSC process * ("udi_msc_process_trans()") called by main loop: @@ -288,7 +288,7 @@ bool udi_msc_trans_block(bool b_read, uint8_t * block, iram_size_t block_size, * In this use case, the "USB MSC (Composite Device)" module is used to * create a USB composite device. Thus, this USB module can be associated with * another "Composite Device" module, like "USB HID Mouse (Composite Device)". - * + * * Also, you can refer to application note * * AVR4902 ASF - USB Composite Device. diff --git a/Marlin/src/HAL/HAL_DUE/usb/uotghs_device_due.c b/Marlin/src/HAL/HAL_DUE/usb/uotghs_device_due.c index 0853a4af0c..243e2db541 100644 --- a/Marlin/src/HAL/HAL_DUE/usb/uotghs_device_due.c +++ b/Marlin/src/HAL/HAL_DUE/usb/uotghs_device_due.c @@ -43,7 +43,7 @@ /* * Support and FAQ: visit Atmel Support */ - + #ifdef ARDUINO_ARCH_SAM #include "compiler.h" diff --git a/Marlin/src/HAL/HAL_DUE/usb/uotghs_otg.h b/Marlin/src/HAL/HAL_DUE/usb/uotghs_otg.h index 4fb0ba7c1f..34436165e2 100644 --- a/Marlin/src/HAL/HAL_DUE/usb/uotghs_otg.h +++ b/Marlin/src/HAL/HAL_DUE/usb/uotghs_otg.h @@ -136,17 +136,17 @@ void otg_dual_disable(void); } while (0) //! Enable USB macro #define otg_enable() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_USBE)) - //! Disable USB macro + //! Disable USB macro #define otg_disable() (Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_USBE)) #define Is_otg_enabled() (Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_USBE)) - //! Enable OTG pad + //! Enable OTG pad #define otg_enable_pad() (Set_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_OTGPADE)) - //! Disable OTG pad + //! Disable OTG pad #define otg_disable_pad() (Clr_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_OTGPADE)) #define Is_otg_pad_enabled() (Tst_bits(UOTGHS->UOTGHS_CTRL, UOTGHS_CTRL_OTGPADE)) - //! Check Clock Usable + //! Check Clock Usable //! For parts with HS feature, this one corresponding at UTMI clock #define Is_otg_clock_usable() (Tst_bits(UOTGHS->UOTGHS_SR, UOTGHS_SR_CLKUSABLE)) diff --git a/Marlin/src/HAL/HAL_LPC1768/HAL_spi.cpp b/Marlin/src/HAL/HAL_LPC1768/HAL_spi.cpp index eb8d5ba983..f027d60744 100644 --- a/Marlin/src/HAL/HAL_LPC1768/HAL_spi.cpp +++ b/Marlin/src/HAL/HAL_LPC1768/HAL_spi.cpp @@ -303,9 +303,9 @@ PinCfg.Portnum = LPC1768_PIN_PORT(MISO_PIN); /** Begin SPI transaction, set clock, bit order, data mode */ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { // TODO: to be implemented - - } - + + } + #endif // ENABLED(LPC_SOFTWARE_SPI) #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/HAL_LPC1768/HAL_timers.h b/Marlin/src/HAL/HAL_LPC1768/HAL_timers.h index fcf1dd1546..34b3b24b9a 100644 --- a/Marlin/src/HAL/HAL_LPC1768/HAL_timers.h +++ b/Marlin/src/HAL/HAL_LPC1768/HAL_timers.h @@ -66,7 +66,7 @@ typedef uint32_t hal_timer_t; #define HAL_STEP_TIMER_ISR extern "C" void TIMER0_IRQHandler(void) #define HAL_TEMP_TIMER_ISR extern "C" void TIMER1_IRQHandler(void) -// PWM timer +// PWM timer #define HAL_PWM_TIMER LPC_TIM3 #define HAL_PWM_TIMER_ISR extern "C" void TIMER3_IRQHandler(void) #define HAL_PWM_TIMER_IRQn TIMER3_IRQn diff --git a/Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.cpp b/Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.cpp index 858ded3844..e9bbb9bb09 100644 --- a/Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.cpp +++ b/Marlin/src/HAL/HAL_LPC1768/LPC1768_PWM.cpp @@ -506,7 +506,7 @@ HAL_PWM_TIMER_ISR { if (first_active_entry) next_MR1_val = LPC_PWM1_MR0 + 1; // empty table so disable MR1 interrupt HAL_PWM_TIMER->MR1 = MAX(next_MR1_val, HAL_PWM_TIMER->TC + PWM_LPC1768_ISR_SAFETY_FACTOR); // set next in_PWM_isr = false; - + exit_PWM_ISR: return; } diff --git a/Marlin/src/HAL/HAL_LPC1768/arduino.cpp b/Marlin/src/HAL/HAL_LPC1768/arduino.cpp index b6a4b8c5cf..feab1e8b09 100644 --- a/Marlin/src/HAL/HAL_LPC1768/arduino.cpp +++ b/Marlin/src/HAL/HAL_LPC1768/arduino.cpp @@ -136,7 +136,7 @@ void analogWrite(pin_t pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255 digitalWrite(pin, value); } else { - if (LPC1768_PWM_attach_pin(pin, 1, LPC_PWM1->MR0, 0xff)) + if (LPC1768_PWM_attach_pin(pin, 1, LPC_PWM1->MR0, 0xFF)) LPC1768_PWM_write(pin, map(value, 0, 255, 1, LPC_PWM1->MR0)); // map 1-254 onto PWM range else { // out of PWM channels if (!out_of_PWM_slots) MYSERIAL.printf(".\nWARNING - OUT OF PWM CHANNELS\n.\n"); //only warn once diff --git a/Marlin/src/HAL/HAL_LPC1768/pinmapping.h b/Marlin/src/HAL/HAL_LPC1768/pinmapping.h index 3e9c9701c9..622baaa7c4 100644 --- a/Marlin/src/HAL/HAL_LPC1768/pinmapping.h +++ b/Marlin/src/HAL/HAL_LPC1768/pinmapping.h @@ -253,7 +253,7 @@ constexpr pin_t adc_pin_table[] = { #else #define NUM_ANALOG_INPUTS 6 #endif - + // P0.6 thru P0.9 are for the onboard SD card // P0.29 and P0.30 are for the USB port #define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09, P0_29, P0_30 diff --git a/Marlin/src/HAL/HAL_STM32F1/HAL_spi_Stm32f1.cpp b/Marlin/src/HAL/HAL_STM32F1/HAL_spi_Stm32f1.cpp index 650938c136..c38cee2e9a 100644 --- a/Marlin/src/HAL/HAL_STM32F1/HAL_spi_Stm32f1.cpp +++ b/Marlin/src/HAL/HAL_STM32F1/HAL_spi_Stm32f1.cpp @@ -167,9 +167,9 @@ void spiSendBlock(uint8_t token, const uint8_t* buf) { /** 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); - + SPI.beginTransaction(spiConfig); -} +} #endif // SOFTWARE_SPI diff --git a/Marlin/src/HAL/HAL_TEENSY35_36/HAL_spi_Teensy.cpp b/Marlin/src/HAL/HAL_TEENSY35_36/HAL_spi_Teensy.cpp index 25b3dc9355..e50e42556e 100644 --- a/Marlin/src/HAL/HAL_TEENSY35_36/HAL_spi_Teensy.cpp +++ b/Marlin/src/HAL/HAL_TEENSY35_36/HAL_spi_Teensy.cpp @@ -105,8 +105,7 @@ void spiSendBlock(uint8_t token, const uint8_t* buf) { void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { spiConfig = SPISettings(spiClock, bitOrder, dataMode); - SPI.beginTransaction(spiConfig); -} - + SPI.beginTransaction(spiConfig); +} -#endif +#endif // __MK64FX512__ || __MK66FX1M0__ diff --git a/Marlin/src/gcode/config/M43.cpp b/Marlin/src/gcode/config/M43.cpp index efbef5d1e6..d9e78baa45 100644 --- a/Marlin/src/gcode/config/M43.cpp +++ b/Marlin/src/gcode/config/M43.cpp @@ -270,7 +270,7 @@ void GcodeSuite::M43() { // Watch until click, M108, or reset if (parser.boolval('W')) { SERIAL_PROTOCOLLNPGM("Watching pins"); - + #ifdef ARDUINO_ARCH_SAM NOLESS(first_pin, 2); // don't hijack the UART pins #endif diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 35c381b032..ee7e1126f8 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -56,7 +56,7 @@ #define ENCODER_FEEDRATE_DEADZONE 2 #define REVERSE_MENU_DIRECTION -#elif ENABLED(RADDS_DISPLAY) +#elif ENABLED(RADDS_DISPLAY) #define ULTIPANEL #define ENCODER_PULSES_PER_STEP 2 diff --git a/Marlin/src/lcd/ultralcd_impl_DOGM.h b/Marlin/src/lcd/ultralcd_impl_DOGM.h index cf1719297f..57f9ab1ae0 100644 --- a/Marlin/src/lcd/ultralcd_impl_DOGM.h +++ b/Marlin/src/lcd/ultralcd_impl_DOGM.h @@ -187,7 +187,7 @@ // Based on the Adafruit ST7565 (http://www.adafruit.com/products/250) //U8GLIB_LM6059 u8g(DOGLCD_CS, DOGLCD_A0); // 8 stripes U8GLIB_LM6059_2X u8g(DOGLCD_CS, DOGLCD_A0); // 4 stripes - + #elif ENABLED(U8GLIB_ST7565_64128N) // The MaKrPanel, Mini Viki, and Viki 2.0, ST7565 controller //U8GLIB_64128N_2X_HAL u8g(DOGLCD_CS, DOGLCD_A0); // using HW-SPI diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 5b986e9e41..f872dd2cb1 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -2079,7 +2079,7 @@ void MarlinSettings::reset() { CONFIG_ECHO_START; #if ENABLED(SKEW_CORRECTION_FOR_Z) SERIAL_ECHO(" M852 I"); - SERIAL_ECHO_F(LINEAR_UNIT(planner.xy_skew_factor),6); + SERIAL_ECHO_F(LINEAR_UNIT(planner.xy_skew_factor), 6); SERIAL_ECHOPAIR(" J", LINEAR_UNIT(planner.xz_skew_factor)); SERIAL_ECHOLNPAIR(" K", LINEAR_UNIT(planner.yz_skew_factor)); #else diff --git a/Marlin/src/pins/pins_CHEAPTRONICv2.h b/Marlin/src/pins/pins_CHEAPTRONICv2.h index 6c0d3a58f9..327883898a 100644 --- a/Marlin/src/pins/pins_CHEAPTRONICv2.h +++ b/Marlin/src/pins/pins_CHEAPTRONICv2.h @@ -110,7 +110,7 @@ // Other board specific pins // #define FIL_RUNOUT_PIN 37 // board input labeled as F-DET -#define Z_MIN_PROBE_PIN 36 // additional external board input labeled as E-SENS (should be used for Z-probe) +#define Z_MIN_PROBE_PIN 36 // additional external board input labeled as E-SENS (should be used for Z-probe) #define LED_PIN 13 #define SPINDLE_ENABLE_PIN 4 // additional PWM pin 1 at JP1 connector - should be used for laser control too #define EXT_2 5 // additional PWM pin 2 at JP1 connector diff --git a/Marlin/src/pins/pins_MKS_BASE.h b/Marlin/src/pins/pins_MKS_BASE.h index 60f9678aac..6c6e11496b 100644 --- a/Marlin/src/pins/pins_MKS_BASE.h +++ b/Marlin/src/pins/pins_MKS_BASE.h @@ -40,7 +40,7 @@ // XSTEP,YSTEP ... must be adapted with M92 accordingly (128/16 => multiply by factor 8). */ #define X_MS1_PIN 5 // Digital 3 / Pin 5 / PE3 -#define X_MS2_PIN 6 // Digital 6 / Pin 14 / PH3 +#define X_MS2_PIN 6 // Digital 6 / Pin 14 / PH3 #define Y_MS1_PIN 59 // Analog 5 / Pin 92 / PF5 #define Y_MS2_PIN 58 // Analog 4 / Pin 93 / PF4 #define Z_MS1_PIN 22 // Digital 22 / Pin 78 / PA0