✨ SAMD21 HAL / Minitronics v2.0 (#24976)
This commit is contained in:
		
				
					committed by
					
						 Scott Lahteine
						Scott Lahteine
					
				
			
			
				
	
			
			
			
						parent
						
							ec6349f2ac
						
					
				
				
					commit
					ac05f0cb8b
				
			| @@ -2741,7 +2741,7 @@ | |||||||
|  |  | ||||||
| // | // | ||||||
| // ReprapWorld Graphical LCD | // ReprapWorld Graphical LCD | ||||||
| // https://reprapworld.com/?products_details&products_id/1218 | // https://reprapworld.com/electronics/3d-printer-modules/autonomous-printing/graphical-lcd-screen-v1-0/ | ||||||
| // | // | ||||||
| //#define REPRAPWORLD_GRAPHICAL_LCD | //#define REPRAPWORLD_GRAPHICAL_LCD | ||||||
|  |  | ||||||
|   | |||||||
| @@ -168,4 +168,4 @@ uint8_t u8g_com_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void | |||||||
| #endif | #endif | ||||||
|  |  | ||||||
| #endif // IS_U8GLIB_ST7920 | #endif // IS_U8GLIB_ST7920 | ||||||
| #endif // TARGET_LPC1768 | #endif // __PLAT_NATIVE_SIM__ | ||||||
|   | |||||||
							
								
								
									
										212
									
								
								Marlin/src/HAL/SAMD21/HAL.cpp
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										212
									
								
								Marlin/src/HAL/SAMD21/HAL.cpp
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,212 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  | #ifdef __SAMD21__ | ||||||
|  |  | ||||||
|  | #include "../../inc/MarlinConfig.h" | ||||||
|  |  | ||||||
|  | #include <wiring_private.h> | ||||||
|  |  | ||||||
|  | #if USING_HW_SERIALUSB | ||||||
|  |   DefaultSerial1 MSerialUSB(false, SerialUSB); | ||||||
|  | #endif | ||||||
|  | #if USING_HW_SERIAL0 | ||||||
|  |   DefaultSerial2 MSerial1(false, Serial1); | ||||||
|  | #endif | ||||||
|  | #if USING_HW_SERIAL1 | ||||||
|  |   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) | ||||||
|  |  | ||||||
|  | #if ENABLED(USE_WATCHDOG) | ||||||
|  |  | ||||||
|  |   #define WDT_TIMEOUT_REG TERN(WATCHDOG_DURATION_8S, WDT_CONFIG_PER_CYC8192, WDT_CONFIG_PER_CYC4096) // 4 or 8 second timeout | ||||||
|  |  | ||||||
|  |   void MarlinHAL::watchdog_init() { | ||||||
|  |        // Set up the generic clock (GCLK2) used to clock the watchdog timer at 1.024kHz | ||||||
|  |     GCLK->GENDIV.reg = GCLK_GENDIV_DIV(4) |            // Divide the 32.768kHz clock source by divisor 32, where 2^(4 + 1): 32.768kHz/32=1.024kHz | ||||||
|  |                       GCLK_GENDIV_ID(2);              // Select Generic Clock (GCLK) 2 | ||||||
|  |     while (GCLK->STATUS.bit.SYNCBUSY);                // Wait for synchronization | ||||||
|  |  | ||||||
|  |     REG_GCLK_GENCTRL =  GCLK_GENCTRL_DIVSEL |         // Set to divide by 2^(GCLK_GENDIV_DIV(4) + 1) | ||||||
|  |                         GCLK_GENCTRL_IDC |            // Set the duty cycle to 50/50 HIGH/LOW | ||||||
|  |                         GCLK_GENCTRL_GENEN |          // Enable GCLK2 | ||||||
|  |                         GCLK_GENCTRL_SRC_OSCULP32K |  // Set the clock source to the ultra low power oscillator (OSCULP32K) | ||||||
|  |                         GCLK_GENCTRL_ID(2);           // Select GCLK2 | ||||||
|  |     while (GCLK->STATUS.bit.SYNCBUSY);                // Wait for synchronization | ||||||
|  |  | ||||||
|  |     // Feed GCLK2 to WDT (Watchdog Timer) | ||||||
|  |     REG_GCLK_CLKCTRL =  GCLK_CLKCTRL_CLKEN |          // Enable GCLK2 to the WDT | ||||||
|  |                         GCLK_CLKCTRL_GEN_GCLK2 |      // Select GCLK2 | ||||||
|  |                         GCLK_CLKCTRL_ID_WDT;          // Feed the GCLK2 to the WDT | ||||||
|  |     while (GCLK->STATUS.bit.SYNCBUSY);                // Wait for synchronization | ||||||
|  |  | ||||||
|  |     WDT->CONFIG.bit.PER = WDT_CONFIG_PER_7;                // Set the WDT reset timeout to 4 seconds | ||||||
|  |     while (WDT->STATUS.bit.SYNCBUSY);                 // Wait for synchronization | ||||||
|  |     REG_WDT_CTRL = WDT_CTRL_ENABLE;                   // Enable the WDT in normal mode | ||||||
|  |     while (WDT->STATUS.bit.SYNCBUSY);                 // Wait for synchronization | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   // Reset watchdog. MUST be called at least every 4 seconds after the | ||||||
|  |   // first watchdog_init or SAMD will go into emergency procedures. | ||||||
|  |   void MarlinHAL::watchdog_refresh() { | ||||||
|  |     WDT->CLEAR.reg = WDT_CLEAR_CLEAR_KEY; | ||||||
|  |     while (WDT->STATUS.bit.SYNCBUSY); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | // ------------------------ | ||||||
|  | // Types | ||||||
|  | // ------------------------ | ||||||
|  |  | ||||||
|  | // ------------------------ | ||||||
|  | // Private Variables | ||||||
|  | // ------------------------ | ||||||
|  |  | ||||||
|  | // ------------------------ | ||||||
|  | // Private functions | ||||||
|  | // ------------------------ | ||||||
|  |  | ||||||
|  | void MarlinHAL::dma_init() {} | ||||||
|  |  | ||||||
|  | // ------------------------ | ||||||
|  | // Public functions | ||||||
|  | // ------------------------ | ||||||
|  |  | ||||||
|  | // HAL initialization task | ||||||
|  | void MarlinHAL::init() { | ||||||
|  |   TERN_(DMA_IS_REQUIRED, dma_init()); | ||||||
|  |   #if ENABLED(SDSUPPORT) | ||||||
|  |     #if HAS_SD_DETECT && SD_CONNECTION_IS(ONBOARD) | ||||||
|  |       SET_INPUT_PULLUP(SD_DETECT_PIN); | ||||||
|  |     #endif | ||||||
|  |     OUT_WRITE(SDSS, HIGH);  // Try to set SDSS inactive before any other SPI users start up | ||||||
|  |   #endif | ||||||
|  | } | ||||||
|  |  | ||||||
|  | #pragma push_macro("WDT") | ||||||
|  | #undef WDT    // Required to be able to use '.bit.WDT'. Compiler wrongly replace struct field with WDT define | ||||||
|  | uint8_t MarlinHAL::get_reset_source() { | ||||||
|  |  | ||||||
|  |   return 0; | ||||||
|  | } | ||||||
|  | #pragma pop_macro("WDT") | ||||||
|  |  | ||||||
|  | void MarlinHAL::reboot() { NVIC_SystemReset(); } | ||||||
|  |  | ||||||
|  | extern "C" { | ||||||
|  |   void * _sbrk(int incr); | ||||||
|  |   extern unsigned int __bss_end__; // end of bss section | ||||||
|  | } | ||||||
|  |  | ||||||
|  | // Return free memory between end of heap (or end bss) and whatever is current | ||||||
|  | int freeMemory() { | ||||||
|  |   int free_memory, heap_end = (int)_sbrk(0); | ||||||
|  |   return (int)&free_memory - (heap_end ?: (int)&__bss_end__); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | // ------------------------ | ||||||
|  | // ADC | ||||||
|  | // ------------------------ | ||||||
|  |  | ||||||
|  | uint16_t MarlinHAL::adc_result; | ||||||
|  |  | ||||||
|  | void MarlinHAL::adc_init() { | ||||||
|  |   /* thanks to https://www.eevblog.com/forum/microcontrollers/samd21g18-adc-with-resrdy-interrupts-only-reads-once-or-twice/ */ | ||||||
|  |  | ||||||
|  |   ADC->CTRLA.bit.ENABLE = false; | ||||||
|  |   while(ADC->STATUS.bit.SYNCBUSY); | ||||||
|  |  | ||||||
|  |   // load chip corrections | ||||||
|  |   uint32_t bias = (*((uint32_t *) ADC_FUSES_BIASCAL_ADDR) & ADC_FUSES_BIASCAL_Msk) >> ADC_FUSES_BIASCAL_Pos; | ||||||
|  |   uint32_t linearity = (*((uint32_t *) ADC_FUSES_LINEARITY_0_ADDR) & ADC_FUSES_LINEARITY_0_Msk) >> ADC_FUSES_LINEARITY_0_Pos; | ||||||
|  |   linearity |= ((*((uint32_t *) ADC_FUSES_LINEARITY_1_ADDR) & ADC_FUSES_LINEARITY_1_Msk) >> ADC_FUSES_LINEARITY_1_Pos) << 5; | ||||||
|  |  | ||||||
|  |   /* Wait for bus synchronization. */ | ||||||
|  |   while (ADC->STATUS.bit.SYNCBUSY) {}; | ||||||
|  |  | ||||||
|  |   ADC->CALIB.reg = ADC_CALIB_BIAS_CAL(bias) | ADC_CALIB_LINEARITY_CAL(linearity); | ||||||
|  |  | ||||||
|  |   /* Wait for bus synchronization. */ | ||||||
|  |   while (ADC->STATUS.bit.SYNCBUSY) {}; | ||||||
|  |  | ||||||
|  |   ADC->CTRLA.bit.SWRST = true; | ||||||
|  |   while(ADC->STATUS.bit.SYNCBUSY); | ||||||
|  |  | ||||||
|  |   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; | ||||||
|  |   while(ADC->STATUS.bit.SYNCBUSY); | ||||||
|  |  | ||||||
|  |   ADC->SAMPCTRL.bit.SAMPLEN = 0x00; | ||||||
|  |   while(ADC->STATUS.bit.SYNCBUSY); | ||||||
|  |  | ||||||
|  |   ADC->INPUTCTRL.reg =  ADC_INPUTCTRL_INPUTSCAN(HAL_ADC_AIN_LEN) // scan  (INPUTSCAN + NUM_EXTUDERS - 1) pins | ||||||
|  |   | ADC_INPUTCTRL_GAIN_DIV2  |ADC_INPUTCTRL_MUXNEG_GND| HAL_ADC_AIN_START ;  /* set to first AIN */ | ||||||
|  |  | ||||||
|  |   while(ADC->STATUS.bit.SYNCBUSY); | ||||||
|  |  | ||||||
|  |   ADC->INTENSET.reg |= ADC_INTENSET_RESRDY; // enable Result Ready ADC interrupts | ||||||
|  |   while (ADC->STATUS.bit.SYNCBUSY); | ||||||
|  |  | ||||||
|  |   NVIC_EnableIRQ(ADC_IRQn); // enable ADC interrupts | ||||||
|  |  | ||||||
|  |   NVIC_SetPriority(ADC_IRQn, 3); | ||||||
|  |  | ||||||
|  |   ADC->CTRLA.bit.ENABLE = true; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | volatile uint32_t adc_results[HAL_ADC_AIN_NUM_SENSORS]; | ||||||
|  |  | ||||||
|  | void ADC_Handler() { | ||||||
|  |   while(ADC->STATUS.bit.SYNCBUSY == 1); | ||||||
|  |   int pos = ADC->INPUTCTRL.bit.INPUTOFFSET; | ||||||
|  |  | ||||||
|  |   adc_results[pos] = ADC->RESULT.reg; /* Read the value. */ | ||||||
|  |   ADC->INTFLAG.reg = ADC_INTENSET_RESRDY; /* Clear the data ready flag. */ | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void MarlinHAL::adc_start(const pin_t pin) { | ||||||
|  |   /* due to the way INPUTOFFSET works, the last sensor is the first position in the array | ||||||
|  |     and we want the ADC_handler interrupt to be as simple possible, so we do the calculation here. | ||||||
|  |   */ | ||||||
|  |   unsigned int pos = PIN_TO_INPUTCTRL(pin) - HAL_ADC_AIN_START + 1; | ||||||
|  |   if (pos == HAL_ADC_AIN_NUM_SENSORS) pos = 0; | ||||||
|  |   adc_result = adc_results[pos]; // 16-bit resolution | ||||||
|  |   //adc_result = 0xFFFF; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | #endif // __SAMD21__ | ||||||
							
								
								
									
										223
									
								
								Marlin/src/HAL/SAMD21/HAL.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										223
									
								
								Marlin/src/HAL/SAMD21/HAL.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,223 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #define CPU_32_BIT | ||||||
|  |  | ||||||
|  | #include "../shared/Marduino.h" | ||||||
|  | #include "../shared/math_32bit.h" | ||||||
|  | #include "../shared/HAL_SPI.h" | ||||||
|  | #include "fastio.h" | ||||||
|  |  | ||||||
|  | // ------------------------ | ||||||
|  | // Serial ports | ||||||
|  | // ------------------------ | ||||||
|  | #include "../../core/serial_hook.h" | ||||||
|  | typedef ForwardSerial1Class< decltype(SerialUSB) > DefaultSerial1; | ||||||
|  | extern DefaultSerial1 MSerialUSB; | ||||||
|  |  | ||||||
|  | // Serial ports | ||||||
|  | typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2; | ||||||
|  | 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)) | ||||||
|  |  | ||||||
|  | #if WITHIN(SERIAL_PORT, 0, 1) | ||||||
|  |   #define MYSERIAL1 MSERIAL(SERIAL_PORT) | ||||||
|  | #elif SERIAL_PORT == -1 | ||||||
|  |   #define MYSERIAL1 MSerialUSB | ||||||
|  | #else | ||||||
|  |   #error "SERIAL_PORT must be -1 (Native USB only)." | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | #ifdef SERIAL_PORT_2 | ||||||
|  |   #if WITHIN(SERIAL_PORT_2, 0, 1) | ||||||
|  |     #define MYSERIAL2 MSERIAL(SERIAL_PORT) | ||||||
|  |   #elif SERIAL_PORT_2 == -1 | ||||||
|  |     #define MYSERIAL2 MSerialUSB | ||||||
|  |   #else | ||||||
|  |     #error "SERIAL_PORT_2 must be -1 (Native USB only)." | ||||||
|  |   #endif | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | #ifdef MMU2_SERIAL_PORT | ||||||
|  |   #if WITHIN(MMU2_SERIAL_PORT, 0, 1) | ||||||
|  |     #define MMU2_SERIAL MSERIAL(SERIAL_PORT) | ||||||
|  |   #elif MMU2_SERIAL_PORT == -1 | ||||||
|  |     #define MMU2_SERIAL MSerialUSB | ||||||
|  |   #else | ||||||
|  |     #error "MMU2_SERIAL_PORT must be -1 (Native USB only)." | ||||||
|  |   #endif | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | #ifdef LCD_SERIAL_PORT | ||||||
|  |   #if WITHIN(LCD_SERIAL_PORT, 0, 1) | ||||||
|  |     #define LCD_SERIAL MSERIAL(SERIAL_PORT) | ||||||
|  |   #elif LCD_SERIAL_PORT == -1 | ||||||
|  |     #define LCD_SERIAL MSerialUSB | ||||||
|  |   #else | ||||||
|  |     #error "LCD_SERIAL_PORT must be -1 (Native USB only)." | ||||||
|  |   #endif | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | typedef int8_t pin_t; | ||||||
|  |  | ||||||
|  | #define SHARED_SERVOS HAS_SERVOS  // Use shared/servos.cpp | ||||||
|  |  | ||||||
|  | class Servo; | ||||||
|  | typedef Servo hal_servo_t; | ||||||
|  |  | ||||||
|  | // | ||||||
|  | // Interrupts | ||||||
|  | // | ||||||
|  | #define CRITICAL_SECTION_START()  const bool irqon = !__get_PRIMASK(); __disable_irq() | ||||||
|  | #define CRITICAL_SECTION_END()    if (irqon) __enable_irq() | ||||||
|  |  | ||||||
|  | #define cli() __disable_irq() // Disable interrupts | ||||||
|  | #define sei() __enable_irq()  // Enable interrupts | ||||||
|  |  | ||||||
|  | // | ||||||
|  | // ADC | ||||||
|  | // | ||||||
|  |  | ||||||
|  | #define HAL_ADC_FILTERED     1     // Disable Marlin's oversampling. The HAL filters ADC values. | ||||||
|  | #define HAL_ADC_VREF         3.3 | ||||||
|  | #define HAL_ADC_RESOLUTION   12 | ||||||
|  | #define HAL_ADC_AIN_START ADC_INPUTCTRL_MUXPOS_PIN3 | ||||||
|  | #define HAL_ADC_AIN_NUM_SENSORS 3 | ||||||
|  | #define HAL_ADC_AIN_LEN HAL_ADC_AIN_NUM_SENSORS-1 | ||||||
|  |  | ||||||
|  | // | ||||||
|  | // Pin Mapping for M42, M43, M226 | ||||||
|  | // | ||||||
|  | #define GET_PIN_MAP_PIN(index) index | ||||||
|  | #define GET_PIN_MAP_INDEX(pin) pin | ||||||
|  | #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) | ||||||
|  |  | ||||||
|  | // | ||||||
|  | // Tone | ||||||
|  | // | ||||||
|  | void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0); | ||||||
|  | void noTone(const pin_t _pin); | ||||||
|  |  | ||||||
|  | // ------------------------ | ||||||
|  | // Class Utilities | ||||||
|  | // ------------------------ | ||||||
|  |  | ||||||
|  | #pragma GCC diagnostic push | ||||||
|  | #if GCC_VERSION <= 50000 | ||||||
|  |   #pragma GCC diagnostic ignored "-Wunused-function" | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | #ifdef __cplusplus | ||||||
|  |   extern "C" { | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s); | ||||||
|  |  | ||||||
|  | extern "C" int freeMemory(); | ||||||
|  |  | ||||||
|  | #ifdef __cplusplus | ||||||
|  |   } | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | #pragma GCC diagnostic pop | ||||||
|  |  | ||||||
|  | // ------------------------ | ||||||
|  | // MarlinHAL Class | ||||||
|  | // ------------------------ | ||||||
|  |  | ||||||
|  | class MarlinHAL { | ||||||
|  | public: | ||||||
|  |  | ||||||
|  |   // Earliest possible init, before setup() | ||||||
|  |   MarlinHAL() {} | ||||||
|  |  | ||||||
|  |   // Watchdog | ||||||
|  |   static void watchdog_init()    IF_DISABLED(USE_WATCHDOG, {}); | ||||||
|  |   static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {}); | ||||||
|  |  | ||||||
|  |   static void init();          // Called early in setup() | ||||||
|  |   static void init_board() {}  // Called less early in setup() | ||||||
|  |   static void reboot();        // Restart the firmware from 0x0 | ||||||
|  |  | ||||||
|  |   // Interrupts | ||||||
|  |   static bool isr_state() { return !__get_PRIMASK(); } | ||||||
|  |   static void isr_on()  { sei(); } | ||||||
|  |   static void isr_off() { cli(); } | ||||||
|  |  | ||||||
|  |   static void delay_ms(const int ms) { delay(ms); } | ||||||
|  |  | ||||||
|  |   // Tasks, called from idle() | ||||||
|  |   static void idletask() {} | ||||||
|  |  | ||||||
|  |   // Reset | ||||||
|  |   static uint8_t get_reset_source(); | ||||||
|  |   static void clear_reset_source() {} | ||||||
|  |  | ||||||
|  |   // Free SRAM | ||||||
|  |   static int freeMemory() { return ::freeMemory(); } | ||||||
|  |  | ||||||
|  |   // | ||||||
|  |   // ADC Methods | ||||||
|  |   // | ||||||
|  |  | ||||||
|  |   static uint16_t adc_result; | ||||||
|  |  | ||||||
|  |   // Called by Temperature::init once at startup | ||||||
|  |   static void adc_init(); | ||||||
|  |  | ||||||
|  |   // Called by Temperature::init for each sensor at startup | ||||||
|  |   static void adc_enable(const uint8_t ch) {} | ||||||
|  |  | ||||||
|  |   // Begin ADC sampling on the given pin. Called from Temperature::isr! | ||||||
|  |   static void adc_start(const pin_t pin); | ||||||
|  |  | ||||||
|  |   // Is the ADC ready for reading? | ||||||
|  |   static bool adc_ready() { return true; } | ||||||
|  |  | ||||||
|  |   // The current value of the ADC register | ||||||
|  |   static uint16_t adc_value() { return adc_result; } | ||||||
|  |  | ||||||
|  |   /** | ||||||
|  |    * Set the PWM duty cycle for the pin to the given value. | ||||||
|  |    * No option to invert the duty cycle [default = false] | ||||||
|  |    * No option to change the scale of the provided value to enable finer PWM duty control [default = 255] | ||||||
|  |    */ | ||||||
|  |   static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { | ||||||
|  |     analogWrite(pin, v); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  | private: | ||||||
|  |   static void dma_init(); | ||||||
|  | }; | ||||||
							
								
								
									
										148
									
								
								Marlin/src/HAL/SAMD21/HAL_SPI.cpp
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										148
									
								
								Marlin/src/HAL/SAMD21/HAL_SPI.cpp
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,148 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Hardware and software SPI implementations are included in this file. | ||||||
|  |  * | ||||||
|  |  * Control of the slave select pin(s) is handled by the calling routines and | ||||||
|  |  * SAMD21 let hardware SPI handling to remove SS from its logic. | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #ifdef __SAMD21__ | ||||||
|  |  | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  | // Includes | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  |  | ||||||
|  | #include "../../inc/MarlinConfig.h" | ||||||
|  | #include <SPI.h> | ||||||
|  |  | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  | // Public functions | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  |  | ||||||
|  | #if EITHER(SOFTWARE_SPI, FORCE_SOFT_SPI) | ||||||
|  |  | ||||||
|  |   // ------------------------ | ||||||
|  |   // Software SPI | ||||||
|  |   // ------------------------ | ||||||
|  |   #error "Software SPI not supported for SAMD21. Use Hardware SPI." | ||||||
|  |  | ||||||
|  | #else // !SOFTWARE_SPI | ||||||
|  |  | ||||||
|  |   static SPISettings spiConfig; | ||||||
|  |  | ||||||
|  |   // ------------------------ | ||||||
|  |   // Hardware SPI | ||||||
|  |   // ------------------------ | ||||||
|  |   void spiBegin() { | ||||||
|  |     spiInit(SPI_HALF_SPEED); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   void spiInit(uint8_t spiRate) { | ||||||
|  |     // Use datarates Marlin uses | ||||||
|  |     uint32_t clock; | ||||||
|  |     switch (spiRate) { | ||||||
|  |       case SPI_FULL_SPEED:      clock = 8000000; break; | ||||||
|  |       case SPI_HALF_SPEED:      clock = 4000000; break; | ||||||
|  |       case SPI_QUARTER_SPEED:   clock = 2000000; break; | ||||||
|  |       case SPI_EIGHTH_SPEED:    clock = 1000000; break; | ||||||
|  |       case SPI_SIXTEENTH_SPEED: clock =  500000; break; | ||||||
|  |       case SPI_SPEED_5:         clock =  250000; break; | ||||||
|  |       case SPI_SPEED_6:         clock =  125000; break; | ||||||
|  |       default:                  clock = 4000000; break; // Default from the SPI library | ||||||
|  |     } | ||||||
|  |     spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); | ||||||
|  |     SPI.begin(); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   /** | ||||||
|  |    * @brief  Receives a single byte from the SPI port. | ||||||
|  |    * | ||||||
|  |    * @return Byte received | ||||||
|  |    * | ||||||
|  |    * @details | ||||||
|  |    */ | ||||||
|  |   uint8_t spiRec() { | ||||||
|  |     SPI.beginTransaction(spiConfig); | ||||||
|  |     uint8_t returnByte = SPI.transfer(0xFF); | ||||||
|  |     SPI.endTransaction(); | ||||||
|  |     return returnByte; | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   /** | ||||||
|  |    * @brief  Receives a number of bytes from the SPI port to a buffer | ||||||
|  |    * | ||||||
|  |    * @param  buf   Pointer to starting address of buffer to write to. | ||||||
|  |    * @param  nbyte Number of bytes to receive. | ||||||
|  |    * @return Nothing | ||||||
|  |    */ | ||||||
|  |   void spiRead(uint8_t *buf, uint16_t nbyte) { | ||||||
|  |     if (nbyte == 0) return; | ||||||
|  |     memset(buf, 0xFF, nbyte); | ||||||
|  |  | ||||||
|  |     SPI.beginTransaction(spiConfig); | ||||||
|  |     SPI.transfer(buf, nbyte); | ||||||
|  |     SPI.endTransaction(); | ||||||
|  |  | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   /** | ||||||
|  |    * @brief  Sends a single byte on SPI port | ||||||
|  |    * | ||||||
|  |    * @param  b Byte to send | ||||||
|  |    * | ||||||
|  |    * @details | ||||||
|  |    */ | ||||||
|  |   void spiSend(uint8_t b) { | ||||||
|  |     SPI.beginTransaction(spiConfig); | ||||||
|  |     SPI.transfer(b); | ||||||
|  |     SPI.endTransaction(); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   /** | ||||||
|  |    * @brief  Write token and then write from 512 byte buffer to SPI (for SD card) | ||||||
|  |    * | ||||||
|  |    * @param  buf   Pointer with buffer start address | ||||||
|  |    * @return Nothing | ||||||
|  |    * | ||||||
|  |    * @details Uses DMA | ||||||
|  |    */ | ||||||
|  |   void spiSendBlock(uint8_t token, const uint8_t *buf) { | ||||||
|  |     SPI.beginTransaction(spiConfig); | ||||||
|  |     SPI.transfer(token); | ||||||
|  |     SPI.transfer((uint8_t*)buf, 512); | ||||||
|  |     SPI.endTransaction(); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { | ||||||
|  |     spiConfig = SPISettings(spiClock, (BitOrder)bitOrder, dataMode); | ||||||
|  |     SPI.beginTransaction(spiConfig); | ||||||
|  |   } | ||||||
|  | #endif // !SOFTWARE_SPI | ||||||
|  |  | ||||||
|  | #endif // __SAMD21__ | ||||||
							
								
								
									
										31
									
								
								Marlin/src/HAL/SAMD21/MarlinSPI.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										31
									
								
								Marlin/src/HAL/SAMD21/MarlinSPI.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,31 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
|  |  | ||||||
|  | #include <SPI.h> | ||||||
|  |  | ||||||
|  | using MarlinSPI = SPIClass; | ||||||
							
								
								
									
										82
									
								
								Marlin/src/HAL/SAMD21/QSPIFlash.cpp
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										82
									
								
								Marlin/src/HAL/SAMD21/QSPIFlash.cpp
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,82 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  | #include "../../inc/MarlinConfig.h" | ||||||
|  |  | ||||||
|  | #if ENABLED(QSPI_EEPROM) | ||||||
|  |  | ||||||
|  | #include "QSPIFlash.h" | ||||||
|  |  | ||||||
|  | #define INVALID_ADDR    0xFFFFFFFF | ||||||
|  | #define SECTOR_OF(a)    (a & ~(SFLASH_SECTOR_SIZE - 1)) | ||||||
|  | #define OFFSET_OF(a)    (a & (SFLASH_SECTOR_SIZE - 1)) | ||||||
|  |  | ||||||
|  | Adafruit_SPIFlashBase * QSPIFlash::_flashBase = nullptr; | ||||||
|  | uint8_t QSPIFlash::_buf[SFLASH_SECTOR_SIZE]; | ||||||
|  | uint32_t QSPIFlash::_addr = INVALID_ADDR; | ||||||
|  |  | ||||||
|  | void QSPIFlash::begin() { | ||||||
|  |   if (_flashBase) return; | ||||||
|  |  | ||||||
|  |   _flashBase = new Adafruit_SPIFlashBase(new Adafruit_FlashTransport_QSPI()); | ||||||
|  |   _flashBase->begin(nullptr); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | size_t QSPIFlash::size() { | ||||||
|  |   return _flashBase->size(); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | uint8_t QSPIFlash::readByte(const uint32_t address) { | ||||||
|  |   if (SECTOR_OF(address) == _addr) return _buf[OFFSET_OF(address)]; | ||||||
|  |  | ||||||
|  |   return _flashBase->read8(address); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void QSPIFlash::writeByte(const uint32_t address, const uint8_t value) { | ||||||
|  |   uint32_t const sector_addr = SECTOR_OF(address); | ||||||
|  |  | ||||||
|  |   // Page changes, flush old and update new cache | ||||||
|  |   if (sector_addr != _addr) { | ||||||
|  |     flush(); | ||||||
|  |     _addr = sector_addr; | ||||||
|  |  | ||||||
|  |     // read a whole page from flash | ||||||
|  |     _flashBase->readBuffer(sector_addr, _buf, SFLASH_SECTOR_SIZE); | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   _buf[OFFSET_OF(address)] = value; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void QSPIFlash::flush() { | ||||||
|  |   if (_addr == INVALID_ADDR) return; | ||||||
|  |  | ||||||
|  |   _flashBase->eraseSector(_addr / SFLASH_SECTOR_SIZE); | ||||||
|  |   _flashBase->writeBuffer(_addr, _buf, SFLASH_SECTOR_SIZE); | ||||||
|  |  | ||||||
|  |   _addr = INVALID_ADDR; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | #endif // QSPI_EEPROM | ||||||
							
								
								
									
										49
									
								
								Marlin/src/HAL/SAMD21/QSPIFlash.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										49
									
								
								Marlin/src/HAL/SAMD21/QSPIFlash.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,49 @@ | |||||||
|  | /** | ||||||
|  |  * @file QSPIFlash.h | ||||||
|  |  * | ||||||
|  |  * The MIT License (MIT) | ||||||
|  |  * | ||||||
|  |  * Copyright (c) 2019 Ha Thach and Dean Miller for Adafruit Industries LLC | ||||||
|  |  * | ||||||
|  |  * Permission is hereby granted, free of charge, to any person obtaining a copy | ||||||
|  |  * of this software and associated documentation files (the "Software"), to deal | ||||||
|  |  * in the Software without restriction, including without limitation the rights | ||||||
|  |  * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell | ||||||
|  |  * copies of the Software, and to permit persons to whom the Software is | ||||||
|  |  * furnished to do so, subject to the following conditions: | ||||||
|  |  * | ||||||
|  |  * The above copyright notice and this permission notice shall be included in | ||||||
|  |  * all copies or substantial portions of the Software. | ||||||
|  |  * | ||||||
|  |  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR | ||||||
|  |  * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, | ||||||
|  |  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE | ||||||
|  |  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER | ||||||
|  |  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, | ||||||
|  |  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN | ||||||
|  |  * THE SOFTWARE. | ||||||
|  |  * | ||||||
|  |  * Derived from Adafruit_SPIFlash class with no SdFat references | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
|  |  | ||||||
|  | #include <Adafruit_SPIFlashBase.h> | ||||||
|  |  | ||||||
|  | // This class extends Adafruit_SPIFlashBase by adding caching support. | ||||||
|  | // | ||||||
|  | // This class will use 4096 Bytes of RAM as a block cache. | ||||||
|  | class QSPIFlash { | ||||||
|  |   public: | ||||||
|  |     static void begin(); | ||||||
|  |     static size_t size(); | ||||||
|  |     static uint8_t readByte(const uint32_t address); | ||||||
|  |     static void writeByte(const uint32_t address, const uint8_t v); | ||||||
|  |     static void flush(); | ||||||
|  |  | ||||||
|  |   private: | ||||||
|  |     static Adafruit_SPIFlashBase * _flashBase; | ||||||
|  |     static uint8_t _buf[SFLASH_SECTOR_SIZE]; | ||||||
|  |     static uint32_t _addr; | ||||||
|  | }; | ||||||
|  |  | ||||||
|  | extern QSPIFlash qspi; | ||||||
							
								
								
									
										66
									
								
								Marlin/src/HAL/SAMD21/SAMD21.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										66
									
								
								Marlin/src/HAL/SAMD21/SAMD21.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,66 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #define SYNC(sc)    while (sc) {  \ | ||||||
|  |                       asm("");    \ | ||||||
|  |                     } | ||||||
|  |  | ||||||
|  | // Get SAMD port/pin from specified arduino pin | ||||||
|  | #define GET_SAMD_PORT(P)    _GET_SAMD_PORT(PIN_TO_SAMD_PIN(P)) | ||||||
|  | #define GET_SAMD_PIN(P)     _GET_SAMD_PIN(PIN_TO_SAMD_PIN(P)) | ||||||
|  |  | ||||||
|  | // Get external interrupt line associated to specified arduino pin | ||||||
|  | #define PIN_TO_EILINE(P)    _SAMDPORTPIN_TO_EILINE(GET_SAMD_PORT(P), GET_SAMD_PIN(P)) | ||||||
|  |  | ||||||
|  | // Get adc/ain associated to specified arduino pin | ||||||
|  | #define PIN_TO_ADC(P)       (ANAPIN_TO_ADCAIN(P) >> 8) | ||||||
|  |  | ||||||
|  | // Private defines | ||||||
|  | #define PIN_TO_SAMD_PIN(P)    DIO##P##_PIN | ||||||
|  |  | ||||||
|  | #define _GET_SAMD_PORT(P)     ((P) >> 5) | ||||||
|  | #define _GET_SAMD_PIN(P)      ((P) & 0x1F) | ||||||
|  |  | ||||||
|  | // Get external interrupt line | ||||||
|  | #define _SAMDPORTPIN_TO_EILINE(P,B)   ((P == 0 && WITHIN(B, 0, 31) && B != 26 && B != 28 && B != 29) ? (B) & 0xF    \ | ||||||
|  |                                        : (P == 1 && (WITHIN(B, 0, 25) || WITHIN(B, 30, 31))) ? (B) & 0xF                      \ | ||||||
|  |                                        : (P == 1 && WITHIN(B, 26, 29)) ? 12 + (B) - 26                                        \ | ||||||
|  |                                        : (P == 2 && (WITHIN(B, 0, 6) || WITHIN(B, 10, 31)) && B != 29) ? (B) & 0xF            \ | ||||||
|  |                                        : (P == 2 && B == 7) ? 9                                                               \ | ||||||
|  |                                        : (P == 3 && WITHIN(B, 0, 1)) ? (B)                                                    \ | ||||||
|  |                                        : (P == 3 && WITHIN(B, 8, 12)) ? 3 + (B) - 8                                           \ | ||||||
|  |                                        : (P == 3 && WITHIN(B, 20, 21)) ? 10 + (B) - 20                                        \ | ||||||
|  |                                        : -1) | ||||||
|  |  | ||||||
|  |  | ||||||
|  |  | ||||||
|  | #define A2_AIN 3 | ||||||
|  | #define A3_AIN 4 | ||||||
|  | #define A4_AIN 5 | ||||||
|  | #define PIN_TO_AIN(P)    A##P##_AIN | ||||||
|  | #define AIN_TO_RESULT(P) ( (P - HAL_ADC_AIN_START == HAL_ADC_AIN_NUM_SENSORS-1) ? 0 :  (P - HAL_ADC_AIN_START + 1) ) | ||||||
							
								
								
									
										220
									
								
								Marlin/src/HAL/SAMD21/Servo.cpp
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										220
									
								
								Marlin/src/HAL/SAMD21/Servo.cpp
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,220 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * This comes from Arduino library which at the moment is buggy and uncompilable | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #ifdef __SAMD21__ | ||||||
|  |  | ||||||
|  | #include "../../inc/MarlinConfig.h" | ||||||
|  |  | ||||||
|  | #if HAS_SERVOS | ||||||
|  |  | ||||||
|  | #include "../shared/servo.h" | ||||||
|  | #include "../shared/servo_private.h" | ||||||
|  | #include "SAMD21.h" | ||||||
|  |  | ||||||
|  | #define __TC_GCLK_ID(t)         TC##t##_GCLK_ID | ||||||
|  | #define _TC_GCLK_ID(t)          __TC_GCLK_ID(t) | ||||||
|  | #define TC_GCLK_ID              _TC_GCLK_ID(SERVO_TC) | ||||||
|  |  | ||||||
|  | #define _TC_PRESCALER(d)        TC_CTRLA_PRESCALER_DIV##d##_Val | ||||||
|  | #define TC_PRESCALER(d)         _TC_PRESCALER(d) | ||||||
|  |  | ||||||
|  | #define __SERVO_IRQn(t)         TC##t##_IRQn | ||||||
|  | #define _SERVO_IRQn(t)          __SERVO_IRQn(t) | ||||||
|  | #define SERVO_IRQn              _SERVO_IRQn(SERVO_TC) | ||||||
|  |  | ||||||
|  | #define HAL_SERVO_TIMER_ISR()   TC_HANDLER(SERVO_TC) | ||||||
|  |  | ||||||
|  | #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() { | ||||||
|  |   Tcc * const tc = timer_config[SERVO_TC].pTcc; | ||||||
|  |  | ||||||
|  |   tc->CTRLBSET.reg = TCC_CTRLBCLR_CMD_READSYNC; | ||||||
|  |   SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY); | ||||||
|  |  | ||||||
|  |   return tc->COUNT.bit.COUNT; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | // ---------------------------- | ||||||
|  | // Interrupt handler for the TC | ||||||
|  | // ---------------------------- | ||||||
|  | HAL_SERVO_TIMER_ISR() { | ||||||
|  |   Tcc * const tc = timer_config[SERVO_TC].pTcc; | ||||||
|  |   const timer16_Sequence_t timer = | ||||||
|  |     #ifndef _useTimer1 | ||||||
|  |       _timer2 | ||||||
|  |     #elif !defined(_useTimer2) | ||||||
|  |       _timer1 | ||||||
|  |     #else | ||||||
|  |       (tc->INTFLAG.reg & tc->INTENSET.reg & TC_INTFLAG_MC0) ? _timer1 : _timer2 | ||||||
|  |     #endif | ||||||
|  |   ; | ||||||
|  |   const uint8_t tcChannel = TIMER_TCCHANNEL(timer); | ||||||
|  |  | ||||||
|  |   int8_t cho = currentServoIndex[timer];                // Handle the prior servo first | ||||||
|  |   if (cho < 0) {                                        // Servo -1 indicates the refresh interval completed... | ||||||
|  |     #if defined(_useTimer1) && defined(_useTimer2) | ||||||
|  |       if (currentServoIndex[timer ^ 1] >= 0) { | ||||||
|  |         // Wait for both channels | ||||||
|  |         // Clear the interrupt | ||||||
|  |         tc->INTFLAG.reg = (tcChannel == 0) ? TC_INTFLAG_MC0 : TC_INTFLAG_MC1; | ||||||
|  |         return; | ||||||
|  |       } | ||||||
|  |     #endif | ||||||
|  |     tc->COUNT.reg = TC_COUNTER_START_VAL;       // ...so reset the timer | ||||||
|  |     SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY); | ||||||
|  |   } | ||||||
|  |   else if (SERVO_INDEX(timer, cho) < ServoCount)        // prior channel handled? | ||||||
|  |     digitalWrite(SERVO(timer, cho).Pin.nbr, LOW);       // pulse the prior channel LOW | ||||||
|  |  | ||||||
|  |   currentServoIndex[timer] = ++cho;                     // go to the next channel (or 0) | ||||||
|  |   if (cho < SERVOS_PER_TIMER && SERVO_INDEX(timer, cho) < ServoCount) { | ||||||
|  |     if (SERVO(timer, cho).Pin.isActive)                 // activated? | ||||||
|  |       digitalWrite(SERVO(timer, cho).Pin.nbr, HIGH);    // yes: pulse HIGH | ||||||
|  |  | ||||||
|  |     tc->CC[tcChannel].reg = getTimerCount() - (uint16_t)SERVO(timer, cho).ticks; | ||||||
|  |   } | ||||||
|  |   else { | ||||||
|  |     // finished all channels so wait for the refresh period to expire before starting over | ||||||
|  |     currentServoIndex[timer] = -1;                                          // reset the timer COUNT.reg on the next call | ||||||
|  |     const uint16_t cval = getTimerCount() - 256 / (SERVO_TIMER_PRESCALER),  // allow 256 cycles to ensure the next CV not missed | ||||||
|  |                    ival = (TC_COUNTER_START_VAL) - (uint16_t)usToTicks(REFRESH_INTERVAL); // at least REFRESH_INTERVAL has elapsed | ||||||
|  |     tc->CC[tcChannel].reg = min(cval, ival); | ||||||
|  |   } | ||||||
|  |   if (tcChannel == 0) { | ||||||
|  |     SYNC(tc->SYNCBUSY.bit.CC0); | ||||||
|  |     tc->INTFLAG.reg = TC_INTFLAG_MC0; // Clear the interrupt | ||||||
|  |   } | ||||||
|  |   else { | ||||||
|  |     SYNC(tc->SYNCBUSY.bit.CC1); | ||||||
|  |     tc->INTFLAG.reg = TC_INTFLAG_MC1; // Clear the interrupt | ||||||
|  |   } | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void initISR(const timer16_Sequence_t timer) { | ||||||
|  |   Tcc * const tc = timer_config[SERVO_TC].pTcc; | ||||||
|  |   const uint8_t tcChannel = TIMER_TCCHANNEL(timer); | ||||||
|  |  | ||||||
|  |   static bool initialized = false;  // Servo TC has been initialized | ||||||
|  |   if (!initialized) { | ||||||
|  |     NVIC_DisableIRQ(SERVO_IRQn); | ||||||
|  |  | ||||||
|  |     // Disable the timer | ||||||
|  |     tc->CTRLA.bit.ENABLE = false; | ||||||
|  |     SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY); | ||||||
|  |  | ||||||
|  |     // Select GCLK0 as timer/counter input clock source | ||||||
|  |     GCLK->CLKCTRL.reg =(GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(TCC0_GCLK_ID)); | ||||||
|  |     SYNC (GCLK->STATUS.bit.SYNCBUSY); | ||||||
|  |  | ||||||
|  |     // Reset the timer | ||||||
|  |     tc->CTRLA.bit.SWRST = true; | ||||||
|  |     SYNC(tc->CTRLA.bit.SWRST); | ||||||
|  |  | ||||||
|  |     // Set timer counter mode to 16 bits | ||||||
|  |     tc->CTRLA.reg = TC_CTRLA_MODE_COUNT16; | ||||||
|  |  | ||||||
|  |     // Set timer counter mode as normal PWM | ||||||
|  |     tc->WAVE.bit.WAVEGEN = TCC_WAVE_WAVEGEN_NPWM_Val; | ||||||
|  |  | ||||||
|  |     // Set the prescaler factor | ||||||
|  |     tc->CTRLA.bit.PRESCALER = TC_PRESCALER(SERVO_TIMER_PRESCALER); | ||||||
|  |  | ||||||
|  |     // Count down | ||||||
|  |     tc->CTRLBSET.reg = TCC_CTRLBCLR_DIR; | ||||||
|  |     SYNC(tc->SYNCBUSY.bit.CTRLB); | ||||||
|  |  | ||||||
|  |     // Reset all servo indexes | ||||||
|  |     memset((void *)currentServoIndex, 0xFF, sizeof(currentServoIndex)); | ||||||
|  |  | ||||||
|  |     // Configure interrupt request | ||||||
|  |     NVIC_ClearPendingIRQ(SERVO_IRQn); | ||||||
|  |     NVIC_SetPriority(SERVO_IRQn, 5); | ||||||
|  |     NVIC_EnableIRQ(SERVO_IRQn); | ||||||
|  |  | ||||||
|  |     initialized = true; | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   if (!tc->CTRLA.bit.ENABLE) { | ||||||
|  |     // Reset the timer counter | ||||||
|  |     tc->COUNT.reg = TC_COUNTER_START_VAL; | ||||||
|  |     SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY); | ||||||
|  |  | ||||||
|  |     // Enable the timer and start it | ||||||
|  |     tc->CTRLA.bit.ENABLE = true; | ||||||
|  |     SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY); | ||||||
|  |   } | ||||||
|  |   // First interrupt request after 1 ms | ||||||
|  |   tc->CC[tcChannel].reg = getTimerCount() - (uint16_t)usToTicks(1000UL); | ||||||
|  |  | ||||||
|  |   if (tcChannel == 0 ) { | ||||||
|  |     SYNC(tc->SYNCBUSY.bit.CC0); | ||||||
|  |  | ||||||
|  |     // Clear pending match interrupt | ||||||
|  |     tc->INTFLAG.reg = TC_INTENSET_MC0; | ||||||
|  |     // Enable the match channel interrupt request | ||||||
|  |     tc->INTENSET.reg = TC_INTENSET_MC0; | ||||||
|  |   } | ||||||
|  |   else { | ||||||
|  |     SYNC(tc->SYNCBUSY.bit.CC1); | ||||||
|  |  | ||||||
|  |     // Clear pending match interrupt | ||||||
|  |     tc->INTFLAG.reg = TC_INTENSET_MC1; | ||||||
|  |     // Enable the match channel interrupt request | ||||||
|  |     tc->INTENSET.reg = TC_INTENSET_MC1; | ||||||
|  |   } | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void finISR(const timer16_Sequence_t timer_index) { | ||||||
|  |   Tcc * const tc = timer_config[SERVO_TC].pTcc; | ||||||
|  |   const uint8_t tcChannel = TIMER_TCCHANNEL(timer_index); | ||||||
|  |  | ||||||
|  |   // Disable the match channel interrupt request | ||||||
|  |   tc->INTENCLR.reg = (tcChannel == 0) ? TC_INTENCLR_MC0 : TC_INTENCLR_MC1; | ||||||
|  |  | ||||||
|  |   if (true | ||||||
|  |     #if defined(_useTimer1) && defined(_useTimer2) | ||||||
|  |       && (tc->INTENCLR.reg & (TC_INTENCLR_MC0|TC_INTENCLR_MC1)) == 0 | ||||||
|  |     #endif | ||||||
|  |   ) { | ||||||
|  |     // Disable the timer if not used | ||||||
|  |     tc->CTRLA.bit.ENABLE = false; | ||||||
|  |     SYNC(tc->STATUS.reg & TC_STATUS_SYNCBUSY); | ||||||
|  |   } | ||||||
|  | } | ||||||
|  |  | ||||||
|  | #endif // HAS_SERVOS | ||||||
|  |  | ||||||
|  | #endif // __SAMD21__ | ||||||
							
								
								
									
										45
									
								
								Marlin/src/HAL/SAMD21/ServoTimers.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										45
									
								
								Marlin/src/HAL/SAMD21/ServoTimers.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,45 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #define _useTimer1 | ||||||
|  | #define _useTimer2 | ||||||
|  |  | ||||||
|  | #define TRIM_DURATION           5   // compensation ticks to trim adjust for digitalWrite delays | ||||||
|  | #define SERVO_TIMER_PRESCALER   64  // timer prescaler factor to 64 (avoid overflowing 16-bit clock counter, at 120MHz this is 1831 ticks per millisecond | ||||||
|  |  | ||||||
|  | #define SERVO_TC                3 | ||||||
|  |  | ||||||
|  | typedef enum { | ||||||
|  |   #ifdef _useTimer1 | ||||||
|  |     _timer1, | ||||||
|  |   #endif | ||||||
|  |   #ifdef _useTimer2 | ||||||
|  |     _timer2, | ||||||
|  |   #endif | ||||||
|  |   _Nbr_16timers | ||||||
|  | } timer16_Sequence_t; | ||||||
							
								
								
									
										141
									
								
								Marlin/src/HAL/SAMD21/eeprom_flash.cpp
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										141
									
								
								Marlin/src/HAL/SAMD21/eeprom_flash.cpp
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,141 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  | #ifdef __SAMD21__ | ||||||
|  |  | ||||||
|  | #include "../../inc/MarlinConfig.h" | ||||||
|  |  | ||||||
|  | #if ENABLED(FLASH_EEPROM_EMULATION) | ||||||
|  |  | ||||||
|  | #define TOTAL_FLASH_SIZE (MARLIN_EEPROM_SIZE+255)/256*256 | ||||||
|  |  | ||||||
|  | /* reserve flash memory */ | ||||||
|  | static const uint8_t flashdata[TOTAL_FLASH_SIZE]  __attribute__((__aligned__(256))) { }; \ | ||||||
|  |  | ||||||
|  | #include "../shared/eeprom_api.h" | ||||||
|  |  | ||||||
|  | size_t PersistentStore::capacity() { | ||||||
|  |   return MARLIN_EEPROM_SIZE; | ||||||
|  |  /* const uint8_t psz = NVMCTRL->SEESTAT.bit.PSZ, | ||||||
|  |                 sblk = NVMCTRL->SEESTAT.bit.SBLK; | ||||||
|  |  | ||||||
|  |   return   (!psz && !sblk)         ? 0 | ||||||
|  |          : (psz <= 2)              ? (0x200 << psz) | ||||||
|  |          : (sblk == 1 || psz == 3) ?  4096 | ||||||
|  |          : (sblk == 2 || psz == 4) ?  8192 | ||||||
|  |          : (sblk <= 4 || psz == 5) ? 16384 | ||||||
|  |          : (sblk >= 9 && psz == 7) ? 65536 | ||||||
|  |                                    : 32768;*/ | ||||||
|  | } | ||||||
|  |  | ||||||
|  | uint32_t PAGE_SIZE; | ||||||
|  | uint32_t ROW_SIZE; | ||||||
|  | bool hasWritten = false; | ||||||
|  | uint8_t * buffer; | ||||||
|  |  | ||||||
|  | void _erase(const volatile void *flash_ptr) { | ||||||
|  |   NVMCTRL->ADDR.reg = ((uint32_t)flash_ptr) / 2; | ||||||
|  |   NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_ER; | ||||||
|  |   while (!NVMCTRL->INTFLAG.bit.READY) { } | ||||||
|  |  | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void erase(const volatile void *flash_ptr, uint32_t size) { | ||||||
|  |   const uint8_t *ptr = (const uint8_t *)flash_ptr; | ||||||
|  |   while (size > ROW_SIZE) { | ||||||
|  |     _erase(ptr); | ||||||
|  |     ptr += ROW_SIZE; | ||||||
|  |     size -= ROW_SIZE; | ||||||
|  |   } | ||||||
|  |   _erase(ptr); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | bool PersistentStore::access_start() { | ||||||
|  |   /* clear page buffer*/ | ||||||
|  |   NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_PBC; | ||||||
|  |   while (NVMCTRL->INTFLAG.bit.READY == 0) { } | ||||||
|  |  | ||||||
|  |   PAGE_SIZE =  pow(2,3 + NVMCTRL->PARAM.bit.PSZ); | ||||||
|  |   ROW_SIZE= PAGE_SIZE * 4; | ||||||
|  |   /*NVMCTRL->SEECFG.reg = NVMCTRL_SEECFG_WMODE_BUFFERED;  // Buffered mode and segment reallocation active | ||||||
|  |   if (NVMCTRL->SEESTAT.bit.RLOCK) | ||||||
|  |     NVMCTRL_CMD(NVMCTRL_CTRLB_CMD_USEE);  */  // Unlock E2P data write access | ||||||
|  |   //   erase(&flashdata[0], TOTAL_FLASH_SIZE); | ||||||
|  |   return true; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | bool PersistentStore::access_finish() { | ||||||
|  |   if (hasWritten) { | ||||||
|  |     erase(&flashdata[0], TOTAL_FLASH_SIZE); | ||||||
|  |  | ||||||
|  |     NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_PBC; | ||||||
|  |     while (NVMCTRL->INTFLAG.bit.READY == 0) { } | ||||||
|  |  | ||||||
|  |      NVMCTRL->CTRLB.bit.MANW = 0; | ||||||
|  |  | ||||||
|  |     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) { | ||||||
|  |  | ||||||
|  |       *dst_addr = (uint32_t) *pointer; | ||||||
|  |       pointer++; | ||||||
|  |       dst_addr ++; | ||||||
|  |     } | ||||||
|  |  | ||||||
|  |     // Execute "WP" Write Page | ||||||
|  |     NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_WP; | ||||||
|  |     while (NVMCTRL->INTFLAG.bit.READY == 0) { } | ||||||
|  |  | ||||||
|  |     free(buffer); | ||||||
|  |     hasWritten = false; | ||||||
|  |   } | ||||||
|  |   return true; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { | ||||||
|  |   if (!hasWritten) { | ||||||
|  |     // init temp buffer | ||||||
|  |     buffer = (uint8_t *) malloc(MARLIN_EEPROM_SIZE); | ||||||
|  |     hasWritten=true; | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   memcpy(buffer+pos,value,size); | ||||||
|  |   pos += size; | ||||||
|  |   return false; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { | ||||||
|  |   volatile uint8_t *dst_addr =  (volatile uint8_t *) &flashdata; | ||||||
|  |   dst_addr += pos; | ||||||
|  |  | ||||||
|  |   memcpy(value,(const void *) dst_addr,size); | ||||||
|  |   pos += size; | ||||||
|  |   return false; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | #endif // FLASH_EEPROM_EMULATION | ||||||
|  | #endif // __SAMD21__ | ||||||
							
								
								
									
										79
									
								
								Marlin/src/HAL/SAMD21/eeprom_qspi.cpp
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										79
									
								
								Marlin/src/HAL/SAMD21/eeprom_qspi.cpp
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,79 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  | #ifdef __SAMD21__ | ||||||
|  |  | ||||||
|  | #include "../../inc/MarlinConfig.h" | ||||||
|  |  | ||||||
|  | #if ENABLED(QSPI_EEPROM) | ||||||
|  |  | ||||||
|  | #error "QSPI_EEPROM emulation Not implemented on SAMD21" | ||||||
|  |  | ||||||
|  | #include "../shared/eeprom_api.h" | ||||||
|  |  | ||||||
|  | #include "QSPIFlash.h" | ||||||
|  |  | ||||||
|  | static bool initialized; | ||||||
|  |  | ||||||
|  | size_t PersistentStore::capacity() { return qspi.size(); } | ||||||
|  |  | ||||||
|  | bool PersistentStore::access_start() { | ||||||
|  |   if (!initialized) { | ||||||
|  |     qspi.begin(); | ||||||
|  |     initialized = true; | ||||||
|  |   } | ||||||
|  |   return true; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | bool PersistentStore::access_finish() { | ||||||
|  |   qspi.flush(); | ||||||
|  |   return true; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { | ||||||
|  |   while (size--) { | ||||||
|  |     const uint8_t v = *value; | ||||||
|  |     qspi.writeByte(pos, v); | ||||||
|  |     crc16(crc, &v, 1); | ||||||
|  |     pos++; | ||||||
|  |     value++; | ||||||
|  |   } | ||||||
|  |   return false; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { | ||||||
|  |   while (size--) { | ||||||
|  |     uint8_t c = qspi.readByte(pos); | ||||||
|  |     if (writing) *value = c; | ||||||
|  |     crc16(crc, &c, 1); | ||||||
|  |     pos++; | ||||||
|  |     value++; | ||||||
|  |   } | ||||||
|  |   return false; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | #endif // QSPI_EEPROM | ||||||
|  | #endif // __SAMD21__ | ||||||
							
								
								
									
										82
									
								
								Marlin/src/HAL/SAMD21/eeprom_wired.cpp
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										82
									
								
								Marlin/src/HAL/SAMD21/eeprom_wired.cpp
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,82 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  | #ifdef __SAMD21__ | ||||||
|  |  | ||||||
|  | #include "../../inc/MarlinConfig.h" | ||||||
|  |  | ||||||
|  | #if USE_WIRED_EEPROM | ||||||
|  |  | ||||||
|  | #error "USE_WIRED_EEPROM emulation Not implemented on SAMD21" | ||||||
|  | /** | ||||||
|  |  * PersistentStore for Arduino-style EEPROM interface | ||||||
|  |  * with simple implementations supplied by Marlin. | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #include "../shared/eeprom_if.h" | ||||||
|  | #include "../shared/eeprom_api.h" | ||||||
|  |  | ||||||
|  | #ifndef MARLIN_EEPROM_SIZE | ||||||
|  |   #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM." | ||||||
|  | #endif | ||||||
|  | size_t PersistentStore::capacity()    { return MARLIN_EEPROM_SIZE; } | ||||||
|  |  | ||||||
|  | bool PersistentStore::access_start()  { eeprom_init(); return true; } | ||||||
|  | bool PersistentStore::access_finish() { return true; } | ||||||
|  |  | ||||||
|  | bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { | ||||||
|  |   uint16_t written = 0; | ||||||
|  |   while (size--) { | ||||||
|  |     const uint8_t v = *value; | ||||||
|  |     uint8_t * const p = (uint8_t * const)pos; | ||||||
|  |     if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! | ||||||
|  |       eeprom_write_byte(p, v); | ||||||
|  |       if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes | ||||||
|  |       if (eeprom_read_byte(p) != v) { | ||||||
|  |         SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); | ||||||
|  |         return true; | ||||||
|  |       } | ||||||
|  |     } | ||||||
|  |     crc16(crc, &v, 1); | ||||||
|  |     pos++; | ||||||
|  |     value++; | ||||||
|  |   } | ||||||
|  |   return false; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { | ||||||
|  |   while (size--) { | ||||||
|  |     uint8_t c = eeprom_read_byte((uint8_t*)pos); | ||||||
|  |     if (writing) *value = c; | ||||||
|  |     crc16(crc, &c, 1); | ||||||
|  |     pos++; | ||||||
|  |     value++; | ||||||
|  |   } | ||||||
|  |   return false; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | #endif // USE_WIRED_EEPROM | ||||||
|  | #endif // __SAMD21__ | ||||||
							
								
								
									
										253
									
								
								Marlin/src/HAL/SAMD21/endstop_interrupts.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										253
									
								
								Marlin/src/HAL/SAMD21/endstop_interrupts.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,253 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Endstop interrupts for ATMEL SAMD21 based targets. | ||||||
|  |  * | ||||||
|  |  * On SAMD21, all pins support external interrupt capability. | ||||||
|  |  * Any pin can be used for external interrupts, but there are some restrictions. | ||||||
|  |  * At most 16 different external interrupts can be used at one time. | ||||||
|  |  * Further, you can’t just pick any 16 pins to use. This is because every pin on the SAMD21 | ||||||
|  |  * connects to what is called an EXTINT line, and only one pin per EXTINT line can be used for external | ||||||
|  |  * interrupts at a time | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Endstop Interrupts | ||||||
|  |  * | ||||||
|  |  * Without endstop interrupts the endstop pins must be polled continually in | ||||||
|  |  * the temperature-ISR via endstops.update(), most of the time finding no change. | ||||||
|  |  * With this feature endstops.update() is called only when we know that at | ||||||
|  |  * least one endstop has changed state, saving valuable CPU cycles. | ||||||
|  |  * | ||||||
|  |  * This feature only works when all used endstop pins can generate an 'external interrupt'. | ||||||
|  |  * | ||||||
|  |  * Test whether pins issue interrupts on your board by flashing 'pin_interrupt_test.ino'. | ||||||
|  |  * (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino) | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #include "../../module/endstops.h" | ||||||
|  |  | ||||||
|  | #define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2)) | ||||||
|  | #define MATCH_X_MAX_EILINE(P)   TERN0(HAS_X_MAX,  DEFER4(MATCH_EILINE)(P, X_MAX_PIN)) | ||||||
|  | #define MATCH_X_MIN_EILINE(P)   TERN0(HAS_X_MIN,  DEFER4(MATCH_EILINE)(P, X_MIN_PIN)) | ||||||
|  | #define MATCH_Y_MAX_EILINE(P)   TERN0(HAS_Y_MAX,  DEFER4(MATCH_EILINE)(P, Y_MAX_PIN)) | ||||||
|  | #define MATCH_Y_MIN_EILINE(P)   TERN0(HAS_Y_MIN,  DEFER4(MATCH_EILINE)(P, Y_MIN_PIN)) | ||||||
|  | #define MATCH_Z_MAX_EILINE(P)   TERN0(HAS_Z_MAX,  DEFER4(MATCH_EILINE)(P, Z_MAX_PIN)) | ||||||
|  | #define MATCH_Z_MIN_EILINE(P)   TERN0(HAS_Z_MIN,  DEFER4(MATCH_EILINE)(P, Z_MIN_PIN)) | ||||||
|  | #define MATCH_I_MAX_EILINE(P)   TERN0(HAS_I_MAX,  DEFER4(MATCH_EILINE)(P, I_MAX_PIN)) | ||||||
|  | #define MATCH_I_MIN_EILINE(P)   TERN0(HAS_I_MIN,  DEFER4(MATCH_EILINE)(P, I_MIN_PIN)) | ||||||
|  | #define MATCH_J_MAX_EILINE(P)   TERN0(HAS_J_MAX,  DEFER4(MATCH_EILINE)(P, J_MAX_PIN)) | ||||||
|  | #define MATCH_J_MIN_EILINE(P)   TERN0(HAS_J_MIN,  DEFER4(MATCH_EILINE)(P, J_MIN_PIN)) | ||||||
|  | #define MATCH_K_MAX_EILINE(P)   TERN0(HAS_K_MAX,  DEFER4(MATCH_EILINE)(P, K_MAX_PIN)) | ||||||
|  | #define MATCH_K_MIN_EILINE(P)   TERN0(HAS_K_MIN,  DEFER4(MATCH_EILINE)(P, K_MIN_PIN)) | ||||||
|  | #define MATCH_U_MAX_EILINE(P)   TERN0(HAS_U_MAX,  DEFER4(MATCH_EILINE)(P, U_MAX_PIN)) | ||||||
|  | #define MATCH_U_MIN_EILINE(P)   TERN0(HAS_U_MIN,  DEFER4(MATCH_EILINE)(P, U_MIN_PIN)) | ||||||
|  | #define MATCH_V_MAX_EILINE(P)   TERN0(HAS_V_MAX,  DEFER4(MATCH_EILINE)(P, V_MAX_PIN)) | ||||||
|  | #define MATCH_V_MIN_EILINE(P)   TERN0(HAS_V_MIN,  DEFER4(MATCH_EILINE)(P, V_MIN_PIN)) | ||||||
|  | #define MATCH_W_MAX_EILINE(P)   TERN0(HAS_W_MAX,  DEFER4(MATCH_EILINE)(P, W_MAX_PIN)) | ||||||
|  | #define MATCH_W_MIN_EILINE(P)   TERN0(HAS_W_MIN,  DEFER4(MATCH_EILINE)(P, W_MIN_PIN)) | ||||||
|  | #define MATCH_Z2_MAX_EILINE(P)  TERN0(HAS_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN)) | ||||||
|  | #define MATCH_Z2_MIN_EILINE(P)  TERN0(HAS_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN)) | ||||||
|  | #define MATCH_Z3_MAX_EILINE(P)  TERN0(HAS_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN)) | ||||||
|  | #define MATCH_Z3_MIN_EILINE(P)  TERN0(HAS_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN)) | ||||||
|  | #define MATCH_Z4_MAX_EILINE(P)  TERN0(HAS_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN)) | ||||||
|  | #define MATCH_Z4_MIN_EILINE(P)  TERN0(HAS_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN)) | ||||||
|  | #define MATCH_Z_MIN_PROBE_EILINE(P) TERN0(HAS_Z_MIN_PROBE_PIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PROBE_PIN)) | ||||||
|  |  | ||||||
|  | #define AVAILABLE_EILINE(P) ( PIN_TO_EILINE(P) != -1    \ | ||||||
|  |   && !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P)   \ | ||||||
|  |   && !MATCH_Y_MAX_EILINE(P) && !MATCH_Y_MIN_EILINE(P)   \ | ||||||
|  |   && !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P)   \ | ||||||
|  |   && !MATCH_I_MAX_EILINE(P) && !MATCH_I_MIN_EILINE(P)   \ | ||||||
|  |   && !MATCH_J_MAX_EILINE(P) && !MATCH_J_MIN_EILINE(P)   \ | ||||||
|  |   && !MATCH_K_MAX_EILINE(P) && !MATCH_K_MIN_EILINE(P)   \ | ||||||
|  |   && !MATCH_U_MAX_EILINE(P) && !MATCH_U_MIN_EILINE(P)   \ | ||||||
|  |   && !MATCH_V_MAX_EILINE(P) && !MATCH_V_MIN_EILINE(P)   \ | ||||||
|  |   && !MATCH_W_MAX_EILINE(P) && !MATCH_W_MIN_EILINE(P)   \ | ||||||
|  |   && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \ | ||||||
|  |   && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \ | ||||||
|  |   && !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \ | ||||||
|  |   && !MATCH_Z_MIN_PROBE_EILINE(P) ) | ||||||
|  |  | ||||||
|  | // One ISR for all EXT-Interrupts | ||||||
|  | void endstop_ISR() { endstops.update(); } | ||||||
|  |  | ||||||
|  | void setup_endstop_interrupts() { | ||||||
|  |   #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE) | ||||||
|  |   #if HAS_X_MAX | ||||||
|  |     #if !AVAILABLE_EILINE(X_MAX_PIN) | ||||||
|  |       #error "X_MAX_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     _ATTACH(X_MAX_PIN); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_X_MIN | ||||||
|  |     #if !AVAILABLE_EILINE(X_MIN_PIN) | ||||||
|  |       #error "X_MIN_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     _ATTACH(X_MIN_PIN); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_Y_MAX | ||||||
|  |     #if !AVAILABLE_EILINE(Y_MAX_PIN) | ||||||
|  |       #error "Y_MAX_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     _ATTACH(Y_MAX_PIN); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_Y_MIN | ||||||
|  |     #if !AVAILABLE_EILINE(Y_MIN_PIN) | ||||||
|  |       #error "Y_MIN_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     _ATTACH(Y_MIN_PIN); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_Z_MAX | ||||||
|  |     #if !AVAILABLE_EILINE(Z_MAX_PIN) | ||||||
|  |       #error "Z_MAX_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     _ATTACH(Z_MAX_PIN); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_Z_MIN | ||||||
|  |     #if !AVAILABLE_EILINE(Z_MIN_PIN) | ||||||
|  |       #error "Z_MIN_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     _ATTACH(Z_MIN_PIN); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_Z2_MAX | ||||||
|  |     #if !AVAILABLE_EILINE(Z2_MAX_PIN) | ||||||
|  |       #error "Z2_MAX_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     _ATTACH(Z2_MAX_PIN); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_Z2_MIN | ||||||
|  |     #if !AVAILABLE_EILINE(Z2_MIN_PIN) | ||||||
|  |       #error "Z2_MIN_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     _ATTACH(Z2_MIN_PIN); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_Z3_MAX | ||||||
|  |     #if !AVAILABLE_EILINE(Z3_MAX_PIN) | ||||||
|  |       #error "Z3_MAX_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     _ATTACH(Z3_MAX_PIN); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_Z3_MIN | ||||||
|  |     #if !AVAILABLE_EILINE(Z3_MIN_PIN) | ||||||
|  |       #error "Z3_MIN_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     _ATTACH(Z3_MIN_PIN); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_Z4_MAX | ||||||
|  |     #if !AVAILABLE_EILINE(Z4_MAX_PIN) | ||||||
|  |       #error "Z4_MAX_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     _ATTACH(Z4_MAX_PIN); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_Z4_MIN | ||||||
|  |     #if !AVAILABLE_EILINE(Z4_MIN_PIN) | ||||||
|  |       #error "Z4_MIN_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     _ATTACH(Z4_MIN_PIN); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_Z_MIN_PROBE_PIN | ||||||
|  |     #if !AVAILABLE_EILINE(Z_MIN_PROBE_PIN) | ||||||
|  |       #error "Z_MIN_PROBE_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     _ATTACH(Z_MIN_PROBE_PIN); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_I_MAX | ||||||
|  |     #if !AVAILABLE_EILINE(I_MAX_PIN) | ||||||
|  |       #error "I_MAX_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     attachInterrupt(I_MAX_PIN, endstop_ISR, CHANGE); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_I_MIN | ||||||
|  |     #if !AVAILABLE_EILINE(I_MIN_PIN) | ||||||
|  |       #error "I_MIN_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     attachInterrupt(I_MIN_PIN, endstop_ISR, CHANGE); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_J_MAX | ||||||
|  |     #if !AVAILABLE_EILINE(J_MAX_PIN) | ||||||
|  |       #error "J_MAX_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     attachInterrupt(J_MAX_PIN, endstop_ISR, CHANGE); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_J_MIN | ||||||
|  |     #if !AVAILABLE_EILINE(J_MIN_PIN) | ||||||
|  |       #error "J_MIN_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     attachInterrupt(J_MIN_PIN, endstop_ISR, CHANGE); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_K_MAX | ||||||
|  |     #if !AVAILABLE_EILINE(K_MAX_PIN) | ||||||
|  |       #error "K_MAX_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     attachInterrupt(K_MAX_PIN, endstop_ISR, CHANGE); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_K_MIN | ||||||
|  |     #if !AVAILABLE_EILINE(K_MIN_PIN) | ||||||
|  |       #error "K_MIN_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     attachInterrupt(K_MIN_PIN, endstop_ISR, CHANGE); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_U_MAX | ||||||
|  |     #if !AVAILABLE_EILINE(U_MAX_PIN) | ||||||
|  |       #error "U_MAX_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     attachInterrupt(U_MAX_PIN, endstop_ISR, CHANGE); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_U_MIN | ||||||
|  |     #if !AVAILABLE_EILINE(U_MIN_PIN) | ||||||
|  |       #error "U_MIN_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     attachInterrupt(U_MIN_PIN, endstop_ISR, CHANGE); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_V_MAX | ||||||
|  |     #if !AVAILABLE_EILINE(V_MAX_PIN) | ||||||
|  |       #error "V_MAX_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     attachInterrupt(V_MAX_PIN, endstop_ISR, CHANGE); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_V_MIN | ||||||
|  |     #if !AVAILABLE_EILINE(V_MIN_PIN) | ||||||
|  |       #error "V_MIN_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     attachInterrupt(V_MIN_PIN, endstop_ISR, CHANGE); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_W_MAX | ||||||
|  |     #if !AVAILABLE_EILINE(W_MAX_PIN) | ||||||
|  |       #error "W_MAX_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     attachInterrupt(W_MAX_PIN, endstop_ISR, CHANGE); | ||||||
|  |   #endif | ||||||
|  |   #if HAS_W_MIN | ||||||
|  |     #if !AVAILABLE_EILINE(W_MIN_PIN) | ||||||
|  |       #error "W_MIN_PIN has no EXTINT line available." | ||||||
|  |     #endif | ||||||
|  |     attachInterrupt(W_MIN_PIN, endstop_ISR, CHANGE); | ||||||
|  |   #endif | ||||||
|  | } | ||||||
							
								
								
									
										216
									
								
								Marlin/src/HAL/SAMD21/fastio.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										216
									
								
								Marlin/src/HAL/SAMD21/fastio.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,216 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Fast IO functions for SAMD21 | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #include "SAMD21.h" | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Utility functions | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #ifndef MASK | ||||||
|  |   #define MASK(PIN) _BV(PIN) | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Magic I/O routines | ||||||
|  |  * | ||||||
|  |  * Now you can simply SET_OUTPUT(IO); WRITE(IO, HIGH); WRITE(IO, LOW); | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | // Read a pin | ||||||
|  | #define READ(IO)        ((PORT->Group[(EPortType)GET_SAMD_PORT(IO)].IN.reg & MASK(GET_SAMD_PIN(IO))) != 0) | ||||||
|  |  | ||||||
|  | // Write to a pin | ||||||
|  | #define WRITE(IO,V)     do{                                                     \ | ||||||
|  |                           const EPortType port = (EPortType)GET_SAMD_PORT(IO);  \ | ||||||
|  |                           const uint32_t mask = MASK(GET_SAMD_PIN(IO));         \ | ||||||
|  |                                                                                 \ | ||||||
|  |                           if (V) PORT->Group[port].OUTSET.reg = mask;           \ | ||||||
|  |                           else PORT->Group[port].OUTCLR.reg = mask;             \ | ||||||
|  |                         }while(0) | ||||||
|  |  | ||||||
|  | // Toggle a pin | ||||||
|  | #define TOGGLE(IO)      PORT->Group[(EPortType)GET_SAMD_PORT(IO)].OUTTGL.reg = MASK(GET_SAMD_PIN(IO)); | ||||||
|  |  | ||||||
|  | // Set pin as input | ||||||
|  | #define SET_INPUT(IO)           do{                                                                 \ | ||||||
|  |                                   const EPortType port = (EPortType)GET_SAMD_PORT(IO);              \ | ||||||
|  |                                   const uint32_t pin = GET_SAMD_PIN(IO);                            \ | ||||||
|  |                                                                                                     \ | ||||||
|  |                                   PORT->Group[port].PINCFG[pin].reg = (uint8_t)(PORT_PINCFG_INEN);  \ | ||||||
|  |                                   PORT->Group[port].DIRCLR.reg = MASK(pin);                         \ | ||||||
|  |                                 }while(0) | ||||||
|  | // Set pin as input with pullup | ||||||
|  | #define SET_INPUT_PULLUP(IO)    do{                                                                                       \ | ||||||
|  |                                   const EPortType port = (EPortType)GET_SAMD_PORT(IO);                                    \ | ||||||
|  |                                   const uint32_t pin = GET_SAMD_PIN(IO);                                                  \ | ||||||
|  |                                   const uint32_t mask = MASK(pin);                                                        \ | ||||||
|  |                                                                                                                           \ | ||||||
|  |                                   PORT->Group[port].PINCFG[pin].reg = (uint8_t)(PORT_PINCFG_INEN | PORT_PINCFG_PULLEN);   \ | ||||||
|  |                                   PORT->Group[port].DIRCLR.reg = mask;                                                    \ | ||||||
|  |                                   PORT->Group[port].OUTSET.reg = mask;                                                    \ | ||||||
|  |                                 }while(0) | ||||||
|  | // Set pin as input with pulldown | ||||||
|  | #define SET_INPUT_PULLDOWN(IO)  do{                                                                                       \ | ||||||
|  |                                   const EPortType port = (EPortType)GET_SAMD_PORT(IO);                                    \ | ||||||
|  |                                   const uint32_t pin = GET_SAMD_PIN(IO);                                                  \ | ||||||
|  |                                   const uint32_t mask = MASK(pin);                                                        \ | ||||||
|  |                                                                                                                           \ | ||||||
|  |                                   PORT->Group[port].PINCFG[pin].reg = (uint8_t)(PORT_PINCFG_INEN | PORT_PINCFG_PULLEN);   \ | ||||||
|  |                                   PORT->Group[port].DIRCLR.reg = mask;                                                    \ | ||||||
|  |                                   PORT->Group[port].OUTCLR.reg = mask;                                                    \ | ||||||
|  |                                 }while(0) | ||||||
|  | // Set pin as output (push pull) | ||||||
|  | #define SET_OUTPUT(IO)          do{                                                                 \ | ||||||
|  |                                   const EPortType port = (EPortType)GET_SAMD_PORT(IO);              \ | ||||||
|  |                                   const uint32_t pin = GET_SAMD_PIN(IO);                            \ | ||||||
|  |                                                                                                     \ | ||||||
|  |                                   PORT->Group[port].DIRSET.reg = MASK(pin);                         \ | ||||||
|  |                                   PORT->Group[port].PINCFG[pin].reg = 0;                            \ | ||||||
|  |                                 }while(0) | ||||||
|  | // Set pin as output (open drain) | ||||||
|  | #define SET_OUTPUT_OD(IO)       do{                                                                   \ | ||||||
|  |                                   const EPortType port = (EPortType)GET_SAMD_PORT(IO);                \ | ||||||
|  |                                   const uint32_t pin = GET_SAMD_PIN(IO);                              \ | ||||||
|  |                                                                                                       \ | ||||||
|  |                                   PORT->Group[port].PINCFG[pin].reg = (uint8_t)(PORT_PINCFG_PULLEN);  \ | ||||||
|  |                                   PORT->Group[port].DIRCLR.reg = MASK(pin);                           \ | ||||||
|  |                                 }while(0) | ||||||
|  | // Set pin as PWM (push pull) | ||||||
|  | #define SET_PWM                 SET_OUTPUT | ||||||
|  | // Set pin as PWM (open drain) | ||||||
|  | #define SET_PWM_OD              SET_OUTPUT_OD | ||||||
|  |  | ||||||
|  | // check if pin is an output | ||||||
|  | #define IS_OUTPUT(IO)            ((PORT->Group[(EPortType)GET_SAMD_PORT(IO)].DIR.reg & MASK(GET_SAMD_PIN(IO))) \ | ||||||
|  |                                  || (PORT->Group[(EPortType)GET_SAMD_PORT(IO)].PINCFG[GET_SAMD_PIN(IO)].reg & (PORT_PINCFG_INEN | PORT_PINCFG_PULLEN)) == PORT_PINCFG_PULLEN) | ||||||
|  | // check if pin is an input | ||||||
|  | #define IS_INPUT(IO)            !IS_OUTPUT(IO) | ||||||
|  |  | ||||||
|  | // Shorthand | ||||||
|  | #define OUT_WRITE(IO,V)         do{ SET_OUTPUT(IO); WRITE(IO,V); }while(0) | ||||||
|  | #define OUT_WRITE_OD(IO,V)      do{ SET_OUTPUT_OD(IO); WRITE(IO,V); }while(0) | ||||||
|  |  | ||||||
|  | // digitalRead/Write wrappers | ||||||
|  | #define extDigitalRead(IO)      digitalRead(IO) | ||||||
|  | #define extDigitalWrite(IO,V)   digitalWrite(IO,V) | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Ports and functions | ||||||
|  |  * 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) | ||||||
|  |  | ||||||
|  | // Return fulfilled ADCx->INPUTCTRL.reg | ||||||
|  | #define PIN_TO_INPUTCTRL(P)     (  (P == 0) ? ADC_INPUTCTRL_MUXPOS_PIN0   \ | ||||||
|  |                                  : ((P) == 1) ? ADC_INPUTCTRL_MUXPOS_PIN1   \ | ||||||
|  |                                  : ((P) == 2) ? ADC_INPUTCTRL_MUXPOS_PIN3   \ | ||||||
|  |                                  : ((P) == 3) ? ADC_INPUTCTRL_MUXPOS_PIN4   \ | ||||||
|  |                                  : ((P) == 4) ? ADC_INPUTCTRL_MUXPOS_PIN5   \ | ||||||
|  |                                  : ((P) == 5) ? ADC_INPUTCTRL_MUXPOS_PIN5   \ | ||||||
|  |                                  : ((P) == 6) ? ADC_INPUTCTRL_MUXPOS_PIN6   \ | ||||||
|  |                                  : ((P) == 7) ? ADC_INPUTCTRL_MUXPOS_PIN7   \ | ||||||
|  |                                  : ((P) == 8) ? ADC_INPUTCTRL_MUXPOS_PIN8   \ | ||||||
|  |                                  : ((P) == 9) ? ADC_INPUTCTRL_MUXPOS_PIN9   \ | ||||||
|  |                                  : ((P) == 10) ? ADC_INPUTCTRL_MUXPOS_PIN10 \ | ||||||
|  |                                  : ((P) == 11) ? ADC_INPUTCTRL_MUXPOS_PIN11 \ | ||||||
|  |                                  : ((P) == 12) ? ADC_INPUTCTRL_MUXPOS_PIN12 \ | ||||||
|  |                                  : ((P) == 13) ? ADC_INPUTCTRL_MUXPOS_PIN13 \ | ||||||
|  |                                  : ((P) == 14) ? ADC_INPUTCTRL_MUXPOS_PIN14 \ | ||||||
|  |                                  : ADC_INPUTCTRL_MUXPOS_PIN15) | ||||||
|  |  | ||||||
|  | #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 | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | // PORTA | ||||||
|  | #define DIO28_PIN   PIN_PA02    // A0 | ||||||
|  | #define DIO56_PIN   PIN_PA03    // A13 | ||||||
|  | #define DIO31_PIN   PIN_PA04    // A13 | ||||||
|  | #define DIO32_PIN   PIN_PA05    // A1 | ||||||
|  | #define DIO8_PIN    PIN_PA06    // A14 | ||||||
|  | #define DIO9_PIN    PIN_PA07    // A15 | ||||||
|  | #define DIO4_PIN    PIN_PA08    // A15 | ||||||
|  | #define DIO3_PIN    PIN_PA09    // A15 | ||||||
|  | #define DIO1_PIN    PIN_PA10 | ||||||
|  | #define DIO0_PIN    PIN_PA11 | ||||||
|  | #define DIO18_PIN   PIN_PA12 | ||||||
|  | #define DIO52_PIN   PIN_PA13 | ||||||
|  | #define DIO2_PIN    PIN_PA14 | ||||||
|  | #define DIO5_PIN    PIN_PA15 | ||||||
|  | #define DIO11_PIN   PIN_PA16 | ||||||
|  | #define DIO13_PIN   PIN_PA17 | ||||||
|  | #define DIO10_PIN   PIN_PA18 | ||||||
|  | #define DIO12_PIN   PIN_PA19 | ||||||
|  | #define DIO6_PIN    PIN_PA20 | ||||||
|  | #define DIO07_PIN   PIN_PA21 | ||||||
|  | #define DIO34_PIN   PIN_PA22 | ||||||
|  | #define DIO35_PIN   PIN_PA23 | ||||||
|  | #define DIO42_PIN   PIN_PA24 | ||||||
|  | #define DIO43_PIN   PIN_PA25 | ||||||
|  |  | ||||||
|  | #define DIO40_PIN   PIN_PA27 | ||||||
|  |  | ||||||
|  | #define DIO26_PIN   PIN_PB00 | ||||||
|  | #define DIO27_PIN   PIN_PB01    // A0 | ||||||
|  | #define DIO33_PIN   PIN_PB02 | ||||||
|  | #define DIO39_PIN   PIN_PB03 | ||||||
|  | #define DIO14_PIN   PIN_PB04 | ||||||
|  | #define DIO15_PIN   PIN_PB05 | ||||||
|  | #define DIO16_PIN   PIN_PB06 | ||||||
|  | #define DIO17_PIN   PIN_PB07 | ||||||
|  | #define DIO29_PIN   PIN_PB08 | ||||||
|  | #define DIO30_PIN   PIN_PB09 | ||||||
|  | #define DIO37_PIN   PIN_PB10 | ||||||
|  | #define DIO38_PIN   PIN_PB11 | ||||||
|  | #define DIO36_PIN   PIN_PB12 | ||||||
|  | #define DIO19_PIN   PIN_PB13 | ||||||
|  | #define DIO20_PIN   PIN_PB14 | ||||||
|  | #define DIO21_PIN   PIN_PB15 | ||||||
|  | #define DIO22_PIN   PIN_PB16 | ||||||
|  | #define DIO23_PIN   PIN_PB17 | ||||||
|  |  | ||||||
|  | #define DIO44_PIN   PIN_PB22 | ||||||
|  | #define DIO45_PIN   PIN_PB23 | ||||||
|  | #define DIO24_PIN   PIN_PB30 | ||||||
|  | #define DIO25_PIN   PIN_PB31 | ||||||
|  |  | ||||||
|  | #define DIO53_PIN   PIN_PA21 | ||||||
|  | #define DIO54_PIN   PIN_PA06 | ||||||
|  | #define DIO55_PIN   PIN_PA07 | ||||||
|  |  | ||||||
							
								
								
									
										31
									
								
								Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										31
									
								
								Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,31 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
|  |  | ||||||
|  | #if HAS_SPI_TFT || HAS_FSMC_TFT | ||||||
|  |   #error "Sorry! TFT displays are not available for HAL/SAMD21." | ||||||
|  | #endif | ||||||
							
								
								
									
										27
									
								
								Marlin/src/HAL/SAMD21/inc/Conditionals_adv.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										27
									
								
								Marlin/src/HAL/SAMD21/inc/Conditionals_adv.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,27 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
							
								
								
									
										33
									
								
								Marlin/src/HAL/SAMD21/inc/Conditionals_post.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										33
									
								
								Marlin/src/HAL/SAMD21/inc/Conditionals_post.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,33 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
|  |  | ||||||
|  | #if USE_FALLBACK_EEPROM | ||||||
|  |   #define FLASH_EEPROM_EMULATION | ||||||
|  | #elif EITHER(I2C_EEPROM, SPI_EEPROM) | ||||||
|  |   #define USE_SHARED_EEPROM 1 | ||||||
|  | #endif | ||||||
							
								
								
									
										50
									
								
								Marlin/src/HAL/SAMD21/inc/SanityCheck.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										50
									
								
								Marlin/src/HAL/SAMD21/inc/SanityCheck.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,50 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Test SAMD21 specific configuration values for errors at compile-time. | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #if SERVO_TC == MF_TIMER_RTC | ||||||
|  |   #error "Servos can't use RTC timer" | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | #if ENABLED(EMERGENCY_PARSER) | ||||||
|  |   #error "EMERGENCY_PARSER is not yet implemented for SAMD21. Disable EMERGENCY_PARSER to continue." | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | #if ENABLED(SDIO_SUPPORT) | ||||||
|  |   #error "SDIO_SUPPORT is not supported on SAMD21." | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | #if ENABLED(FAST_PWM_FAN) | ||||||
|  |   #error "Features requiring Hardware PWM (FAST_PWM_FAN) are not yet supported on SAMD21." | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | #if ENABLED(POSTMORTEM_DEBUGGING) | ||||||
|  |   #error "POSTMORTEM_DEBUGGING is not yet supported on SAMD21." | ||||||
|  | #endif | ||||||
							
								
								
									
										160
									
								
								Marlin/src/HAL/SAMD21/pinsDebug.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										160
									
								
								Marlin/src/HAL/SAMD21/pinsDebug.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,160 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #define NUMBER_PINS_TOTAL PINS_COUNT | ||||||
|  |  | ||||||
|  | #define digitalRead_mod(p) extDigitalRead(p) | ||||||
|  | #define PRINT_PORT(p) do{ SERIAL_ECHOPGM("  Port: "); sprintf_P(buffer, PSTR("%c%02ld"), 'A' + g_APinDescription[p].ulPort, g_APinDescription[p].ulPin); SERIAL_ECHO(buffer); }while (0) | ||||||
|  | #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) | ||||||
|  | #define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0) | ||||||
|  | #define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d)  "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) | ||||||
|  | #define GET_ARRAY_PIN(p) pin_array[p].pin | ||||||
|  | #define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital | ||||||
|  | #define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL) | ||||||
|  | #define DIGITAL_PIN_TO_ANALOG_PIN(p) digitalPinToAnalogInput(p) | ||||||
|  | #define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P)!=-1) | ||||||
|  | #define pwm_status(pin) digitalPinHasPWM(pin) | ||||||
|  | #define MULTI_NAME_PAD 27 // space needed to be pretty if not first name assigned to a pin | ||||||
|  |  | ||||||
|  | // pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities | ||||||
|  | // uses pin index | ||||||
|  | #define M43_NEVER_TOUCH(Q) ((Q) >= 75) | ||||||
|  |  | ||||||
|  | bool GET_PINMODE(int8_t pin) {  // 1: output, 0: input | ||||||
|  |   const EPortType samdport = g_APinDescription[pin].ulPort; | ||||||
|  |   const uint32_t samdpin = g_APinDescription[pin].ulPin; | ||||||
|  |   return PORT->Group[samdport].DIR.reg & MASK(samdpin) || (PORT->Group[samdport].PINCFG[samdpin].reg & (PORT_PINCFG_INEN | PORT_PINCFG_PULLEN)) == PORT_PINCFG_PULLEN; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void pwm_details(int32_t pin) { | ||||||
|  |   if (pwm_status(pin)) { | ||||||
|  |     //uint32_t chan = g_APinDescription[pin].ulPWMChannel TODO when fast pwm is operative; | ||||||
|  |     //SERIAL_ECHOPGM("PWM = ", duty); | ||||||
|  |   } | ||||||
|  | } | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 Board pin|  PORT  | Label | ||||||
|  |  * ----------------+--------+------- | ||||||
|  |  *   0             |  PB25  | "RX0" | ||||||
|  |  *   1             |  PB24  | "TX0" | ||||||
|  |  *   2             |  PC18  | | ||||||
|  |  *   3             |  PC19  | | ||||||
|  |  *   4             |  PC20  | | ||||||
|  |  *   5             |  PC21  | | ||||||
|  |  *   6             |  PD20  | | ||||||
|  |  *   7             |  PD21  | | ||||||
|  |  *   8             |  PB18  | | ||||||
|  |  *   9             |  PB2   | | ||||||
|  |  *  10             |  PB22  | | ||||||
|  |  *  11             |  PB23  | | ||||||
|  |  *  12             |  PB0   | "A16" | ||||||
|  |  *  13             |  PB1   | LED AMBER "L" / "A17" | ||||||
|  |  *  14             |  PB16  | "TX3" | ||||||
|  |  *  15             |  PB17  | "RX3" | ||||||
|  |  *  16             |  PC22  | "TX2" | ||||||
|  |  *  17             |  PC23  | "RX2" | ||||||
|  |  *  18             |  PB12  | "TX1" / "A18" | ||||||
|  |  *  19             |  PB13  | "RX1" | ||||||
|  |  *  20             |  PB20  | "SDA" | ||||||
|  |  *  21             |  PB21  | "SCL" | ||||||
|  |  *  22             |  PD12  | | ||||||
|  |  *  23             |  PA15  | | ||||||
|  |  *  24             |  PC17  | | ||||||
|  |  *  25             |  PC16  | | ||||||
|  |  *  26             |  PA12  | | ||||||
|  |  *  27             |  PA13  | | ||||||
|  |  *  28             |  PA14  | | ||||||
|  |  *  29             |  PB19  | | ||||||
|  |  *  30             |  PA23  | | ||||||
|  |  *  31             |  PA22  | | ||||||
|  |  *  32             |  PA21  | | ||||||
|  |  *  33             |  PA20  | | ||||||
|  |  *  34             |  PA19  | | ||||||
|  |  *  35             |  PA18  | | ||||||
|  |  *  36             |  PA17  | | ||||||
|  |  *  37             |  PA16  | | ||||||
|  |  *  38             |  PB15  | | ||||||
|  |  *  39             |  PB14  | | ||||||
|  |  *  40             |  PC13  | | ||||||
|  |  *  41             |  PC12  | | ||||||
|  |  *  42             |  PC15  | | ||||||
|  |  *  43             |  PC14  | | ||||||
|  |  *  44             |  PC11  | | ||||||
|  |  *  45             |  PC10  | | ||||||
|  |  *  46             |  PC6   | | ||||||
|  |  *  47             |  PC7   | | ||||||
|  |  *  48             |  PC4   | | ||||||
|  |  *  49             |  PC5   | | ||||||
|  |  *  50             |  PD11  | | ||||||
|  |  *  51             |  PD8   | | ||||||
|  |  *  52             |  PD9   | | ||||||
|  |  *  53             |  PD10  | | ||||||
|  |  *  54             |  PB5   | "A8" | ||||||
|  |  *  55             |  PB6   | "A9" | ||||||
|  |  *  56             |  PB7   | "A10" | ||||||
|  |  *  57             |  PB8   | "A11" | ||||||
|  |  *  58             |  PB9   | "A12" | ||||||
|  |  *  69             |  PA4   | "A13" | ||||||
|  |  *  60             |  PA6   | "A14" | ||||||
|  |  *  61             |  PA7   | "A15" | ||||||
|  |  *  62             |  PB17  | | ||||||
|  |  *  63             |  PB20  | | ||||||
|  |  *  64             |  PD11  | | ||||||
|  |  *  65             |  PD8   | | ||||||
|  |  *  66             |  PD9   | | ||||||
|  |  *  67             |  PA2   | "A0" / "DAC0" | ||||||
|  |  *  68             |  PA5   | "A1" / "DAC1" | ||||||
|  |  *  69             |  PB3   | "A2" | ||||||
|  |  *  70             |  PC0   | "A3" | ||||||
|  |  *  71             |  PC1   | "A4" | ||||||
|  |  *  72             |  PC2   | "A5" | ||||||
|  |  *  73             |  PC3   | "A6" | ||||||
|  |  *  74             |  PB4   | "A7" | ||||||
|  |  *  75             |  PC31  | LED GREEN "RX" | ||||||
|  |  *  76             |  PC30  | LED GREEN "TX" | ||||||
|  |  *  77             |  PA27  | USB: Host enable | ||||||
|  |  *  78             |  PA24  | USB: D- | ||||||
|  |  *  79             |  PA25  | USB: D+ | ||||||
|  |  *  80             |  PB29  | SD: MISO | ||||||
|  |  *  81             |  PB27  | SD: SCK | ||||||
|  |  *  82             |  PB26  | SD: MOSI | ||||||
|  |  *  83             |  PB28  | SD: CS | ||||||
|  |  *  84             |  PA3   | AREF | ||||||
|  |  *  85             |  PA2   | DAC0 (Duplicate) | ||||||
|  |  *  86             |  PA5   | DAC1 (Duplicate) | ||||||
|  |  *  87             |  PB1   | LED AMBER "L" (Duplicate) | ||||||
|  |  *  88             |  PC24  | NeoPixel | ||||||
|  |  *  89             |  PB10  | QSPI: SCK | ||||||
|  |  *  90             |  PB11  | QSPI: CS | ||||||
|  |  *  91             |  PA8   | QSPI: IO0 | ||||||
|  |  *  92             |  PA9   | QSPI: IO1 | ||||||
|  |  *  93             |  PA10  | QSPI: IO2 | ||||||
|  |  *  94             |  PA11  | QSPI: IO3 | ||||||
|  |  *  95             |  PB31  | SD: DETECT | ||||||
|  |  */ | ||||||
							
								
								
									
										54
									
								
								Marlin/src/HAL/SAMD21/spi_pins.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										54
									
								
								Marlin/src/HAL/SAMD21/spi_pins.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,54 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 Default SPI Pins | ||||||
|  |  * | ||||||
|  |  *         SS    SCK   MISO   MOSI | ||||||
|  |  *       +-------------------------+ | ||||||
|  |  *  SPI  | 53    52     50     51  | | ||||||
|  |  *  SPI1 | 83    81     80     82  | | ||||||
|  |  *       +-------------------------+ | ||||||
|  |  * Any pin can be used for Chip Select (SD_SS_PIN) | ||||||
|  |  */ | ||||||
|  | #ifndef SD_SCK_PIN | ||||||
|  |   #define SD_SCK_PIN    38 | ||||||
|  | #endif | ||||||
|  | #ifndef SD_MISO_PIN | ||||||
|  |   #define SD_MISO_PIN   36 | ||||||
|  | #endif | ||||||
|  | #ifndef SD_MOSI_PIN | ||||||
|  |   #define SD_MOSI_PIN   37 | ||||||
|  | #endif | ||||||
|  | #ifndef SDSS | ||||||
|  |   #define SDSS          18 | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | #ifndef SD_SS_PIN | ||||||
|  |   #define SD_SS_PIN     SDSS | ||||||
|  | #endif | ||||||
							
								
								
									
										217
									
								
								Marlin/src/HAL/SAMD21/timers.cpp
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										217
									
								
								Marlin/src/HAL/SAMD21/timers.cpp
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,217 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  | #ifdef __SAMD21__ | ||||||
|  |  | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  | // Includes | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  |  | ||||||
|  | #include "../../inc/MarlinConfig.h" | ||||||
|  | #include "ServoTimers.h" // for SERVO_TC | ||||||
|  |  | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  | // Local defines | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  |  | ||||||
|  | #define NUM_HARDWARE_TIMERS 9 | ||||||
|  |  | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  | // Private Variables | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  |  | ||||||
|  | const tTimerConfig timer_config[NUM_HARDWARE_TIMERS] = { | ||||||
|  |   { {.pTcc=TCC0}, TimerType::tcc,  TCC0_IRQn, TC_PRIORITY(0) },  // 0 - stepper (assigned priority 2) | ||||||
|  |   { {.pTcc=TCC1}, TimerType::tcc,  TCC1_IRQn, TC_PRIORITY(1) },  // 1 - stepper (needed by 32 bit timers) | ||||||
|  |   { {.pTcc=TCC2}, TimerType::tcc,  TCC2_IRQn, 5              },  // 2 - tone (reserved by framework and fixed assigned priority 5) | ||||||
|  |   { {.pTc=TC3},   TimerType::tc,   TC3_IRQn, TC_PRIORITY(3) },  // 3 - servo (assigned priority 1) | ||||||
|  |   { {.pTc=TC4},   TimerType::tc,   TC4_IRQn, TC_PRIORITY(4) },  // 4 - software serial (no interrupts used) | ||||||
|  |   { {.pTc=TC5},   TimerType::tc,   TC5_IRQn, TC_PRIORITY(5) }, | ||||||
|  |   { {.pTc=TC6},   TimerType::tc,   TC6_IRQn, TC_PRIORITY(6) }, | ||||||
|  |   { {.pTc=TC7},   TimerType::tc,   TC7_IRQn, TC_PRIORITY(7) }, | ||||||
|  |   { {.pRtc=RTC},  TimerType::rtc,   RTC_IRQn, TC_PRIORITY(8) }   // 8 - temperature (assigned priority 6) | ||||||
|  | }; | ||||||
|  |  | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  | // Private functions | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  |  | ||||||
|  | FORCE_INLINE void Disable_Irq(IRQn_Type irq) { | ||||||
|  |   NVIC_DisableIRQ(irq); | ||||||
|  |  | ||||||
|  |   // We NEED memory barriers to ensure Interrupts are actually disabled! | ||||||
|  |   // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the ) | ||||||
|  |   __DSB(); | ||||||
|  |   __ISB(); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | static bool tcIsSyncing(Tc * tc) { | ||||||
|  |   return tc->COUNT32.STATUS.reg & TC_STATUS_SYNCBUSY; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | static void tcReset( Tc * tc) { | ||||||
|  |   tc->COUNT32.CTRLA.reg = TC_CTRLA_SWRST; | ||||||
|  |   while (tcIsSyncing(tc)) {} | ||||||
|  |   while (tc->COUNT32.CTRLA.bit.SWRST) {} | ||||||
|  | } | ||||||
|  |  | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  | // Public functions | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  |  | ||||||
|  | void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { | ||||||
|  |   IRQn_Type irq = timer_config[timer_num].IRQ_Id; | ||||||
|  |  | ||||||
|  |   // Disable interrupt, just in case it was already enabled | ||||||
|  |   NVIC_DisableIRQ(irq); | ||||||
|  |   NVIC_ClearPendingIRQ(irq); | ||||||
|  |  | ||||||
|  |   if (timer_num == MF_TIMER_RTC) { | ||||||
|  |  | ||||||
|  |     // https://github.com/arduino-libraries/RTCZero | ||||||
|  |     Rtc * const rtc = timer_config[timer_num].pRtc; | ||||||
|  |     PM->APBAMASK.reg |= PM_APBAMASK_RTC; | ||||||
|  |  | ||||||
|  |     GCLK->CLKCTRL.reg = (uint32_t)((GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK4 | (RTC_GCLK_ID << GCLK_CLKCTRL_ID_Pos))); | ||||||
|  |     while (GCLK->STATUS.bit.SYNCBUSY) {} | ||||||
|  |  | ||||||
|  |     GCLK->GENCTRL.reg = (GCLK_GENCTRL_GENEN | GCLK_GENCTRL_SRC_OSCULP32K | GCLK_GENCTRL_ID(4) | GCLK_GENCTRL_DIVSEL ); | ||||||
|  |     while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {} | ||||||
|  |  | ||||||
|  |     GCLK->GENDIV.reg = GCLK_GENDIV_ID(4); | ||||||
|  |     GCLK->GENDIV.bit.DIV=4; | ||||||
|  |     while (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) {} | ||||||
|  |  | ||||||
|  |     // Disable timer interrupt | ||||||
|  |     rtc->MODE0.INTENCLR.reg = RTC_MODE0_INTENCLR_CMP0; | ||||||
|  |     SYNC(rtc->MODE0.STATUS.bit.SYNCBUSY); | ||||||
|  |  | ||||||
|  |     while(rtc->MODE0.STATUS.bit.SYNCBUSY) {} | ||||||
|  |  | ||||||
|  |     // Stop timer, just in case, to be able to reconfigure it | ||||||
|  |     rtc->MODE0.CTRL.reg = | ||||||
|  |       RTC_MODE0_CTRL_MODE_COUNT32 |           // Mode 0 = 32-bits counter | ||||||
|  |       RTC_MODE0_CTRL_PRESCALER_DIV1024;       // Divisor = 1024 | ||||||
|  |  | ||||||
|  |     while(rtc->MODE0.STATUS.bit.SYNCBUSY) {} | ||||||
|  |  | ||||||
|  |     // Mode, reset counter on match | ||||||
|  |     rtc->MODE0.CTRL.reg = RTC_MODE0_CTRL_MODE_COUNT32 | RTC_MODE0_CTRL_MATCHCLR; | ||||||
|  |  | ||||||
|  |     // Set compare value | ||||||
|  |     rtc->MODE0.COMP[0].reg = (32768 + frequency / 2) / frequency; | ||||||
|  |     SYNC(rtc->MODE0.STATUS.bit.SYNCBUSY); | ||||||
|  |  | ||||||
|  |     // Enable interrupt on compare | ||||||
|  |     rtc->MODE0.INTFLAG.reg = RTC_MODE0_INTFLAG_CMP0;    // reset pending interrupt | ||||||
|  |     rtc->MODE0.INTENSET.reg = RTC_MODE0_INTENSET_CMP0;  // enable compare 0 interrupt | ||||||
|  |  | ||||||
|  |     // And start timer | ||||||
|  |     rtc->MODE0.CTRL.bit.ENABLE = true; | ||||||
|  |     SYNC(rtc->MODE0.STATUS.bit.SYNCBUSY); | ||||||
|  |  | ||||||
|  |   } | ||||||
|  |   else if (timer_config[timer_num].type==TimerType::tcc) { | ||||||
|  |      | ||||||
|  |     Tcc * const tc = timer_config[timer_num].pTcc; | ||||||
|  |  | ||||||
|  |     PM->APBCMASK.reg |= PM_APBCMASK_TCC0; | ||||||
|  |      GCLK->CLKCTRL.reg =(GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(TCC0_GCLK_ID)); | ||||||
|  |     SYNC (GCLK->STATUS.bit.SYNCBUSY); | ||||||
|  |  | ||||||
|  |     tc->CTRLA.reg = TCC_CTRLA_SWRST; | ||||||
|  |     SYNC (tc->SYNCBUSY.reg & TCC_SYNCBUSY_SWRST) {} | ||||||
|  |  | ||||||
|  |     SYNC (tc->CTRLA.bit.SWRST); | ||||||
|  |  | ||||||
|  |     tc->CTRLA.reg &= ~(TCC_CTRLA_ENABLE);       // disable TC module | ||||||
|  |  | ||||||
|  |     tc->CTRLA.reg |= TCC_WAVE_WAVEGEN_MFRQ; | ||||||
|  |     tc->CTRLA.reg |= TCC_CTRLA_PRESCALER_DIV2; | ||||||
|  |     tc->CC[0].reg = (HAL_TIMER_RATE) / frequency; | ||||||
|  |     tc->INTENSET.reg = TCC_INTFLAG_MC0; | ||||||
|  |     tc->CTRLA.reg |= TCC_CTRLA_ENABLE; | ||||||
|  |     tc->INTFLAG.reg = 0xFF; | ||||||
|  |     SYNC ( tc->STATUS.reg & TC_STATUS_SYNCBUSY); | ||||||
|  |  | ||||||
|  |   } | ||||||
|  |   else { | ||||||
|  |     Tc * const tc = timer_config[timer_num].pTc; | ||||||
|  |  | ||||||
|  |     // Disable timer interrupt | ||||||
|  |     tc->COUNT32.INTENCLR.reg = TC_INTENCLR_OVF; // disable overflow interrupt | ||||||
|  |  | ||||||
|  |     // TCn clock setup | ||||||
|  |     GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0  | GCLK_CLKCTRL_ID(GCM_TC4_TC5)) ; | ||||||
|  |     SYNC (GCLK->STATUS.bit.SYNCBUSY); | ||||||
|  |  | ||||||
|  |     tcReset(tc); // reset TC | ||||||
|  |  | ||||||
|  |     // Set Timer counter 5 Mode to 16 bits, it will become a 16bit counter ('mode1' in the datasheet) | ||||||
|  |     tc->COUNT32.CTRLA.reg |= TC_CTRLA_MODE_COUNT32; | ||||||
|  |     // Set TC waveform generation mode to 'match frequency' | ||||||
|  |     tc->COUNT32.CTRLA.reg |= TC_CTRLA_WAVEGEN_MFRQ; | ||||||
|  |     //set prescaler | ||||||
|  |     //the clock normally counts at the GCLK_TC frequency, but we can set it to divide that frequency to slow it down | ||||||
|  |     //you can use different prescaler divisons here like TC_CTRLA_PRESCALER_DIV1 to get a different range | ||||||
|  |     tc->COUNT32.CTRLA.reg |= TC_CTRLA_PRESCALER_DIV1 | TC_CTRLA_ENABLE; //it will divide GCLK_TC frequency by 1024 | ||||||
|  |     //set the compare-capture register. | ||||||
|  |     //The counter will count up to this value (it's a 16bit counter so we use uint16_t) | ||||||
|  |     //this is how we fine-tune the frequency, make it count to a lower or higher value | ||||||
|  |     //system clock should be 1MHz (8MHz/8) at Reset by default | ||||||
|  |     tc->COUNT32.CC[0].reg = (uint16_t) (HAL_TIMER_RATE / frequency); | ||||||
|  |     while (tcIsSyncing(tc)) {} | ||||||
|  |  | ||||||
|  |     // Enable the TC interrupt request | ||||||
|  |     tc->COUNT32.INTENSET.bit.MC0 = 1; | ||||||
|  |     while (tcIsSyncing(tc)) {} | ||||||
|  |   } | ||||||
|  |  | ||||||
|  |   NVIC_SetPriority(irq, timer_config[timer_num].priority); | ||||||
|  |   NVIC_EnableIRQ(irq); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void HAL_timer_enable_interrupt(const uint8_t timer_num) { | ||||||
|  |   const IRQn_Type irq = timer_config[timer_num].IRQ_Id; | ||||||
|  |   NVIC_EnableIRQ(irq); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void HAL_timer_disable_interrupt(const uint8_t timer_num) { | ||||||
|  |   const IRQn_Type irq = timer_config[timer_num].IRQ_Id; | ||||||
|  |   Disable_Irq(irq); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | // missing from CMSIS: Check if interrupt is enabled or not | ||||||
|  | static bool NVIC_GetEnabledIRQ(IRQn_Type IRQn) { | ||||||
|  |   return TEST(NVIC->ISER[uint32_t(IRQn) >> 5], uint32_t(IRQn) & 0x1F); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { | ||||||
|  |   const IRQn_Type irq = timer_config[timer_num].IRQ_Id; | ||||||
|  |   return NVIC_GetEnabledIRQ(irq); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | #endif // __SAMD21__ | ||||||
							
								
								
									
										160
									
								
								Marlin/src/HAL/SAMD21/timers.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										160
									
								
								Marlin/src/HAL/SAMD21/timers.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,160 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #include <stdint.h> | ||||||
|  |  | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  | // Defines | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  |  | ||||||
|  | typedef uint32_t hal_timer_t; | ||||||
|  | #define HAL_TIMER_TYPE_MAX 0xFFFFFFFF | ||||||
|  |  | ||||||
|  | #define HAL_TIMER_RATE      F_CPU   // frequency of timers peripherals | ||||||
|  |  | ||||||
|  | #define MF_TIMER_RTC            8   // This is not a TC but a RTC | ||||||
|  |  | ||||||
|  | #ifndef MF_TIMER_STEP | ||||||
|  |   #define MF_TIMER_STEP         4   // Timer Index for Stepper | ||||||
|  | #endif | ||||||
|  | #ifndef MF_TIMER_PULSE | ||||||
|  |   #define MF_TIMER_PULSE        MF_TIMER_STEP | ||||||
|  | #endif | ||||||
|  | #ifndef MF_TIMER_TEMP | ||||||
|  |   #define MF_TIMER_TEMP         MF_TIMER_RTC // Timer Index for Temperature | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | #define TEMP_TIMER_FREQUENCY   1000 // temperature interrupt frequency | ||||||
|  |  | ||||||
|  | #define STEPPER_TIMER_RATE          HAL_TIMER_RATE   // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) | ||||||
|  | #define STEPPER_TIMER_TICKS_PER_US  (STEPPER_TIMER_RATE / 1000000) // stepper timer ticks per µs | ||||||
|  | #define STEPPER_TIMER_PRESCALE      (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) | ||||||
|  |  | ||||||
|  | #define PULSE_TIMER_RATE          STEPPER_TIMER_RATE | ||||||
|  | #define PULSE_TIMER_PRESCALE      STEPPER_TIMER_PRESCALE | ||||||
|  | #define PULSE_TIMER_TICKS_PER_US  STEPPER_TIMER_TICKS_PER_US | ||||||
|  |  | ||||||
|  | #define ENABLE_STEPPER_DRIVER_INTERRUPT()   HAL_timer_enable_interrupt(MF_TIMER_STEP) | ||||||
|  | #define DISABLE_STEPPER_DRIVER_INTERRUPT()  HAL_timer_disable_interrupt(MF_TIMER_STEP) | ||||||
|  | #define STEPPER_ISR_ENABLED()               HAL_timer_interrupt_enabled(MF_TIMER_STEP) | ||||||
|  |  | ||||||
|  | #define ENABLE_TEMPERATURE_INTERRUPT()  HAL_timer_enable_interrupt(MF_TIMER_TEMP) | ||||||
|  | #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) | ||||||
|  |  | ||||||
|  | #define TC_PRIORITY(t) (  t == SERVO_TC ? 1                              \ | ||||||
|  |                        : (t == MF_TIMER_STEP || t == MF_TIMER_PULSE) ? 2 \ | ||||||
|  |                        : (t == MF_TIMER_TEMP) ? 6 : 7 ) | ||||||
|  |  | ||||||
|  | #define _TC_HANDLER(t)          void TC##t##_Handler() | ||||||
|  | #define TC_HANDLER(t)           _TC_HANDLER(t) | ||||||
|  | #ifndef HAL_STEP_TIMER_ISR | ||||||
|  |   #define HAL_STEP_TIMER_ISR()  TC_HANDLER(MF_TIMER_STEP) | ||||||
|  | #endif | ||||||
|  | #if MF_TIMER_STEP != MF_TIMER_PULSE | ||||||
|  |   #define HAL_PULSE_TIMER_ISR() TC_HANDLER(MF_TIMER_PULSE) | ||||||
|  | #endif | ||||||
|  | #if MF_TIMER_TEMP == MF_TIMER_RTC | ||||||
|  |   #define HAL_TEMP_TIMER_ISR()  void RTC_Handler() | ||||||
|  | #else | ||||||
|  |   #define HAL_TEMP_TIMER_ISR()  TC_HANDLER(MF_TIMER_TEMP) | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  | // Types | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  | typedef enum  { tcc, tc, rtc } TimerType; | ||||||
|  |  | ||||||
|  | typedef struct { | ||||||
|  |   union { | ||||||
|  |     Tc  *pTc; | ||||||
|  |     Tcc *pTcc; | ||||||
|  |     Rtc *pRtc; | ||||||
|  |   }; | ||||||
|  |   TimerType type; | ||||||
|  |   IRQn_Type   IRQ_Id; | ||||||
|  |   uint8_t     priority; | ||||||
|  | } tTimerConfig; | ||||||
|  |  | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  | // Public Variables | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  |  | ||||||
|  | extern const tTimerConfig timer_config[]; | ||||||
|  |  | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  | // Public functions | ||||||
|  | // -------------------------------------------------------------------------- | ||||||
|  |  | ||||||
|  | void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); | ||||||
|  |  | ||||||
|  | FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { | ||||||
|  |   // Should never be called with timer MF_TIMER_RTC | ||||||
|  |   Tc * const tc = timer_config[timer_num].pTc; | ||||||
|  |   tc->COUNT32.CC[0].reg = compare; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { | ||||||
|  |   // Should never be called with timer MF_TIMER_RTC | ||||||
|  |   Tc * const tc = timer_config[timer_num].pTc; | ||||||
|  |   return (hal_timer_t)tc->COUNT32.CC[0].reg; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { | ||||||
|  |   // Should never be called with timer MF_TIMER_RTC | ||||||
|  |   Tc * const tc = timer_config[timer_num].pTc; | ||||||
|  |   tc->COUNT32.READREQ.reg = TC_READREQ_RREQ; | ||||||
|  |   // Request a read synchronization | ||||||
|  |   SYNC (tc->COUNT32.STATUS.bit.SYNCBUSY); | ||||||
|  |   //SYNC(tc->COUNT32.STATUS.bit.SYNCBUSY ); | ||||||
|  |   return tc->COUNT32.COUNT.reg; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void HAL_timer_enable_interrupt(const uint8_t timer_num); | ||||||
|  | void HAL_timer_disable_interrupt(const uint8_t timer_num); | ||||||
|  | bool HAL_timer_interrupt_enabled(const uint8_t timer_num); | ||||||
|  |  | ||||||
|  | FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { | ||||||
|  |   if (timer_num == MF_TIMER_RTC) { | ||||||
|  |     Rtc * const rtc = timer_config[timer_num].pRtc; | ||||||
|  |     // Clear interrupt flag | ||||||
|  |     rtc->MODE0.INTFLAG.reg = RTC_MODE0_INTFLAG_CMP0| RTC_MODE0_INTFLAG_OVF; | ||||||
|  |  | ||||||
|  |   } | ||||||
|  |   else if (timer_config[timer_num].type == TimerType::tcc){ | ||||||
|  |     Tcc * const tc = timer_config[timer_num].pTcc; | ||||||
|  |     // Clear interrupt flag | ||||||
|  |     tc->INTFLAG.reg = TCC_INTFLAG_OVF; | ||||||
|  |   } | ||||||
|  |   else { | ||||||
|  |     Tc * const tc = timer_config[timer_num].pTc; | ||||||
|  |     // Clear interrupt flag | ||||||
|  |     tc->COUNT32.INTFLAG.bit.MC0 = 1; | ||||||
|  |   } | ||||||
|  | } | ||||||
|  |  | ||||||
|  | #define HAL_timer_isr_epilogue(timer_num) | ||||||
							
								
								
									
										32
									
								
								Marlin/src/HAL/SAMD21/u8g/LCD_I2C_routines.cpp
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										32
									
								
								Marlin/src/HAL/SAMD21/u8g/LCD_I2C_routines.cpp
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,32 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  | // adapted from  I2C/master/master.c example | ||||||
|  | //   https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html | ||||||
|  |  | ||||||
|  | #ifdef __SAMD21__ | ||||||
|  |  | ||||||
|  | #endif // __SAMD21__ | ||||||
							
								
								
									
										27
									
								
								Marlin/src/HAL/SAMD21/u8g/LCD_I2C_routines.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										27
									
								
								Marlin/src/HAL/SAMD21/u8g/LCD_I2C_routines.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,27 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
							
								
								
									
										41
									
								
								Marlin/src/HAL/SAMD21/u8g/LCD_defines.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										41
									
								
								Marlin/src/HAL/SAMD21/u8g/LCD_defines.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,41 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 LCD-specific defines | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | // The following are optional depending on the platform. | ||||||
|  |  | ||||||
|  | // definitions of HAL specific com and device drivers. | ||||||
|  | uint8_t u8g_com_samd21_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); | ||||||
|  | uint8_t u8g_com_samd21_st7920_hw_spi_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_samd21_st7920_hw_spi_fn  // use SAMD21 specific hardware SPI routine | ||||||
|  | #define U8G_COM_ST7920_HW_SPI u8g_com_samd21_st7920_hw_spi_fn | ||||||
							
								
								
									
										42
									
								
								Marlin/src/HAL/SAMD21/u8g/LCD_pin_routines.c
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										42
									
								
								Marlin/src/HAL/SAMD21/u8g/LCD_pin_routines.c
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,42 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Low level pin manipulation routines - used by all the drivers. | ||||||
|  |  * | ||||||
|  |  * These are based on the SAMD51 pinMode, digitalRead & digitalWrite routines. | ||||||
|  |  * | ||||||
|  |  * Couldn't just call exact copies because the overhead killed the LCD update speed | ||||||
|  |  * With an intermediate level the softspi was running in the 10-20kHz range which | ||||||
|  |  * resulted in using about about 25% of the CPU's time. | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #ifdef __SAMD21__ | ||||||
|  |  | ||||||
|  | #include <Arduino.h> | ||||||
|  |  | ||||||
|  | #endif // __SAMD21__ | ||||||
							
								
								
									
										42
									
								
								Marlin/src/HAL/SAMD21/u8g/LCD_pin_routines.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										42
									
								
								Marlin/src/HAL/SAMD21/u8g/LCD_pin_routines.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,42 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Low level pin manipulation routines - used by all the drivers. | ||||||
|  |  * | ||||||
|  |  * These are based on the SAMD51 pinMode, digitalRead & digitalWrite routines. | ||||||
|  |  * | ||||||
|  |  * Couldn't just call exact copies because the overhead killed the LCD update speed | ||||||
|  |  * With an intermediate level the softspi was running in the 10-20kHz range which | ||||||
|  |  * resulted in using about about 25% of the CPU's time. | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | void u8g_SetPinOutput(uint8_t internal_pin_number); | ||||||
|  | void u8g_SetPinInput(uint8_t internal_pin_number); | ||||||
|  | void u8g_SetPinLevel(uint8_t  pin, uint8_t  pin_status); | ||||||
|  | uint8_t u8g_GetPinLevel(uint8_t pin); | ||||||
							
								
								
									
										154
									
								
								Marlin/src/HAL/SAMD21/u8g/u8g_com_HAL_samd21_shared_hw_spi.cpp
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										154
									
								
								Marlin/src/HAL/SAMD21/u8g/u8g_com_HAL_samd21_shared_hw_spi.cpp
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,154 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * SAMD21 HAL developed by Bart Meijer (brupje) | ||||||
|  |  * Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician) | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * Based on u8g_com_msp430_hw_spi.c | ||||||
|  |  * | ||||||
|  |  * Universal 8bit Graphics Library | ||||||
|  |  * | ||||||
|  |  * Copyright (c) 2012, olikraus@gmail.com | ||||||
|  |  * All rights reserved. | ||||||
|  |  * | ||||||
|  |  * Redistribution and use in source and binary forms, with or without modification, | ||||||
|  |  * are permitted provided that the following conditions are met: | ||||||
|  |  * | ||||||
|  |  * * Redistributions of source code must retain the above copyright notice, this list | ||||||
|  |  * of conditions and the following disclaimer. | ||||||
|  |  * | ||||||
|  |  * * Redistributions in binary form must reproduce the above copyright notice, this | ||||||
|  |  * list of conditions and the following disclaimer in the documentation and/or other | ||||||
|  |  * materials provided with the distribution. | ||||||
|  |  * | ||||||
|  |  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND | ||||||
|  |  * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, | ||||||
|  |  * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF | ||||||
|  |  * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE | ||||||
|  |  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR | ||||||
|  |  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, | ||||||
|  |  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT | ||||||
|  |  * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; | ||||||
|  |  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER | ||||||
|  |  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, | ||||||
|  |  * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) | ||||||
|  |  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF | ||||||
|  |  * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #ifdef __SAMD21__ | ||||||
|  |  | ||||||
|  | #include <U8glib-HAL.h> | ||||||
|  | #include "SPI.h" | ||||||
|  |  | ||||||
|  | #include "../../shared/HAL_SPI.h" | ||||||
|  |  | ||||||
|  | #ifndef LCD_SPI_SPEED | ||||||
|  |   #define LCD_SPI_SPEED SPI_QUARTER_SPEED | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | void u8g_SetPIOutput(u8g_t *u8g, uint8_t pin_index) { | ||||||
|  |   if (u8g->pin_list[pin_index]!= U8G_PIN_NONE) | ||||||
|  |   pinMode(u8g->pin_list[pin_index],OUTPUT); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | void u8g_SetPILevel(u8g_t *u8g, uint8_t pin_index, uint8_t level) { | ||||||
|  |   if (u8g->pin_list[pin_index]!= U8G_PIN_NONE) | ||||||
|  |   digitalWrite(u8g->pin_list[pin_index],level); | ||||||
|  | } | ||||||
|  |  | ||||||
|  | uint8_t u8g_com_samd21_st7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { | ||||||
|  |  | ||||||
|  |   static SPISettings lcdSPIConfig; | ||||||
|  |  | ||||||
|  |   switch (msg) { | ||||||
|  |     case U8G_COM_MSG_STOP: | ||||||
|  |       break; | ||||||
|  |  | ||||||
|  |     case U8G_COM_MSG_INIT: | ||||||
|  |       u8g_SetPIOutput(u8g, U8G_PI_CS); | ||||||
|  |       u8g_SetPIOutput(u8g, U8G_PI_A0); | ||||||
|  |       u8g_SetPIOutput(u8g, U8G_PI_RESET); | ||||||
|  |  | ||||||
|  |       u8g_SetPILevel(u8g, U8G_PI_CS, LOW); | ||||||
|  |  | ||||||
|  |       spiBegin(); | ||||||
|  |       lcdSPIConfig = SPISettings(900000, MSBFIRST, SPI_MODE0); | ||||||
|  |       u8g->pin_list[U8G_PI_A0_STATE] = 0; | ||||||
|  |       break; | ||||||
|  |  | ||||||
|  |     case U8G_COM_MSG_ADDRESS:             // define cmd (arg_val = 0) or data mode (arg_val = 1) | ||||||
|  |       u8g_SetPILevel(u8g, U8G_PI_A0, arg_val); | ||||||
|  |       u8g->pin_list[U8G_PI_A0_STATE] = arg_val; | ||||||
|  |       break; | ||||||
|  |  | ||||||
|  |     case U8G_COM_MSG_CHIP_SELECT:         // arg_val == 1 means chip selected, but ST7920 is active high, so needs inverting | ||||||
|  |       u8g_SetPILevel(u8g, U8G_PI_CS, arg_val ? HIGH : LOW); | ||||||
|  |       break; | ||||||
|  |  | ||||||
|  |     case U8G_COM_MSG_RESET: | ||||||
|  |       u8g_SetPILevel(u8g, U8G_PI_RESET, arg_val); | ||||||
|  |       break; | ||||||
|  |  | ||||||
|  |     case U8G_COM_MSG_WRITE_BYTE: | ||||||
|  |       SPI.beginTransaction(lcdSPIConfig); | ||||||
|  |  | ||||||
|  |       if (u8g->pin_list[U8G_PI_A0_STATE] == 0) { // command | ||||||
|  |         SPI.transfer(0x0f8); u8g->pin_list[U8G_PI_A0_STATE] = 2; | ||||||
|  |       } | ||||||
|  |       else if (u8g->pin_list[U8G_PI_A0_STATE] == 1) { // data | ||||||
|  |         SPI.transfer(0x0fa); u8g->pin_list[U8G_PI_A0_STATE] = 2; | ||||||
|  |       } | ||||||
|  |  | ||||||
|  |       SPI.transfer(arg_val & 0x0f0); | ||||||
|  |       SPI.transfer(arg_val << 4); | ||||||
|  |       SPI.endTransaction(); | ||||||
|  |       break; | ||||||
|  |  | ||||||
|  |     case U8G_COM_MSG_WRITE_SEQ: | ||||||
|  |       SPI.beginTransaction(lcdSPIConfig); | ||||||
|  |  | ||||||
|  |       if (u8g->pin_list[U8G_PI_A0_STATE] == 0 ) { // command | ||||||
|  |         SPI.transfer(0x0f8); u8g->pin_list[U8G_PI_A0_STATE] = 2; | ||||||
|  |       } | ||||||
|  |       else if (u8g->pin_list[U8G_PI_A0_STATE] == 1) { // data | ||||||
|  |         SPI.transfer(0x0fa); u8g->pin_list[U8G_PI_A0_STATE] = 2; | ||||||
|  |       } | ||||||
|  |  | ||||||
|  |       uint8_t *ptr = (uint8_t*)arg_ptr; | ||||||
|  |       while (arg_val > 0) { | ||||||
|  |         SPI.transfer((*ptr) & 0x0f0); | ||||||
|  |         SPI.transfer((*ptr) << 4); | ||||||
|  |         ptr++; | ||||||
|  |         arg_val--; | ||||||
|  |       } | ||||||
|  |  | ||||||
|  |       SPI.endTransaction(); | ||||||
|  |       break; | ||||||
|  |   } | ||||||
|  |   return 1; | ||||||
|  | } | ||||||
|  |  | ||||||
|  | #endif // __SAMD21__ | ||||||
| @@ -50,6 +50,8 @@ | |||||||
|   #define HAL_PATH(PATH, NAME) XSTR(PATH/NATIVE_SIM/NAME) |   #define HAL_PATH(PATH, NAME) XSTR(PATH/NATIVE_SIM/NAME) | ||||||
| #elif defined(__SAMD51__) | #elif defined(__SAMD51__) | ||||||
|   #define HAL_PATH(PATH, NAME) XSTR(PATH/SAMD51/NAME) |   #define HAL_PATH(PATH, NAME) XSTR(PATH/SAMD51/NAME) | ||||||
|  | #elif defined(__SAMD21__) | ||||||
|  |   #define HAL_PATH(PATH, NAME) XSTR(PATH/SAMD21/NAME) | ||||||
| #else | #else | ||||||
|   #error "Unsupported Platform!" |   #error "Unsupported Platform!" | ||||||
| #endif | #endif | ||||||
|   | |||||||
| @@ -83,10 +83,10 @@ | |||||||
| #else | #else | ||||||
|   #include <stdint.h> |   #include <stdint.h> | ||||||
|  |  | ||||||
|   #if defined(__AVR__) || defined(ARDUINO_ARCH_SAM) || defined(__SAMD51__) |   #if defined(__AVR__) || defined(ARDUINO_ARCH_SAM) || defined(__SAMD51__) || defined(__SAMD21__) | ||||||
|     // we're good to go |     // we're good to go | ||||||
|   #else |   #else | ||||||
|     #error "This library only supports boards with an AVR, SAM3X or SAMD51 processor." |     #error "This library only supports boards with an AVR, SAM3X, SAMD21 or SAMD51 processor." | ||||||
|   #endif |   #endif | ||||||
|  |  | ||||||
|   #define Servo_VERSION           2     // software version of this library |   #define Servo_VERSION           2     // software version of this library | ||||||
|   | |||||||
| @@ -49,8 +49,10 @@ | |||||||
|   #include "../DUE/ServoTimers.h" |   #include "../DUE/ServoTimers.h" | ||||||
| #elif defined(__SAMD51__) | #elif defined(__SAMD51__) | ||||||
|   #include "../SAMD51/ServoTimers.h" |   #include "../SAMD51/ServoTimers.h" | ||||||
|  | #elif defined(__SAMD21__) | ||||||
|  |   #include "../SAMD21/ServoTimers.h" | ||||||
| #else | #else | ||||||
|   #error "This library only supports boards with an AVR, SAM3X or SAMD51 processor." |   #error "This library only supports boards with an AVR, SAM3X, SAMD21 or SAMD51 processor." | ||||||
| #endif | #endif | ||||||
|  |  | ||||||
| // Macros | // Macros | ||||||
|   | |||||||
| @@ -465,6 +465,12 @@ | |||||||
| #define BOARD_BRICOLEMON_V1_0         6101  // Bricolemon | #define BOARD_BRICOLEMON_V1_0         6101  // Bricolemon | ||||||
| #define BOARD_BRICOLEMON_LITE_V1_0    6102  // Bricolemon Lite | #define BOARD_BRICOLEMON_LITE_V1_0    6102  // Bricolemon Lite | ||||||
|  |  | ||||||
|  | // | ||||||
|  | // SAMD21 ARM Cortex M4 | ||||||
|  | // | ||||||
|  |  | ||||||
|  | #define BOARD_MINITRONICS20           6103  // Minitronics v2.0 | ||||||
|  |  | ||||||
| // | // | ||||||
| // Custom board | // Custom board | ||||||
| // | // | ||||||
|   | |||||||
| @@ -137,6 +137,7 @@ | |||||||
|   #define DOGLCD |   #define DOGLCD | ||||||
|   #define IS_U8GLIB_ST7920 1 |   #define IS_U8GLIB_ST7920 1 | ||||||
|   #define IS_ULTIPANEL 1 |   #define IS_ULTIPANEL 1 | ||||||
|  |   #define ENCODER_PULSES_PER_STEP 2 | ||||||
|  |  | ||||||
| #elif ENABLED(MKS_12864OLED) | #elif ENABLED(MKS_12864OLED) | ||||||
|  |  | ||||||
|   | |||||||
| @@ -41,6 +41,13 @@ | |||||||
|     #define U8G_COM_HAL_HW_SPI_FN     u8g_com_samd51_hw_spi_fn |     #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 |     #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__) |   #elif defined(__STM32F1__) | ||||||
|  |  | ||||||
|     uint8_t u8g_com_HAL_STM32F1_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); |     uint8_t u8g_com_HAL_STM32F1_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); | ||||||
|   | |||||||
| @@ -36,10 +36,16 @@ | |||||||
|  |  | ||||||
|   // RepRapWorld Graphical LCD |   // RepRapWorld Graphical LCD | ||||||
|  |  | ||||||
|   #define U8G_CLASS U8GLIB_ST7920_128X64_4X |  | ||||||
|   #if DISABLED(SDSUPPORT) && (LCD_PINS_D4 == SD_SCK_PIN) && (LCD_PINS_ENABLE == SD_MOSI_PIN) |   #if DISABLED(SDSUPPORT) && (LCD_PINS_D4 == SD_SCK_PIN) && (LCD_PINS_ENABLE == SD_MOSI_PIN) | ||||||
|  |     #define U8G_CLASS U8GLIB_ST7920_128X64_4X_HAL | ||||||
|  |     #define U8G_PARAM LCD_PINS_RS | ||||||
|  |   #elif ENABLED(SDSUPPORT) && __SAMD21__ | ||||||
|  |  | ||||||
|  |     #define U8G_CLASS U8GLIB_ST7920_128X64_4X | ||||||
|     #define U8G_PARAM LCD_PINS_RS |     #define U8G_PARAM LCD_PINS_RS | ||||||
|   #else |   #else | ||||||
|  |     #define U8G_CLASS U8GLIB_ST7920_128X64_4X | ||||||
|     #define U8G_PARAM LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS |     #define U8G_PARAM LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS | ||||||
|   #endif |   #endif | ||||||
|  |  | ||||||
|   | |||||||
| @@ -72,6 +72,17 @@ void ChironTFT::Startup() { | |||||||
|   live_Zoffset      = 0.0; |   live_Zoffset      = 0.0; | ||||||
|   file_menu         = AC_menu_file; |   file_menu         = AC_menu_file; | ||||||
|  |  | ||||||
|  |   // Setup pins for powerloss detection | ||||||
|  |   // Two IO pins are connected on the Trigorilla Board | ||||||
|  |   // On a power interruption the OUTAGECON_PIN goes low. | ||||||
|  |  | ||||||
|  |   #if ENABLED(POWER_LOSS_RECOVERY) | ||||||
|  |     OUT_WRITE(OUTAGECON_PIN, HIGH); | ||||||
|  |   #endif | ||||||
|  |  | ||||||
|  |   // Filament runout is handled by Marlin settings in Configuration.h | ||||||
|  |   // opt_set    FIL_RUNOUT_STATE HIGH  // Pin state indicating that filament is NOT present. | ||||||
|  |   // opt_enable FIL_RUNOUT_PULLUP | ||||||
|   TFTSer.begin(115200); |   TFTSer.begin(115200); | ||||||
|  |  | ||||||
|   // Wait for the TFT panel to initialize and finish the animation |   // Wait for the TFT panel to initialize and finish the animation | ||||||
|   | |||||||
| @@ -773,6 +773,13 @@ | |||||||
| #elif MB(BRICOLEMON_LITE_V1_0) | #elif MB(BRICOLEMON_LITE_V1_0) | ||||||
|   #include "samd/pins_BRICOLEMON_LITE_V1_0.h"   // SAMD51                                 env:SAMD51_grandcentral_m4 |   #include "samd/pins_BRICOLEMON_LITE_V1_0.h"   // SAMD51                                 env:SAMD51_grandcentral_m4 | ||||||
|  |  | ||||||
|  | // | ||||||
|  | // ReprapWorld Minitronics (SAMD21) | ||||||
|  | // | ||||||
|  |  | ||||||
|  | #elif MB(MINITRONICS20) | ||||||
|  |   #include "samd/pins_MINITRONICS20.h"          // SAMD21                                 env:SAMD21_minitronics20 | ||||||
|  |  | ||||||
| // | // | ||||||
| // Custom board (with custom PIO env) | // Custom board (with custom PIO env) | ||||||
| // | // | ||||||
|   | |||||||
							
								
								
									
										556
									
								
								Marlin/src/pins/samd/pins_MINITRONICS20.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										556
									
								
								Marlin/src/pins/samd/pins_MINITRONICS20.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,556 @@ | |||||||
|  | /** | ||||||
|  |  * Marlin 3D Printer Firmware | ||||||
|  |  * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] | ||||||
|  |  * | ||||||
|  |  * Based on Sprinter and grbl. | ||||||
|  |  * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm | ||||||
|  |  * | ||||||
|  |  * This program is free software: you can redistribute it and/or modify | ||||||
|  |  * it under the terms of the GNU General Public License as published by | ||||||
|  |  * the Free Software Foundation, either version 3 of the License, or | ||||||
|  |  * (at your option) any later version. | ||||||
|  |  * | ||||||
|  |  * This program is distributed in the hope that it will be useful, | ||||||
|  |  * but WITHOUT ANY WARRANTY; without even the implied warranty of | ||||||
|  |  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the | ||||||
|  |  * GNU General Public License for more details. | ||||||
|  |  * | ||||||
|  |  * You should have received a copy of the GNU General Public License | ||||||
|  |  * along with this program.  If not, see <https://www.gnu.org/licenses/>. | ||||||
|  |  * | ||||||
|  |  */ | ||||||
|  | #pragma once | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * ReprapWorld's Minitronics v2.0 | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #if NOT_TARGET(__SAMD21__) | ||||||
|  |   #error "Oops! Select 'Minitronics v2.0' in 'Tools > Board.'" | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | #ifndef BOARD_INFO_NAME | ||||||
|  |   #define BOARD_INFO_NAME "Minitronics V2.0" | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * NOTE: We need the Serial port on the -1 to make it work!!. Remember to change it on configuration.h #define SERIAL_PORT -1 | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | /** | ||||||
|  |  * EEPROM EMULATION: Works with some bugs already, but the board needs an I2C EEPROM memory soldered on. | ||||||
|  |  */ | ||||||
|  | //#define FLASH_EEPROM_EMULATION | ||||||
|  | //#define I2C_EEPROM                              // EEPROM on I2C-0 | ||||||
|  | #define MARLIN_EEPROM_SIZE                   500  // 4000 bytes | ||||||
|  |  | ||||||
|  | //This its another option to emulate an EEPROM, but its more efficient to dont loose the data the first One. | ||||||
|  | //#define SDCARD_EEPROM_EMULATION | ||||||
|  |  | ||||||
|  | // | ||||||
|  | // BLTouch | ||||||
|  | // | ||||||
|  | #define SERVO0_PIN                            33  // BLTouch PWM | ||||||
|  |  | ||||||
|  | // | ||||||
|  | //  Limit Switches | ||||||
|  | // | ||||||
|  | #define X_STOP_PIN                            54 | ||||||
|  | #define Y_STOP_PIN                            55 | ||||||
|  | #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. | ||||||
|  |  */ | ||||||
|  | //#define Z2_STOP_PIN                         14 | ||||||
|  | //#define X2_STOP_PIN                         14 | ||||||
|  | //#define Y2_STOP_PIN                         14 | ||||||
|  |  | ||||||
|  | // | ||||||
|  | // Z Probe (when not Z_MIN_PIN) | ||||||
|  | // | ||||||
|  | #ifndef Z_MIN_PROBE_PIN | ||||||
|  |   #define Z_MIN_PROBE_PIN                     12 | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | // | ||||||
|  | // Steppers | ||||||
|  | // | ||||||
|  | #define X_STEP_PIN                             1 | ||||||
|  | #define X_DIR_PIN                              3 | ||||||
|  | #define X_ENABLE_PIN                           0 | ||||||
|  |  | ||||||
|  | #define Y_STEP_PIN                            29 | ||||||
|  | #define Y_DIR_PIN                             28 | ||||||
|  | #define Y_ENABLE_PIN                           0 | ||||||
|  |  | ||||||
|  | #define Z_STEP_PIN                            16 | ||||||
|  | #define Z_DIR_PIN                             17 | ||||||
|  | #define Z_ENABLE_PIN                           0 | ||||||
|  |  | ||||||
|  | #define E0_STEP_PIN                           14 | ||||||
|  | #define E0_DIR_PIN                            15 | ||||||
|  | #define E0_ENABLE_PIN                          0 | ||||||
|  |  | ||||||
|  | #define E1_STEP_PIN                           20 | ||||||
|  | #define E1_DIR_PIN                            13 | ||||||
|  | #define E1_ENABLE_PIN                         21 | ||||||
|  |  | ||||||
|  | // Filament runout. You may choose to use this pin for some other purpose. It's a normal GPIO that can be configured as I/O. | ||||||
|  | // For example, a switch to detect any kind of behavior, Power supply pin .... etc. | ||||||
|  | #ifndef FIL_RUNOUT_PIN | ||||||
|  |   #define FIL_RUNOUT_PIN                      44 | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | // 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 | ||||||
|  |   #if NUM_Z_STEPPERS > 1 | ||||||
|  |     #define Z2_STOP_PIN                       14 | ||||||
|  |   #endif | ||||||
|  | #else | ||||||
|  |   // If we want to configure the extra stepper as a Extruder, we should have undef all of the extra motors. | ||||||
|  |   #undef X2_DRIVER_TYPE | ||||||
|  |   #undef Y2_DRIVER_TYPE | ||||||
|  |   #undef Z2_DRIVER_TYPE | ||||||
|  |   #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 | ||||||
|  |  | ||||||
|  |   #define FIL_RUNOUT2_PIN                     14 | ||||||
|  |  | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | // | ||||||
|  | // Extruder / Bed | ||||||
|  | // | ||||||
|  |  | ||||||
|  | // Temperature Sensors | ||||||
|  | #define TEMP_0_PIN                             4  // T1 | ||||||
|  |  | ||||||
|  | // You could use one of the ADC for a temp chamber if you don't use the second extruder, for example. | ||||||
|  | #if TEMP_SENSOR_CHAMBER > 0 | ||||||
|  |   #define TEMP_CHAMBER_PIN                     3 | ||||||
|  | #else | ||||||
|  |   #define TEMP_1_PIN                           2  // T3 | ||||||
|  | #endif | ||||||
|  |  | ||||||
|  | #define TEMP_BED_PIN                           3  // T2 | ||||||
|  |  | ||||||
|  | // | ||||||
|  | // Heaters / Fans | ||||||
|  | // | ||||||
|  | #define HEATER_0_PIN                          10 | ||||||
|  | #define HEATER_1_PIN                          11 | ||||||
|  | #define HEATER_BED_PIN                         6 | ||||||
|  | #define SPINDLE_LASER_PWM_PIN                  6 | ||||||
|  |  | ||||||
|  | // The board has 4 PWM fans, use and configure as desired | ||||||
|  | #define FAN_PIN                               24 | ||||||
|  |  | ||||||
|  | // | ||||||
|  | // LCD / Controller | ||||||
|  | // | ||||||
|  |  | ||||||
|  | #if ENABLED(CR10_STOCKDISPLAY) | ||||||
|  |   #define EXP3_01_PIN                EXP1_01_PIN | ||||||
|  |   #define EXP3_02_PIN                EXP1_02_PIN | ||||||
|  |   #define EXP3_03_PIN                EXP1_03_PIN | ||||||
|  |   #define EXP3_04_PIN                EXP1_04_PIN | ||||||
|  |   #define EXP3_05_PIN                EXP1_05_PIN | ||||||
|  |   #define EXP3_06_PIN                EXP1_06_PIN | ||||||
|  |   #define EXP3_07_PIN                EXP1_07_PIN | ||||||
|  |   #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. | ||||||
|  |  * Tested: | ||||||
|  |  *   - Ender 3 Old display (Character LCD) | ||||||
|  |  *   - Ender 3 New Serial DWING Display | ||||||
|  |  *   - Reprap Display | ||||||
|  |  *   - Ender 5 New Serial Display | ||||||
|  |  *   - Any Reprap character display like | ||||||
|  |  */ | ||||||
|  |  | ||||||
|  | #if HAS_WIRED_LCD | ||||||
|  |  | ||||||
|  |   // | ||||||
|  |   // LCD Display output pins | ||||||
|  |   // | ||||||
|  |  | ||||||
|  |   #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) | ||||||
|  |  | ||||||
|  |     #define LCD_PINS_RS                       18  // CS chip select /SS chip slave select | ||||||
|  |     #define LCD_PINS_ENABLE                 MOSI  // SID (MOSI) | ||||||
|  |     #define LCD_PINS_D4                      SCK  // SCK (CLK) clock | ||||||
|  |  | ||||||
|  |     #define BTN_ENC                           23 | ||||||
|  |     #define BTN_EN1                           27 | ||||||
|  |     #define BTN_EN2                           33 | ||||||
|  |  | ||||||
|  |   #elif BOTH(IS_NEWPANEL, PANEL_ONE) | ||||||
|  |  | ||||||
|  |     // TO TEST | ||||||
|  |     //#define LCD_PINS_RS            EXP1_02_PIN | ||||||
|  |     //#define LCD_PINS_ENABLE        EXP2_05_PIN | ||||||
|  |     //#define LCD_PINS_D4                     57  // Mega/Due:65 - AGCM4:57 | ||||||
|  |     //#define LCD_PINS_D5                     58  // Mega/Due:66 - AGCM4:58 | ||||||
|  |     //#define LCD_PINS_D6            EXP2_07_PIN | ||||||
|  |     //#define LCD_PINS_D7                     56  // Mega/Due:64 - AGCM4:56 | ||||||
|  |  | ||||||
|  |   #else | ||||||
|  |  | ||||||
|  |     #if ENABLED(CR10_STOCKDISPLAY) | ||||||
|  |  | ||||||
|  |       // TO TEST | ||||||
|  |       //#define LCD_PINS_RS            EXP3_04_PIN | ||||||
|  |       //#define LCD_PINS_ENABLE        EXP3_03_PIN | ||||||
|  |       //#define LCD_PINS_D4            EXP3_05_PIN | ||||||
|  |  | ||||||
|  |       #if !IS_NEWPANEL | ||||||
|  |         // TO TEST | ||||||
|  |         //#define BEEPER_PIN         EXP3_05_PIN | ||||||
|  |       #endif | ||||||
|  |  | ||||||
|  |     #elif ENABLED(ZONESTAR_LCD) | ||||||
|  |  | ||||||
|  |       // TO TEST | ||||||
|  |       //#define LCD_PINS_RS                   56  // Mega/Due:64 - AGCM4:56 | ||||||
|  |       //#define LCD_PINS_ENABLE      EXP2_07_PIN | ||||||
|  |       //#define LCD_PINS_D4                   55  // Mega/Due:63 - AGCM4:55 | ||||||
|  |       //#define LCD_PINS_D5          EXP1_02_PIN | ||||||
|  |       //#define LCD_PINS_D6          EXP2_05_PIN | ||||||
|  |       //#define LCD_PINS_D7                   57  // Mega/Due:65 - AGCM4:57 | ||||||
|  |  | ||||||
|  |     #else | ||||||
|  |  | ||||||
|  |       #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) | ||||||
|  |         // TO TEST | ||||||
|  |         //#define LCD_PINS_DC                 25  // Set as output on init | ||||||
|  |         //#define LCD_PINS_RS                 27  // Pull low for 1s to init | ||||||
|  |         // DOGM SPI LCD Support | ||||||
|  |         //#define DOGLCD_CS                   16 | ||||||
|  |         //#define DOGLCD_MOSI                 17 | ||||||
|  |         //#define DOGLCD_SCK                  23 | ||||||
|  |         //#define DOGLCD_A0          LCD_PINS_DC | ||||||
|  |  | ||||||
|  |       #else | ||||||
|  |         // Definitions for any standard Display | ||||||
|  |         #define LCD_PINS_RS          EXP1_04_PIN | ||||||
|  |         #define LCD_PINS_ENABLE      EXP1_03_PIN | ||||||
|  |         #define LCD_PINS_D4          EXP1_05_PIN | ||||||
|  |         #define LCD_PINS_D5          EXP1_06_PIN | ||||||
|  |         #define LCD_PINS_D6          EXP1_07_PIN | ||||||
|  |       #endif | ||||||
|  |  | ||||||
|  |       #define LCD_PINS_D7            EXP1_08_PIN | ||||||
|  |  | ||||||
|  |       #if !IS_NEWPANEL | ||||||
|  |         #define BEEPER_PIN           EXP1_01_PIN | ||||||
|  |       #endif | ||||||
|  |  | ||||||
|  |     #endif | ||||||
|  |  | ||||||
|  |     #if !IS_NEWPANEL | ||||||
|  |       // Buttons attached to a shift register | ||||||
|  |       // Not wired yet | ||||||
|  |       //#define SHIFT_CLK_PIN        EXP1_07_PIN | ||||||
|  |       //#define SHIFT_LD_PIN         EXP2_05_PIN | ||||||
|  |       //#define SHIFT_OUT_PIN        EXP1_02_PIN | ||||||
|  |       //#define SHIFT_EN_PIN                  17 | ||||||
|  |     #endif | ||||||
|  |  | ||||||
|  |   #endif | ||||||
|  |  | ||||||
|  |   // | ||||||
|  |   // LCD Display input pins | ||||||
|  |   // | ||||||
|  |   #if IS_NEWPANEL | ||||||
|  |  | ||||||
|  |     #if IS_RRD_SC | ||||||
|  |  | ||||||
|  |       //#define BEEPER_PIN             EXP1_01_PIN | ||||||
|  |  | ||||||
|  |       #if ENABLED(CR10_STOCKDISPLAY) | ||||||
|  |         // TO TEST | ||||||
|  |         #define BTN_EN1              EXP1_03_PIN | ||||||
|  |         #define BTN_EN2              EXP1_05_PIN | ||||||
|  |       #else | ||||||
|  |         // Definitions fpr any standard Display | ||||||
|  |         #define BTN_EN1              EXP2_05_PIN | ||||||
|  |         #define BTN_EN2              EXP2_03_PIN | ||||||
|  |         #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) | ||||||
|  |           #define BTN_ENC_EN         LCD_PINS_D7  // Detect the presence of the encoder | ||||||
|  |         #endif | ||||||
|  |       #endif | ||||||
|  |  | ||||||
|  |       #define BTN_ENC                EXP1_02_PIN | ||||||
|  |       #ifndef SD_DETECT_PIN | ||||||
|  |         #define SD_DETECT_PIN        EXP2_07_PIN | ||||||
|  |       #endif | ||||||
|  |       //#define KILL_PIN               EXP2_10_PIN | ||||||
|  |  | ||||||
|  |       #if ENABLED(BQ_LCD_SMART_CONTROLLER) | ||||||
|  |         //#define LCD_BACKLIGHT_PIN  EXP1_08_PIN  // TO TEST | ||||||
|  |       #endif | ||||||
|  |  | ||||||
|  |     #elif ENABLED(LCD_I2C_PANELOLU2) | ||||||
|  |  | ||||||
|  |       // TO TEST | ||||||
|  |       //#define BTN_EN1                       47 | ||||||
|  |       //#define BTN_EN2              EXP2_03_PIN | ||||||
|  |       //#define BTN_ENC                       32 | ||||||
|  |       //#define LCD_SDSS                    SDSS | ||||||
|  |       //#define KILL_PIN             EXP1_01_PIN | ||||||
|  |  | ||||||
|  |     #elif ENABLED(LCD_I2C_VIKI) | ||||||
|  |  | ||||||
|  |       // TO TEST | ||||||
|  |       //#define BTN_EN1              EXP1_02_PIN  // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. | ||||||
|  |       //#define BTN_EN2              EXP2_05_PIN | ||||||
|  |       //#define BTN_ENC                       -1 | ||||||
|  |  | ||||||
|  |       //#define LCD_SDSS                    SDSS | ||||||
|  |       //#define SD_DETECT_PIN        EXP2_10_PIN | ||||||
|  |  | ||||||
|  |     #elif EITHER(VIKI2, miniVIKI) | ||||||
|  |  | ||||||
|  |       // TO TEST | ||||||
|  |       //#define DOGLCD_CS                     45 | ||||||
|  |       //#define DOGLCD_A0            EXP2_07_PIN | ||||||
|  |       //#define LCD_SCREEN_ROT_180 | ||||||
|  |  | ||||||
|  |       //#define BEEPER_PIN                    33 | ||||||
|  |       //#define STAT_LED_RED_PIN              32 | ||||||
|  |       //#define STAT_LED_BLUE_PIN    EXP1_03_PIN | ||||||
|  |  | ||||||
|  |       //#define BTN_EN1                       22 | ||||||
|  |       //#define BTN_EN2                        7 | ||||||
|  |       //#define BTN_ENC              EXP1_08_PIN | ||||||
|  |  | ||||||
|  |       //#define SD_DETECT_PIN                 -1  // Pin 49 for display SD interface, 72 for easy adapter board | ||||||
|  |       //#define KILL_PIN                      31 | ||||||
|  |  | ||||||
|  |     #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) | ||||||
|  |  | ||||||
|  |       // TO TEST | ||||||
|  |       //#define DOGLCD_CS                     29 | ||||||
|  |       //#define DOGLCD_A0                     27 | ||||||
|  |  | ||||||
|  |       //#define BEEPER_PIN                    23 | ||||||
|  |       //#define LCD_BACKLIGHT_PIN             33 | ||||||
|  |  | ||||||
|  |       //#define BTN_EN1              EXP1_03_PIN | ||||||
|  |       //#define BTN_EN2              EXP1_06_PIN | ||||||
|  |       //#define BTN_ENC                       31 | ||||||
|  |  | ||||||
|  |       //#define LCD_SDSS                    SDSS | ||||||
|  |       //#define SD_DETECT_PIN        EXP2_10_PIN | ||||||
|  |       //#define KILL_PIN             EXP1_01_PIN | ||||||
|  |  | ||||||
|  |     #elif EITHER(MKS_MINI_12864, FYSETC_MINI_12864) | ||||||
|  |  | ||||||
|  |       // TO TEST | ||||||
|  |       //#define BEEPER_PIN           EXP1_06_PIN | ||||||
|  |       //#define BTN_ENC              EXP1_03_PIN | ||||||
|  |       //#define SD_DETECT_PIN        EXP2_10_PIN | ||||||
|  |  | ||||||
|  |       //#ifndef KILL_PIN | ||||||
|  |       //  #define KILL_PIN           EXP1_01_PIN | ||||||
|  |       //#endif | ||||||
|  |  | ||||||
|  |       #if ENABLED(MKS_MINI_12864) | ||||||
|  |  | ||||||
|  |         // TO TEST | ||||||
|  |         //#define DOGLCD_A0                   27 | ||||||
|  |         //#define DOGLCD_CS                   25 | ||||||
|  |  | ||||||
|  |         // GLCD features | ||||||
|  |         // Uncomment screen orientation | ||||||
|  |         //#define LCD_SCREEN_ROT_90 | ||||||
|  |         //#define LCD_SCREEN_ROT_180 | ||||||
|  |         //#define LCD_SCREEN_ROT_270 | ||||||
|  |  | ||||||
|  |         // not connected to a pin | ||||||
|  |         //#define LCD_BACKLIGHT_PIN           57  // backlight LED on A11/D? (Mega/Due:65 - AGCM4:57) | ||||||
|  |  | ||||||
|  |         //#define BTN_EN1                     31 | ||||||
|  |         //#define BTN_EN2                     33 | ||||||
|  |  | ||||||
|  |       #elif ENABLED(FYSETC_MINI_12864) | ||||||
|  |  | ||||||
|  |         // From https://wiki.fysetc.com/Mini12864_Panel/ | ||||||
|  |  | ||||||
|  |         // TO TEST | ||||||
|  |         //#define DOGLCD_A0                   16 | ||||||
|  |         //#define DOGLCD_CS                   17 | ||||||
|  |  | ||||||
|  |         //#define BTN_EN1                     33 | ||||||
|  |         //#define BTN_EN2                     31 | ||||||
|  |  | ||||||
|  |         //#define FORCE_SOFT_SPI                  // Use this if default of hardware SPI causes display problems | ||||||
|  |                                                   //   results in LCD soft SPI mode 3, SD soft SPI mode 0 | ||||||
|  |  | ||||||
|  |         //#define LCD_RESET_PIN               23  // Must be high or open for LCD to operate normally. | ||||||
|  |  | ||||||
|  |         #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) | ||||||
|  |           #ifndef RGB_LED_R_PIN | ||||||
|  |             // TO TEST | ||||||
|  |             //#define RGB_LED_R_PIN           25 | ||||||
|  |           #endif | ||||||
|  |           #ifndef RGB_LED_G_PIN | ||||||
|  |             // TO TEST | ||||||
|  |             //#define RGB_LED_G_PIN           27 | ||||||
|  |           #endif | ||||||
|  |           #ifndef RGB_LED_B_PIN | ||||||
|  |             // TO TEST | ||||||
|  |             //#define RGB_LED_B_PIN           29 | ||||||
|  |           #endif | ||||||
|  |         #elif ENABLED(FYSETC_MINI_12864_2_1) | ||||||
|  |           // TO TEST | ||||||
|  |           //#define NEOPIXEL_PIN              25 | ||||||
|  |         #endif | ||||||
|  |  | ||||||
|  |       #endif | ||||||
|  |  | ||||||
|  |     #elif ENABLED(MINIPANEL) | ||||||
|  |  | ||||||
|  |       // 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 DOGLCD_A0            EXP2_07_PIN | ||||||
|  |       //#define DOGLCD_CS                     58  // Mega/Due:66 - AGCM4:58 | ||||||
|  |  | ||||||
|  |       // GLCD features | ||||||
|  |       // Uncomment screen orientation | ||||||
|  |       //#define LCD_SCREEN_ROT_90 | ||||||
|  |       //#define LCD_SCREEN_ROT_180 | ||||||
|  |       //#define LCD_SCREEN_ROT_270 | ||||||
|  |  | ||||||
|  |       //#define BTN_EN1              EXP1_02_PIN | ||||||
|  |       //#define BTN_EN2                       55  // Mega/Due:63 - AGCM4:55 | ||||||
|  |       //#define BTN_ENC                       72  // Mega/Due:59 - AGCM4:72 | ||||||
|  |  | ||||||
|  |       //#define SD_DETECT_PIN        EXP2_10_PIN | ||||||
|  |       //#define KILL_PIN                      56  // Mega/Due:64 - AGCM4:56 | ||||||
|  |  | ||||||
|  |     #elif ENABLED(ZONESTAR_LCD) | ||||||
|  |  | ||||||
|  |       // TO TEST | ||||||
|  |       //#define ADC_KEYPAD_PIN                12 | ||||||
|  |  | ||||||
|  |     #elif ENABLED(AZSMZ_12864) | ||||||
|  |  | ||||||
|  |       // TO TEST | ||||||
|  |  | ||||||
|  |     #else | ||||||
|  |  | ||||||
|  |       // Beeper on AUX-4 | ||||||
|  |       //#define BEEPER_PIN                    33 | ||||||
|  |  | ||||||
|  |       // Buttons are directly attached to AUX-2 | ||||||
|  |       #if IS_RRW_KEYPAD | ||||||
|  |         // TO TEST | ||||||
|  |         //#define SHIFT_OUT_PIN      EXP1_02_PIN | ||||||
|  |         //#define SHIFT_CLK_PIN      EXP2_07_PIN | ||||||
|  |         //#define SHIFT_LD_PIN       EXP2_05_PIN | ||||||
|  |         //#define BTN_EN1                     56  // Mega/Due:64 - AGCM4:56 | ||||||
|  |         //#define BTN_EN2                     72  // Mega/Due:59 - AGCM4:72 | ||||||
|  |         //#define BTN_ENC                     55  // Mega/Due:63 - AGCM4:55 | ||||||
|  |       #elif ENABLED(PANEL_ONE) | ||||||
|  |         // TO TEST | ||||||
|  |         //#define BTN_EN1                     72  // AUX2 PIN 3 (Mega/Due:59 - AGCM4:72) | ||||||
|  |         //#define BTN_EN2                     55  // AUX2 PIN 4 (Mega/Due:63 - AGCM4:55) | ||||||
|  |         //#define BTN_ENC            EXP2_10_PIN  // AUX3 PIN 7 | ||||||
|  |       #else | ||||||
|  |         // TO TEST | ||||||
|  |         //#define BTN_EN1            EXP1_06_PIN | ||||||
|  |         //#define BTN_EN2            EXP1_03_PIN | ||||||
|  |         //#define BTN_ENC                     31 | ||||||
|  |       #endif | ||||||
|  |  | ||||||
|  |       #if ENABLED(G3D_PANEL) | ||||||
|  |         // TO TEST | ||||||
|  |         //#define SD_DETECT_PIN      EXP2_10_PIN | ||||||
|  |         //#define KILL_PIN           EXP1_01_PIN | ||||||
|  |       #endif | ||||||
|  |  | ||||||
|  |     #endif | ||||||
|  |   #endif // IS_NEWPANEL | ||||||
|  |  | ||||||
|  | #endif // HAS_WIRED_LCD | ||||||
|  |  | ||||||
|  | // | ||||||
|  | // SD Support | ||||||
|  | // | ||||||
|  |  | ||||||
|  | #define SDSS                                   2 | ||||||
|  | #undef SD_DETECT_PIN | ||||||
|  | #define SD_DETECT_PIN                         22 | ||||||
|  |  | ||||||
|  | #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. | ||||||
|  |    */ | ||||||
|  |   #ifndef X_SLAVE_ADDRESS | ||||||
|  |     #define X_SLAVE_ADDRESS                 0b00 | ||||||
|  |   #endif | ||||||
|  |   #ifndef Y_SLAVE_ADDRESS | ||||||
|  |     #define Y_SLAVE_ADDRESS                 0b01 | ||||||
|  |   #endif | ||||||
|  |   #ifndef Z_SLAVE_ADDRESS | ||||||
|  |     #define Z_SLAVE_ADDRESS                 0b10 | ||||||
|  |   #endif | ||||||
|  |   #ifndef E0_SLAVE_ADDRESS | ||||||
|  |     #define E0_SLAVE_ADDRESS                0b11 | ||||||
|  |   #endif | ||||||
|  |   #ifndef E1_SLAVE_ADDRESS | ||||||
|  |     #define E1_SLAVE_ADDRESS                0b00 | ||||||
|  |   #endif | ||||||
|  |  | ||||||
|  |   /** | ||||||
|  |    * 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) | ||||||
|  |    */ | ||||||
|  |  | ||||||
|  |   //#define X_HARDWARE_SERIAL  Serial1 | ||||||
|  |   //#define Y_HARDWARE_SERIAL  Serial1 | ||||||
|  |   //#define Z_HARDWARE_SERIAL  Serial1 | ||||||
|  |   //#define E0_HARDWARE_SERIAL Serial1 | ||||||
|  |   //#define E1_HARDWARE_SERIAL Serial2 | ||||||
|  |  | ||||||
|  |   #define TMC_BAUD_RATE 250000 | ||||||
|  |  | ||||||
|  |   // | ||||||
|  |   // Software serial | ||||||
|  |   // | ||||||
|  |   #define X_SERIAL_TX_PIN                      0 | ||||||
|  |   #define X_SERIAL_RX_PIN                      1 | ||||||
|  |  | ||||||
|  |   #define Y_SERIAL_TX_PIN        X_SERIAL_TX_PIN | ||||||
|  |   #define Y_SERIAL_RX_PIN        X_SERIAL_RX_PIN | ||||||
|  |  | ||||||
|  |   #define Z_SERIAL_TX_PIN        X_SERIAL_TX_PIN | ||||||
|  |   #define Z_SERIAL_RX_PIN        X_SERIAL_RX_PIN | ||||||
|  |  | ||||||
|  |   #define E0_SERIAL_TX_PIN       X_SERIAL_TX_PIN | ||||||
|  |   #define E0_SERIAL_RX_PIN       X_SERIAL_RX_PIN | ||||||
|  |  | ||||||
|  |   #define E1_SERIAL_TX_PIN                    17 | ||||||
|  |   #define E1_SERIAL_RX_PIN                    16 | ||||||
|  |  | ||||||
|  | #endif | ||||||
| @@ -452,7 +452,7 @@ | |||||||
|       //#define SD_DETECT_PIN                 49 |       //#define SD_DETECT_PIN                 49 | ||||||
|  |  | ||||||
|       //#ifndef KILL_PIN |       //#ifndef KILL_PIN | ||||||
|       //  #define KILL_PIN         41 |       //  #define KILL_PIN                    41 | ||||||
|       //#endif |       //#endif | ||||||
|  |  | ||||||
|       #if ENABLED(MKS_MINI_12864) |       #if ENABLED(MKS_MINI_12864) | ||||||
|   | |||||||
							
								
								
									
										19
									
								
								buildroot/share/PlatformIO/scripts/SAMD21_minitronics20.py
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										19
									
								
								buildroot/share/PlatformIO/scripts/SAMD21_minitronics20.py
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,19 @@ | |||||||
|  | # | ||||||
|  | # SAMD21_minitronics20.py | ||||||
|  | # Customizations for env:SAMD21_minitronics20 | ||||||
|  | # | ||||||
|  | import pioutil | ||||||
|  | if pioutil.is_pio_build(): | ||||||
|  |     from os.path import join, isfile | ||||||
|  |     import shutil | ||||||
|  |  | ||||||
|  |     Import("env") | ||||||
|  |  | ||||||
|  |     mf = env["MARLIN_FEATURES"] | ||||||
|  |     rxBuf = mf["RX_BUFFER_SIZE"] if "RX_BUFFER_SIZE" in mf else "0" | ||||||
|  |     txBuf = mf["TX_BUFFER_SIZE"] if "TX_BUFFER_SIZE" in mf else "0" | ||||||
|  |  | ||||||
|  |     serialBuf = str(max(int(rxBuf), int(txBuf), 350)) | ||||||
|  |  | ||||||
|  |     build_flags = env.get('BUILD_FLAGS') | ||||||
|  |     env.Replace(BUILD_FLAGS=build_flags) | ||||||
							
								
								
									
										33
									
								
								buildroot/tests/SAMD21_minitronics20
									
									
									
									
									
										Executable file
									
								
							
							
						
						
									
										33
									
								
								buildroot/tests/SAMD21_minitronics20
									
									
									
									
									
										Executable file
									
								
							| @@ -0,0 +1,33 @@ | |||||||
|  | #!/usr/bin/env bash | ||||||
|  | # | ||||||
|  | # Build tests for SAMD21 (Minitronics 2.0) | ||||||
|  | # | ||||||
|  |  | ||||||
|  | # exit on first failure | ||||||
|  | set -e | ||||||
|  |  | ||||||
|  | # | ||||||
|  | # Build with the default configurations | ||||||
|  | # | ||||||
|  | restore_configs | ||||||
|  | opt_set MOTHERBOARD BOARD_MINITRONICS20 SERIAL_PORT -1 \ | ||||||
|  |         TEMP_SENSOR_0 11 TEMP_SENSOR_BED 11 \ | ||||||
|  |         X_DRIVER_TYPE DRV8825 Y_DRIVER_TYPE DRV8825 Z_DRIVER_TYPE DRV8825 E0_DRIVER_TYPE DRV8825 \ | ||||||
|  |         RESTORE_LEVELING_AFTER_G28 false \ | ||||||
|  |         LCD_LANGUAGE it \ | ||||||
|  |         SDCARD_CONNECTION LCD \ | ||||||
|  |         HOMING_BUMP_MM '{ 0, 0, 0 }' | ||||||
|  | opt_enable ENDSTOP_INTERRUPTS_FEATURE BLTOUCH Z_MIN_PROBE_REPEATABILITY_TEST \ | ||||||
|  |            FILAMENT_RUNOUT_SENSOR G26_MESH_VALIDATION MESH_EDIT_GFX_OVERLAY Z_SAFE_HOMING \ | ||||||
|  |            EEPROM_SETTINGS NOZZLE_PARK_FEATURE SDSUPPORT SD_CHECK_AND_RETRY \ | ||||||
|  |            REPRAPWORLD_GRAPHICAL_LCD ADAPTIVE_STEP_SMOOTHING \ | ||||||
|  |            STATUS_MESSAGE_SCROLLING SET_PROGRESS_MANUALLY SHOW_REMAINING_TIME SET_REMAINING_TIME \ | ||||||
|  |            LONG_FILENAME_HOST_SUPPORT CUSTOM_FIRMWARE_UPLOAD M20_TIMESTAMP_SUPPORT \ | ||||||
|  |            SCROLL_LONG_FILENAMES BABYSTEPPING DOUBLECLICK_FOR_Z_BABYSTEPPING \ | ||||||
|  |            MOVE_Z_WHEN_IDLE BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \ | ||||||
|  |            LIN_ADVANCE ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE MONITOR_DRIVER_STATUS SENSORLESS_HOMING \ | ||||||
|  |            SQUARE_WAVE_STEPPING EXPERIMENTAL_SCURVE | ||||||
|  | exec_test $1 $2 "Minitronics 2.0 with assorted features" "$3" | ||||||
|  |  | ||||||
|  | # clean up | ||||||
|  | restore_configs | ||||||
| @@ -27,7 +27,7 @@ opt_enable ENDSTOP_INTERRUPTS_FEATURE S_CURVE_ACCELERATION BLTOUCH Z_MIN_PROBE_R | |||||||
|            MOVE_Z_WHEN_IDLE BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \ |            MOVE_Z_WHEN_IDLE BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \ | ||||||
|            LIN_ADVANCE ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE MONITOR_DRIVER_STATUS SENSORLESS_HOMING \ |            LIN_ADVANCE ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE MONITOR_DRIVER_STATUS SENSORLESS_HOMING \ | ||||||
|            SQUARE_WAVE_STEPPING TMC_DEBUG EXPERIMENTAL_SCURVE |            SQUARE_WAVE_STEPPING TMC_DEBUG EXPERIMENTAL_SCURVE | ||||||
| exec_test $1 $2 "Build Grand Central M4 Default Configuration" "$3" | exec_test $1 $2 "Grand Central M4 with assorted features" "$3" | ||||||
|  |  | ||||||
| # clean up | # clean up | ||||||
| restore_configs | restore_configs | ||||||
|   | |||||||
							
								
								
									
										26
									
								
								ini/samd21.ini
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										26
									
								
								ini/samd21.ini
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,26 @@ | |||||||
|  | # | ||||||
|  | # Marlin Firmware | ||||||
|  | # PlatformIO Configuration File | ||||||
|  | # | ||||||
|  |  | ||||||
|  | ################################# | ||||||
|  | #                               # | ||||||
|  | #      SAMD21 Architecture      # | ||||||
|  | #                               # | ||||||
|  | ################################# | ||||||
|  |  | ||||||
|  | # | ||||||
|  | # Adafruit Grand Central M4 (Atmel SAMD51P20A ARM Cortex-M4) | ||||||
|  | # | ||||||
|  | [env:SAMD21_minitronics20] | ||||||
|  | platform         = atmelsam | ||||||
|  | board            = minitronics20 | ||||||
|  | build_flags      = ${common.build_flags} -std=gnu++17 | ||||||
|  |                    -DUSBCON -DUSBD_USE_CDC -D__SAMD21__ -DARDUINO_SAMD_MINITRONICS20  -Wno-deprecated-declarations -DU8G_HAL_LINKS -DDEBUG | ||||||
|  |                    -IMarlin/src/HAL/SAMD21/u8g | ||||||
|  | build_unflags    = -std=gnu++11 | ||||||
|  | build_src_filter = ${common.default_src_filter} +<src/HAL/SAMD21> | ||||||
|  | lib_deps         = ${common.lib_deps} | ||||||
|  | extra_scripts    = ${common.extra_scripts} | ||||||
|  |                    pre:buildroot/share/PlatformIO/scripts/SAMD21_minitronics20.py | ||||||
|  | debug_tool       = atmel-ice | ||||||
| @@ -23,6 +23,7 @@ extra_configs = | |||||||
|     ini/features.ini |     ini/features.ini | ||||||
|     ini/lpc176x.ini |     ini/lpc176x.ini | ||||||
|     ini/native.ini |     ini/native.ini | ||||||
|  |     ini/samd21.ini | ||||||
|     ini/samd51.ini |     ini/samd51.ini | ||||||
|     ini/stm32-common.ini |     ini/stm32-common.ini | ||||||
|     ini/stm32f0.ini |     ini/stm32f0.ini | ||||||
|   | |||||||
		Reference in New Issue
	
	Block a user