From 02c40202285da6c5d0a2f36279017e35223380d8 Mon Sep 17 00:00:00 2001 From: Ron Evans Date: Thu, 6 Jun 2019 12:03:58 +0200 Subject: [PATCH] machine/atsamd51: add support for ATSAMD51 processor using Adafruit ItsyBitsy-M4 board Signed-off-by: Ron Evans --- Makefile | 1 + src/machine/board_itsybitsy-m4.go | 83 ++ src/machine/machine_atsamd51.go | 2026 ++++++++++++++++++++++++++++ src/machine/machine_atsamd51g19.go | 569 ++++++++ src/runtime/runtime_atsamd51.go | 302 +++++ src/runtime/runtime_atsamd51g19.go | 43 + targets/atsamd51.ld | 10 + targets/atsamd51g19a.json | 15 + targets/itsybitsy-m4.json | 5 + 9 files changed, 3054 insertions(+) create mode 100644 src/machine/board_itsybitsy-m4.go create mode 100644 src/machine/machine_atsamd51.go create mode 100644 src/machine/machine_atsamd51g19.go create mode 100644 src/runtime/runtime_atsamd51.go create mode 100644 src/runtime/runtime_atsamd51g19.go create mode 100644 targets/atsamd51.ld create mode 100644 targets/atsamd51g19a.json create mode 100644 targets/itsybitsy-m4.json diff --git a/Makefile b/Makefile index 659a7d53..7877f652 100644 --- a/Makefile +++ b/Makefile @@ -125,6 +125,7 @@ smoketest: tinygo build -size short -o test.elf -target=stm32f4disco examples/blinky2 tinygo build -size short -o test.elf -target=circuitplay-express examples/i2s tinygo build -size short -o test.elf -target=gameboy-advance examples/gba-display + tinygo build -size short -o test.elf -target=itsybitsy-m4 examples/blinky1 ifneq ($(AVR), 0) tinygo build -size short -o test.elf -target=arduino examples/blinky1 tinygo build -size short -o test.elf -target=digispark examples/blinky1 diff --git a/src/machine/board_itsybitsy-m4.go b/src/machine/board_itsybitsy-m4.go new file mode 100644 index 00000000..6998a9cf --- /dev/null +++ b/src/machine/board_itsybitsy-m4.go @@ -0,0 +1,83 @@ +// +build sam,atsamd51,itsybitsy_m4 + +package machine + +import "device/sam" + +// used to reset into bootloader +const RESET_MAGIC_VALUE = 0xf01669ef + +// GPIO Pins +const ( + D0 = PA16 // UART0 RX/PWM available + D1 = PA17 // UART0 TX/PWM available + D2 = PA07 + D3 = PB22 + D4 = PA14 // PWM available + D5 = PA15 // PWM available + D6 = PB02 // dotStar clock + D7 = PA18 // PWM available + D8 = PB03 // dotStar data + D9 = PA19 // PWM available + D10 = PA20 // can be used for PWM or UART1 TX + D11 = PA21 // can be used for PWM or UART1 RX + D12 = PA23 // PWM available + D13 = PA22 // PWM available +) + +// Analog pins +const ( + A0 = PA02 // ADC/AIN[0] + A1 = PB05 // ADC/AIN[2] + A2 = PB08 // ADC/AIN[3] + A3 = PB09 // ADC/AIN[4] + A4 = PA04 // ADC/AIN[5] + A5 = PA06 // ADC/AIN[10] +) + +const ( + LED = D13 +) + +// UART0 aka USBCDC pins +const ( + USBCDC_DM_PIN = PA24 + USBCDC_DP_PIN = PA25 +) + +// UART1 pins +const ( + UART_TX_PIN = D1 + UART_RX_PIN = D0 +) + +// I2C pins +const ( + SDA_PIN = PA12 // SDA: SERCOM3/PAD[0] + SCL_PIN = PA13 // SCL: SERCOM3/PAD[1] +) + +// I2C on the ItsyBitsy M4. +var ( + I2C0 = I2C{Bus: sam.SERCOM2_I2CM, + SDA: SDA_PIN, + SCL: SCL_PIN, + PinMode: PinSERCOM} +) + +// SPI pins +const ( + SPI0_SCK_PIN = PA01 // SCK: SERCOM1/PAD[1] + SPI0_MOSI_PIN = PA00 // MOSI: SERCOM1/PAD[0] + SPI0_MISO_PIN = PB23 // MISO: SERCOM1/PAD[3] +) + +// SPI on the ItsyBitsy M4. +var ( + SPI0 = SPI{Bus: sam.SERCOM1_SPI, + SCK: SPI0_SCK_PIN, + MOSI: SPI0_MOSI_PIN, + MISO: SPI0_MISO_PIN, + DOpad: spiTXPad2SCK3, + DIpad: sercomRXPad0} +) diff --git a/src/machine/machine_atsamd51.go b/src/machine/machine_atsamd51.go new file mode 100644 index 00000000..c2573f84 --- /dev/null +++ b/src/machine/machine_atsamd51.go @@ -0,0 +1,2026 @@ +// +build sam,atsamd51 + +// Peripheral abstraction layer for the atsamd51. +// +// Datasheet: +// http://ww1.microchip.com/downloads/en/DeviceDoc/60001507C.pdf +// +package machine + +import ( + "bytes" + "device/arm" + "device/sam" + "encoding/binary" + "errors" + "unsafe" +) + +const CPU_FREQUENCY = 120000000 + +type PinMode uint8 + +const ( + PinAnalog PinMode = 1 + PinSERCOM PinMode = 2 + PinSERCOMAlt PinMode = 3 + PinTimer PinMode = 4 + PinTimerAlt PinMode = 5 + PinTCCPDEC PinMode = 6 + PinCom PinMode = 7 + PinSDHC PinMode = 8 + PinI2S PinMode = 9 + PinPCC PinMode = 10 + PinGMAC PinMode = 11 + PinACCLK PinMode = 12 + PinCCL PinMode = 13 + PinDigital PinMode = 14 + PinInput PinMode = 15 + PinInputPullup PinMode = 16 + PinOutput PinMode = 17 + PinPWME PinMode = PinTimer + PinPWMF PinMode = PinTimerAlt + PinPWMG PinMode = PinTCCPDEC + PinInputPulldown PinMode = 18 +) + +// Hardware pins +const ( + PA00 Pin = 0 + PA01 Pin = 1 + PA02 Pin = 2 + PA03 Pin = 3 + PA04 Pin = 4 + PA05 Pin = 5 + PA06 Pin = 6 + PA07 Pin = 7 + PA08 Pin = 8 + PA09 Pin = 9 + PA10 Pin = 10 + PA11 Pin = 11 + PA12 Pin = 12 + PA13 Pin = 13 + PA14 Pin = 14 + PA15 Pin = 15 + PA16 Pin = 16 + PA17 Pin = 17 + PA18 Pin = 18 + PA19 Pin = 19 + PA20 Pin = 20 + PA21 Pin = 21 + PA22 Pin = 22 + PA23 Pin = 23 + PA24 Pin = 24 + PA25 Pin = 25 + PA26 Pin = 26 + PA27 Pin = 27 + PA28 Pin = 28 + PA29 Pin = 29 + PA30 Pin = 30 + PA31 Pin = 31 + PB00 Pin = 32 + PB01 Pin = 33 + PB02 Pin = 34 + PB03 Pin = 35 + PB04 Pin = 36 + PB05 Pin = 37 + PB06 Pin = 38 + PB07 Pin = 39 + PB08 Pin = 40 + PB09 Pin = 41 + PB10 Pin = 42 + PB11 Pin = 43 + PB12 Pin = 44 + PB13 Pin = 45 + PB14 Pin = 46 + PB15 Pin = 47 + PB16 Pin = 48 + PB17 Pin = 49 + PB18 Pin = 50 + PB19 Pin = 51 + PB20 Pin = 52 + PB21 Pin = 53 + PB22 Pin = 54 + PB23 Pin = 55 + PB24 Pin = 56 + PB25 Pin = 57 + PB26 Pin = 58 + PB27 Pin = 59 + PB28 Pin = 60 + PB29 Pin = 61 + PB30 Pin = 62 + PB31 Pin = 63 +) + +// InitADC initializes the ADC. +func InitADC() { + // ADC Bias Calibration + // NVMCTRL_SW0 0x00800080 + // #define ADC0_FUSES_BIASCOMP_ADDR NVMCTRL_SW0 + // #define ADC0_FUSES_BIASCOMP_Pos 2 /**< \brief (NVMCTRL_SW0) ADC Comparator Scaling */ + // #define ADC0_FUSES_BIASCOMP_Msk (_Ul(0x7) << ADC0_FUSES_BIASCOMP_Pos) + // #define ADC0_FUSES_BIASCOMP(value) (ADC0_FUSES_BIASCOMP_Msk & ((value) << ADC0_FUSES_BIASCOMP_Pos)) + + // #define ADC0_FUSES_BIASR2R_ADDR NVMCTRL_SW0 + // #define ADC0_FUSES_BIASR2R_Pos 8 /**< \brief (NVMCTRL_SW0) ADC Bias R2R ampli scaling */ + // #define ADC0_FUSES_BIASR2R_Msk (_Ul(0x7) << ADC0_FUSES_BIASR2R_Pos) + // #define ADC0_FUSES_BIASR2R(value) (ADC0_FUSES_BIASR2R_Msk & ((value) << ADC0_FUSES_BIASR2R_Pos)) + + // #define ADC0_FUSES_BIASREFBUF_ADDR NVMCTRL_SW0 + // #define ADC0_FUSES_BIASREFBUF_Pos 5 /**< \brief (NVMCTRL_SW0) ADC Bias Reference Buffer Scaling */ + // #define ADC0_FUSES_BIASREFBUF_Msk (_Ul(0x7) << ADC0_FUSES_BIASREFBUF_Pos) + // #define ADC0_FUSES_BIASREFBUF(value) (ADC0_FUSES_BIASREFBUF_Msk & ((value) << ADC0_FUSES_BIASREFBUF_Pos)) + + // #define ADC1_FUSES_BIASCOMP_ADDR NVMCTRL_SW0 + // #define ADC1_FUSES_BIASCOMP_Pos 16 /**< \brief (NVMCTRL_SW0) ADC Comparator Scaling */ + // #define ADC1_FUSES_BIASCOMP_Msk (_Ul(0x7) << ADC1_FUSES_BIASCOMP_Pos) + // #define ADC1_FUSES_BIASCOMP(value) (ADC1_FUSES_BIASCOMP_Msk & ((value) << ADC1_FUSES_BIASCOMP_Pos)) + + // #define ADC1_FUSES_BIASR2R_ADDR NVMCTRL_SW0 + // #define ADC1_FUSES_BIASR2R_Pos 22 /**< \brief (NVMCTRL_SW0) ADC Bias R2R ampli scaling */ + // #define ADC1_FUSES_BIASR2R_Msk (_Ul(0x7) << ADC1_FUSES_BIASR2R_Pos) + // #define ADC1_FUSES_BIASR2R(value) (ADC1_FUSES_BIASR2R_Msk & ((value) << ADC1_FUSES_BIASR2R_Pos)) + + // #define ADC1_FUSES_BIASREFBUF_ADDR NVMCTRL_SW0 + // #define ADC1_FUSES_BIASREFBUF_Pos 19 /**< \brief (NVMCTRL_SW0) ADC Bias Reference Buffer Scaling */ + // #define ADC1_FUSES_BIASREFBUF_Msk (_Ul(0x7) << ADC1_FUSES_BIASREFBUF_Pos) + // #define ADC1_FUSES_BIASREFBUF(value) (ADC1_FUSES_BIASREFBUF_Msk & ((value) << ADC1_FUSES_BIASREFBUF_Pos)) + + adcFuse := *(*uint32)(unsafe.Pointer(uintptr(0x00800080))) + + // uint32_t biascomp = (*((uint32_t *)ADC0_FUSES_BIASCOMP_ADDR) & ADC0_FUSES_BIASCOMP_Msk) >> ADC0_FUSES_BIASCOMP_Pos; + biascomp := (adcFuse & uint32(0x7<<2)) //>> 2 + + // uint32_t biasr2r = (*((uint32_t *)ADC0_FUSES_BIASR2R_ADDR) & ADC0_FUSES_BIASR2R_Msk) >> ADC0_FUSES_BIASR2R_Pos; + biasr2r := (adcFuse & uint32(0x7<<8)) //>> 8 + + // uint32_t biasref = (*((uint32_t *)ADC0_FUSES_BIASREFBUF_ADDR) & ADC0_FUSES_BIASREFBUF_Msk) >> ADC0_FUSES_BIASREFBUF_Pos; + biasref := (adcFuse & uint32(0x7<<5)) //>> 5 + + // calibrate ADC0 + sam.ADC0.CALIB.Set(uint16(biascomp | biasr2r | biasref)) + + // biascomp = (*((uint32_t *)ADC1_FUSES_BIASCOMP_ADDR) & ADC1_FUSES_BIASCOMP_Msk) >> ADC1_FUSES_BIASCOMP_Pos; + biascomp = (adcFuse & uint32(0x7<<16)) //>> 16 + + // biasr2r = (*((uint32_t *)ADC1_FUSES_BIASR2R_ADDR) & ADC1_FUSES_BIASR2R_Msk) >> ADC1_FUSES_BIASR2R_Pos; + biasr2r = (adcFuse & uint32(0x7<<22)) //>> 22 + + // biasref = (*((uint32_t *)ADC1_FUSES_BIASREFBUF_ADDR) & ADC1_FUSES_BIASREFBUF_Msk) >> ADC1_FUSES_BIASREFBUF_Pos; + biasref = (adcFuse & uint32(0x7<<19)) //>> 19 + + // calibrate ADC1 + sam.ADC1.CALIB.Set(uint16((biascomp | biasr2r | biasref) >> 16)) + + sam.ADC0.CTRLA.SetBits(sam.ADC_CTRLA_PRESCALER_DIV32 << sam.ADC_CTRLA_PRESCALER_Pos) + // adcs[i]->CTRLB.bit.RESSEL = ADC_CTRLB_RESSEL_10BIT_Val; + sam.ADC0.CTRLB.SetBits(sam.ADC_CTRLB_RESSEL_10BIT << sam.ADC_CTRLB_RESSEL_Pos) + + // wait for sync + for sam.ADC0.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_CTRLB) { + } + + // sampling Time Length + sam.ADC0.SAMPCTRL.Set(5) + + // wait for sync + for sam.ADC0.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_SAMPCTRL) { + } + + // No Negative input (Internal Ground) + sam.ADC0.INPUTCTRL.Set(sam.ADC_INPUTCTRL_MUXNEG_GND << sam.ADC_INPUTCTRL_MUXNEG_Pos) + + // wait for sync + for sam.ADC0.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_INPUTCTRL) { + } + + // Averaging (see datasheet table in AVGCTRL register description) + // 1 sample only (no oversampling nor averaging), adjusting result by 0 + sam.ADC0.AVGCTRL.Set(sam.ADC_AVGCTRL_SAMPLENUM_1 | (0 << sam.ADC_AVGCTRL_ADJRES_Pos)) + + // wait for sync + for sam.ADC0.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_AVGCTRL) { + } + + // same for ADC1, as for ADC0 + sam.ADC1.CTRLA.SetBits(sam.ADC_CTRLA_PRESCALER_DIV32 << sam.ADC_CTRLA_PRESCALER_Pos) + sam.ADC1.CTRLB.SetBits(sam.ADC_CTRLB_RESSEL_10BIT << sam.ADC_CTRLB_RESSEL_Pos) + for sam.ADC1.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_CTRLB) { + } + sam.ADC1.SAMPCTRL.Set(5) + for sam.ADC1.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_SAMPCTRL) { + } + sam.ADC1.INPUTCTRL.Set(sam.ADC_INPUTCTRL_MUXNEG_GND << sam.ADC_INPUTCTRL_MUXNEG_Pos) + for sam.ADC1.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_INPUTCTRL) { + } + sam.ADC1.AVGCTRL.Set(sam.ADC_AVGCTRL_SAMPLENUM_1 | (0 << sam.ADC_AVGCTRL_ADJRES_Pos)) + for sam.ADC1.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_AVGCTRL) { + } + + // wait for sync + for sam.ADC0.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_REFCTRL) { + } + for sam.ADC1.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_REFCTRL) { + } + + // default is 3V3 reference voltage + sam.ADC0.REFCTRL.SetBits(sam.ADC_REFCTRL_REFSEL_INTVCC1) + sam.ADC1.REFCTRL.SetBits(sam.ADC_REFCTRL_REFSEL_INTVCC1) +} + +// Configure configures a ADCPin to be able to be used to read data. +func (a ADC) Configure() { + a.Pin.Configure(PinConfig{Mode: PinAnalog}) +} + +// Get returns the current value of a ADC pin, in the range 0..0xffff. +func (a ADC) Get() uint16 { + bus := a.getADCBus() + ch := a.getADCChannel() + + for bus.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_INPUTCTRL) { + } + + // Selection for the positive ADC input + bus.INPUTCTRL.ClearBits(sam.ADC_INPUTCTRL_MUXPOS_Msk) + for bus.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_ENABLE) { + } + bus.INPUTCTRL.SetBits(uint16(ch << sam.ADC_INPUTCTRL_MUXPOS_Pos)) + for bus.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_ENABLE) { + } + + // Enable ADC + bus.CTRLA.SetBits(sam.ADC_CTRLA_ENABLE) + for bus.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_ENABLE) { + } + + // Start conversion + bus.SWTRIG.SetBits(sam.ADC_SWTRIG_START) + for !bus.INTFLAG.HasBits(sam.ADC_INTFLAG_RESRDY) { + } + + // Clear the Data Ready flag + bus.INTFLAG.SetBits(sam.ADC_INTFLAG_RESRDY) + for bus.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_ENABLE) { + } + + // Start conversion again, since first conversion after reference voltage changed is invalid. + bus.SWTRIG.SetBits(sam.ADC_SWTRIG_START) + + // Waiting for conversion to complete + for !bus.INTFLAG.HasBits(sam.ADC_INTFLAG_RESRDY) { + } + val := bus.RESULT.Get() + + // Disable ADC + for bus.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_ENABLE) { + } + bus.CTRLA.ClearBits(sam.ADC_CTRLA_ENABLE) + for bus.SYNCBUSY.HasBits(sam.ADC_SYNCBUSY_ENABLE) { + } + + return uint16(val) << 4 // scales from 12 to 16-bit result +} + +func (a ADC) getADCBus() *sam.ADC_Type { + return sam.ADC0 +} + +func (a ADC) getADCChannel() uint8 { + switch a.Pin { + case PA02: + return 0 + case PB08: + return 2 + case PB09: + return 3 + case PA04: + return 4 + case PA05: + return 5 + case PA06: + return 6 + case PA07: + return 7 + case PB02: + return 10 + case PB03: + return 11 + case PA09: + return 17 + case PA11: + return 19 + default: + return 0 + } +} + +// UART on the SAMD51. +type UART struct { + Buffer *RingBuffer + Bus *sam.SERCOM_USART_Type + Mode PinMode +} + +var ( + // UART0 is actually a USB CDC interface. + UART0 = USBCDC{Buffer: NewRingBuffer()} + + // The first hardware serial port on the SAMD51. Uses the SERCOM3 interface. + UART1 = UART{Bus: sam.SERCOM3_USART, + Buffer: NewRingBuffer(), + Mode: PinSERCOMAlt, + } +) + +const ( + sampleRate16X = 16 + lsbFirst = 1 + sercomRXPad0 = 0 + sercomRXPad1 = 1 + sercomRXPad2 = 2 + sercomRXPad3 = 3 + sercomTXPad0 = 0 // Only for UART + sercomTXPad2 = 1 // Only for UART + sercomTXPad023 = 2 // Only for UART with TX on PAD0, RTS on PAD2 and CTS on PAD3 + + spiTXPad0SCK1 = 0 + spiTXPad2SCK3 = 1 + spiTXPad3SCK1 = 2 + spiTXPad0SCK3 = 3 +) + +// Configure the UART. +func (uart UART) Configure(config UARTConfig) { + // Default baud rate to 115200. + if config.BaudRate == 0 { + config.BaudRate = 115200 + } + + // determine pins + if config.TX == 0 { + // use default pins + config.TX = UART_TX_PIN + config.RX = UART_RX_PIN + } + + // determine pads + var txpad, rxpad int + switch config.TX { + case PA10: + txpad = sercomTXPad2 + case PA18: + txpad = sercomTXPad2 + case PA16: + txpad = sercomTXPad0 + default: + panic("Invalid TX pin for UART") + } + + switch config.RX { + case PA11: + rxpad = sercomRXPad3 + case PA18: + rxpad = sercomRXPad2 + case PA16: + rxpad = sercomRXPad0 + case PA19: + rxpad = sercomRXPad3 + case PA17: + rxpad = sercomRXPad1 + default: + panic("Invalid RX pin for UART") + } + + // configure pins + config.TX.Configure(PinConfig{Mode: uart.Mode}) + config.RX.Configure(PinConfig{Mode: uart.Mode}) + + // reset SERCOM0 + uart.Bus.CTRLA.SetBits(sam.SERCOM_USART_CTRLA_SWRST) + for uart.Bus.CTRLA.HasBits(sam.SERCOM_USART_CTRLA_SWRST) || + uart.Bus.SYNCBUSY.HasBits(sam.SERCOM_USART_SYNCBUSY_SWRST) { + } + + // set UART mode/sample rate + // SERCOM_USART_CTRLA_MODE(mode) | + // SERCOM_USART_CTRLA_SAMPR(sampleRate); + // sam.SERCOM_USART_CTRLA_MODE_USART_INT_CLK = 1? + uart.Bus.CTRLA.Set((1 << sam.SERCOM_USART_CTRLA_MODE_Pos) | + (1 << sam.SERCOM_USART_CTRLA_SAMPR_Pos)) // sample rate of 16x + + // Set baud rate + uart.SetBaudRate(config.BaudRate) + + // setup UART frame + // SERCOM_USART_CTRLA_FORM( (parityMode == SERCOM_NO_PARITY ? 0 : 1) ) | + // dataOrder << SERCOM_USART_CTRLA_DORD_Pos; + uart.Bus.CTRLA.SetBits((0 << sam.SERCOM_USART_CTRLA_FORM_Pos) | // no parity + (lsbFirst << sam.SERCOM_USART_CTRLA_DORD_Pos)) // data order + + // set UART stop bits/parity + // SERCOM_USART_CTRLB_CHSIZE(charSize) | + // nbStopBits << SERCOM_USART_CTRLB_SBMODE_Pos | + // (parityMode == SERCOM_NO_PARITY ? 0 : parityMode) << SERCOM_USART_CTRLB_PMODE_Pos; //If no parity use default value + uart.Bus.CTRLB.SetBits((0 << sam.SERCOM_USART_CTRLB_CHSIZE_Pos) | // 8 bits is 0 + (0 << sam.SERCOM_USART_CTRLB_SBMODE_Pos) | // 1 stop bit is zero + (0 << sam.SERCOM_USART_CTRLB_PMODE_Pos)) // no parity + + // set UART pads. This is not same as pins... + // SERCOM_USART_CTRLA_TXPO(txPad) | + // SERCOM_USART_CTRLA_RXPO(rxPad); + uart.Bus.CTRLA.SetBits(uint32((txpad << sam.SERCOM_USART_CTRLA_TXPO_Pos) | + (rxpad << sam.SERCOM_USART_CTRLA_RXPO_Pos))) + + // Enable Transceiver and Receiver + //sercom->USART.CTRLB.reg |= SERCOM_USART_CTRLB_TXEN | SERCOM_USART_CTRLB_RXEN ; + uart.Bus.CTRLB.SetBits(sam.SERCOM_USART_CTRLB_TXEN | sam.SERCOM_USART_CTRLB_RXEN) + + // Enable USART1 port. + // sercom->USART.CTRLA.bit.ENABLE = 0x1u; + uart.Bus.CTRLA.SetBits(sam.SERCOM_USART_CTRLA_ENABLE) + for uart.Bus.SYNCBUSY.HasBits(sam.SERCOM_USART_SYNCBUSY_ENABLE) { + } + + // setup interrupt on receive + uart.Bus.INTENSET.Set(sam.SERCOM_USART_INTENSET_RXC) + + // Enable RX IRQ. Currently assumes SERCOM3. + arm.EnableIRQ(sam.IRQ_SERCOM3_0) + arm.EnableIRQ(sam.IRQ_SERCOM3_1) + arm.EnableIRQ(sam.IRQ_SERCOM3_2) + arm.EnableIRQ(sam.IRQ_SERCOM3_OTHER) +} + +// SetBaudRate sets the communication speed for the UART. +func (uart UART) SetBaudRate(br uint32) { + // Asynchronous fractional mode (Table 24-2 in datasheet) + // BAUD = fref / (sampleRateValue * fbaud) + // (multiply by 8, to calculate fractional piece) + // uint32_t baudTimes8 = (SystemCoreClock * 8) / (16 * baudrate); + baud := (SERCOM_FREQ_REF * 8) / (sampleRate16X * br) + + // sercom->USART.BAUD.FRAC.FP = (baudTimes8 % 8); + // sercom->USART.BAUD.FRAC.BAUD = (baudTimes8 / 8); + uart.Bus.BAUD.Set(uint16(((baud % 8) << sam.SERCOM_USART_BAUD_FRAC_MODE_FP_Pos) | + ((baud / 8) << sam.SERCOM_USART_BAUD_FRAC_MODE_BAUD_Pos))) +} + +// WriteByte writes a byte of data to the UART. +func (uart UART) WriteByte(c byte) error { + // wait until ready to receive + for !uart.Bus.INTFLAG.HasBits(sam.SERCOM_USART_INTFLAG_DRE) { + } + uart.Bus.DATA.Set(uint32(c)) + return nil +} + +//go:export SERCOM3_0_IRQHandler +func handleSERCOM3_0() { + handleUART1() +} + +//go:export SERCOM3_1_IRQHandler +func handleSERCOM3_1() { + handleUART1() +} + +//go:export SERCOM3_2_IRQHandler +func handleSERCOM3_2() { + handleUART1() +} + +//go:export SERCOM3_OTHER_IRQHandler +func handleSERCOM3_OTHER() { + handleUART1() +} + +func handleUART1() { + // should reset IRQ + UART1.Receive(byte((UART1.Bus.DATA.Get() & 0xFF))) + UART1.Bus.INTFLAG.SetBits(sam.SERCOM_USART_INTFLAG_RXC) +} + +// I2C on the SAMD51. +type I2C struct { + Bus *sam.SERCOM_I2CM_Type + SCL Pin + SDA Pin + PinMode PinMode +} + +// I2CConfig is used to store config info for I2C. +type I2CConfig struct { + Frequency uint32 + SCL Pin + SDA Pin +} + +const ( + // SERCOM_FREQ_REF is always reference frequency on SAMD51 regardless of CPU speed. + SERCOM_FREQ_REF = 48000000 + + // Default rise time in nanoseconds, based on 4.7K ohm pull up resistors + riseTimeNanoseconds = 125 + + // wire bus states + wireUnknownState = 0 + wireIdleState = 1 + wireOwnerState = 2 + wireBusyState = 3 + + // wire commands + wireCmdNoAction = 0 + wireCmdRepeatStart = 1 + wireCmdRead = 2 + wireCmdStop = 3 +) + +const i2cTimeout = 1000 + +// Configure is intended to setup the I2C interface. +func (i2c I2C) Configure(config I2CConfig) { + // Default I2C bus speed is 100 kHz. + if config.Frequency == 0 { + config.Frequency = TWI_FREQ_100KHZ + } + + // reset SERCOM + i2c.Bus.CTRLA.SetBits(sam.SERCOM_I2CM_CTRLA_SWRST) + for i2c.Bus.CTRLA.HasBits(sam.SERCOM_I2CM_CTRLA_SWRST) || + i2c.Bus.SYNCBUSY.HasBits(sam.SERCOM_I2CM_SYNCBUSY_SWRST) { + } + + // Set i2c master mode + //SERCOM_I2CM_CTRLA_MODE( I2C_MASTER_OPERATION ) + // sam.SERCOM_I2CM_CTRLA_MODE_I2C_MASTER = 5? + i2c.Bus.CTRLA.Set(5 << sam.SERCOM_I2CM_CTRLA_MODE_Pos) // | + + i2c.SetBaudRate(config.Frequency) + + // Enable I2CM port. + // sercom->USART.CTRLA.bit.ENABLE = 0x1u; + i2c.Bus.CTRLA.SetBits(sam.SERCOM_I2CM_CTRLA_ENABLE) + for i2c.Bus.SYNCBUSY.HasBits(sam.SERCOM_I2CM_SYNCBUSY_ENABLE) { + } + + // set bus idle mode + i2c.Bus.STATUS.SetBits(wireIdleState << sam.SERCOM_I2CM_STATUS_BUSSTATE_Pos) + for i2c.Bus.SYNCBUSY.HasBits(sam.SERCOM_I2CM_SYNCBUSY_SYSOP) { + } + + // enable pins + i2c.SDA.Configure(PinConfig{Mode: i2c.PinMode}) + i2c.SCL.Configure(PinConfig{Mode: i2c.PinMode}) +} + +// SetBaudRate sets the communication speed for the I2C. +func (i2c I2C) SetBaudRate(br uint32) { + // Synchronous arithmetic baudrate, via Adafruit SAMD51 implementation: + // sercom->I2CM.BAUD.bit.BAUD = SERCOM_FREQ_REF / ( 2 * baudrate) - 1 ; + baud := SERCOM_FREQ_REF/(2*br) - 1 + i2c.Bus.BAUD.Set(baud) +} + +// Tx does a single I2C transaction at the specified address. +// It clocks out the given address, writes the bytes in w, reads back len(r) +// bytes and stores them in r, and generates a stop condition on the bus. +func (i2c I2C) Tx(addr uint16, w, r []byte) error { + var err error + if len(w) != 0 { + // send start/address for write + i2c.sendAddress(addr, true) + + // wait until transmission complete + timeout := i2cTimeout + for !i2c.Bus.INTFLAG.HasBits(sam.SERCOM_I2CM_INTFLAG_MB) { + timeout-- + if timeout == 0 { + return errors.New("I2C timeout on ready to write data") + } + } + + // ACK received (0: ACK, 1: NACK) + if i2c.Bus.STATUS.HasBits(sam.SERCOM_I2CM_STATUS_RXNACK) { + return errors.New("I2C write error: expected ACK not NACK") + } + + // write data + for _, b := range w { + err = i2c.WriteByte(b) + if err != nil { + return err + } + } + + err = i2c.signalStop() + if err != nil { + return err + } + } + if len(r) != 0 { + // send start/address for read + i2c.sendAddress(addr, false) + + // wait transmission complete + for !i2c.Bus.INTFLAG.HasBits(sam.SERCOM_I2CM_INTFLAG_SB) { + // If the slave NACKS the address, the MB bit will be set. + // In that case, send a stop condition and return error. + if i2c.Bus.INTFLAG.HasBits(sam.SERCOM_I2CM_INTFLAG_MB) { + i2c.Bus.CTRLB.SetBits(wireCmdStop << sam.SERCOM_I2CM_CTRLB_CMD_Pos) // Stop condition + return errors.New("I2C read error: expected ACK not NACK") + } + } + + // ACK received (0: ACK, 1: NACK) + if i2c.Bus.STATUS.HasBits(sam.SERCOM_I2CM_STATUS_RXNACK) { + return errors.New("I2C read error: expected ACK not NACK") + } + + // read first byte + r[0] = i2c.readByte() + for i := 1; i < len(r); i++ { + // Send an ACK + i2c.Bus.CTRLB.ClearBits(sam.SERCOM_I2CM_CTRLB_ACKACT) + + i2c.signalRead() + + // Read data and send the ACK + r[i] = i2c.readByte() + } + + // Send NACK to end transmission + i2c.Bus.CTRLB.SetBits(sam.SERCOM_I2CM_CTRLB_ACKACT) + + err = i2c.signalStop() + if err != nil { + return err + } + } + + return nil +} + +// WriteByte writes a single byte to the I2C bus. +func (i2c I2C) WriteByte(data byte) error { + // Send data byte + i2c.Bus.DATA.Set(uint32(data)) + + // wait until transmission successful + timeout := i2cTimeout + for !i2c.Bus.INTFLAG.HasBits(sam.SERCOM_I2CM_INTFLAG_MB) { + // check for bus error + if sam.SERCOM3_I2CM.STATUS.HasBits(sam.SERCOM_I2CM_STATUS_BUSERR) { + return errors.New("I2C bus error") + } + timeout-- + if timeout == 0 { + return errors.New("I2C timeout on write data") + } + } + + if i2c.Bus.STATUS.HasBits(sam.SERCOM_I2CM_STATUS_RXNACK) { + return errors.New("I2C write error: expected ACK not NACK") + } + + return nil +} + +// sendAddress sends the address and start signal +func (i2c I2C) sendAddress(address uint16, write bool) error { + data := (address << 1) + if !write { + data |= 1 // set read flag + } + + // wait until bus ready + timeout := i2cTimeout + for !i2c.Bus.STATUS.HasBits(wireIdleState< 0 { + // odd pin, so save the even pins + val := pwm.getPMux() & sam.PORT_PMUX0_PMUXE_Msk + pwm.setPMux(val | uint8(pwmConfig<CTRLA.reg = TCC_CTRLA_PRESCALER_DIV256 | TCC_CTRLA_PRESCSYNC_GCLK; + timer.CTRLA.SetBits(sam.TCC_CTRLA_PRESCALER_DIV256 | sam.TCC_CTRLA_PRESCSYNC_GCLK) + + // Use "Normal PWM" (single-slope PWM) + timer.WAVE.SetBits(sam.TCC_WAVE_WAVEGEN_NPWM) + // Wait for synchronization + for timer.SYNCBUSY.HasBits(sam.TCC_SYNCBUSY_WAVE) { + } + + // while (TCCx->SYNCBUSY.bit.CC0 || TCCx->SYNCBUSY.bit.CC1); + for timer.SYNCBUSY.HasBits(sam.TCC_SYNCBUSY_CC0) || + timer.SYNCBUSY.HasBits(sam.TCC_SYNCBUSY_CC1) { + } + + // Set the initial value + // TCCx->CC[tcChannel].reg = (uint32_t) value; + pwm.setChannel(0) + + for timer.SYNCBUSY.HasBits(sam.TCC_SYNCBUSY_CC0) || + timer.SYNCBUSY.HasBits(sam.TCC_SYNCBUSY_CC1) { + } + + // Set the period (the number to count to (TOP) before resetting timer) + //TCC0->PER.reg = period; + timer.PER.Set(period) + // Wait for synchronization + for timer.SYNCBUSY.HasBits(sam.TCC_SYNCBUSY_PER) { + } + + // enable timer + timer.CTRLA.SetBits(sam.TCC_CTRLA_ENABLE) + // Wait for synchronization + for timer.SYNCBUSY.HasBits(sam.TCC_SYNCBUSY_ENABLE) { + } +} + +// Set turns on the duty cycle for a PWM pin using the provided value. +func (pwm PWM) Set(value uint16) { + // figure out which TCCX timer for this pin + timer := pwm.getTimer() + + // Wait for synchronization + for timer.SYNCBUSY.HasBits(sam.TCC_SYNCBUSY_CTRLB) { + } + for timer.SYNCBUSY.HasBits(sam.TCC_SYNCBUSY_CC0) || + timer.SYNCBUSY.HasBits(sam.TCC_SYNCBUSY_CC1) { + } + + // TCCx->CCBUF[tcChannel].reg = (uint32_t) value; + pwm.setChannelBuffer(uint32(value)) + + for timer.SYNCBUSY.HasBits(sam.TCC_SYNCBUSY_CC0) || + timer.SYNCBUSY.HasBits(sam.TCC_SYNCBUSY_CC1) { + } + + // TCCx->CTRLBCLR.bit.LUPD = 1; + timer.CTRLBCLR.SetBits(sam.TCC_CTRLBCLR_LUPD) + for timer.SYNCBUSY.HasBits(sam.TCC_SYNCBUSY_CTRLB) { + } +} + +// getPMux returns the value for the correct PMUX register for this pin. +func (pwm PWM) getPMux() uint8 { + return pwm.Pin.getPMux() +} + +// setPMux sets the value for the correct PMUX register for this pin. +func (pwm PWM) setPMux(val uint8) { + pwm.Pin.setPMux(val) +} + +// getPinCfg returns the value for the correct PINCFG register for this pin. +func (pwm PWM) getPinCfg() uint8 { + return pwm.Pin.getPinCfg() +} + +// setPinCfg sets the value for the correct PINCFG register for this pin. +func (pwm PWM) setPinCfg(val uint8) { + pwm.Pin.setPinCfg(val) +} + +// getTimer returns the timer to be used for PWM on this pin +func (pwm PWM) getTimer() *sam.TCC_Type { + switch pwm.Pin { + case PA16: + return sam.TCC1 + case PA17: + return sam.TCC1 + case PA14: + return sam.TCC2 + case PA15: + return sam.TCC2 + case PA18: + return sam.TCC1 + case PA19: + return sam.TCC1 + case PA20: + return sam.TCC0 + case PA21: + return sam.TCC0 + case PA23: + return sam.TCC0 + case PA22: + return sam.TCC0 + default: + return nil // not supported on this pin + } +} + +// setChannel sets the value for the correct channel for PWM on this pin +func (pwm PWM) setChannel(val uint32) { + switch pwm.Pin { + case PA16: + pwm.getTimer().CC0.Set(val) + case PA17: + pwm.getTimer().CC1.Set(val) + case PA14: + pwm.getTimer().CC0.Set(val) + case PA15: + pwm.getTimer().CC1.Set(val) + case PA18: + pwm.getTimer().CC2.Set(val) + case PA19: + pwm.getTimer().CC3.Set(val) + case PA20: + pwm.getTimer().CC0.Set(val) + case PA21: + pwm.getTimer().CC1.Set(val) + case PA23: + pwm.getTimer().CC3.Set(val) + case PA22: + pwm.getTimer().CC2.Set(val) + default: + return // not supported on this pin + } +} + +// setChannelBuffer sets the value for the correct channel buffer for PWM on this pin +func (pwm PWM) setChannelBuffer(val uint32) { + switch pwm.Pin { + case PA16: + pwm.getTimer().CCBUF0.Set(val) + case PA17: + pwm.getTimer().CCBUF1.Set(val) + case PA14: + pwm.getTimer().CCBUF0.Set(val) + case PA15: + pwm.getTimer().CCBUF1.Set(val) + case PA18: + pwm.getTimer().CCBUF2.Set(val) + case PA19: + pwm.getTimer().CCBUF3.Set(val) + case PA20: + pwm.getTimer().CCBUF0.Set(val) + case PA21: + pwm.getTimer().CCBUF1.Set(val) + case PA23: + pwm.getTimer().CCBUF3.Set(val) + case PA22: + pwm.getTimer().CCBUF2.Set(val) + default: + return // not supported on this pin + } +} + +// getMux returns the pin mode mux to be used for PWM on this pin. +func (pwm PWM) getMux() PinMode { + switch pwm.Pin { + case PA16: + return PinPWMF + case PA17: + return PinPWMF + case PA14: + return PinPWMF + case PA15: + return PinPWMF + case PA18: + return PinPWMF + case PA19: + return PinPWMF + case PA20: + return PinPWMG + case PA21: + return PinPWMG + case PA23: + return PinPWMG + case PA22: + return PinPWMG + default: + return 0 // not supported on this pin + } +} + +// USBCDC is the USB CDC aka serial over USB interface on the SAMD21. +type USBCDC struct { + Buffer *RingBuffer +} + +// WriteByte writes a byte of data to the USB CDC interface. +func (usbcdc USBCDC) WriteByte(c byte) error { + // Supposedly to handle problem with Windows USB serial ports? + if usbLineInfo.lineState > 0 { + // set the data + udd_ep_in_cache_buffer[usb_CDC_ENDPOINT_IN][0] = c + + usbEndpointDescriptors[usb_CDC_ENDPOINT_IN].DeviceDescBank[1].ADDR.Set(uint32(uintptr(unsafe.Pointer(&udd_ep_in_cache_buffer[usb_CDC_ENDPOINT_IN])))) + + // clean multi packet size of bytes already sent + usbEndpointDescriptors[usb_CDC_ENDPOINT_IN].DeviceDescBank[1].PCKSIZE.ClearBits(usb_DEVICE_PCKSIZE_MULTI_PACKET_SIZE_Mask << usb_DEVICE_PCKSIZE_MULTI_PACKET_SIZE_Pos) + + // set count of bytes to be sent + usbEndpointDescriptors[usb_CDC_ENDPOINT_IN].DeviceDescBank[1].PCKSIZE.SetBits((1 & usb_DEVICE_PCKSIZE_BYTE_COUNT_Mask) << usb_DEVICE_PCKSIZE_BYTE_COUNT_Pos) + + // clear transfer complete flag + setEPINTFLAG(usb_CDC_ENDPOINT_IN, sam.USB_DEVICE_EPINTFLAG_TRCPT1) + + // send data by setting bank ready + setEPSTATUSSET(usb_CDC_ENDPOINT_IN, sam.USB_DEVICE_EPSTATUSSET_BK1RDY) + + // wait for transfer to complete + timeout := 3000 + for (getEPINTFLAG(usb_CDC_ENDPOINT_IN) & sam.USB_DEVICE_EPINTFLAG_TRCPT1) == 0 { + timeout-- + if timeout == 0 { + return errors.New("USBCDC write byte timeout") + } + } + } + + return nil +} + +func (usbcdc USBCDC) DTR() bool { + return (usbLineInfo.lineState & usb_CDC_LINESTATE_DTR) > 0 +} + +func (usbcdc USBCDC) RTS() bool { + return (usbLineInfo.lineState & usb_CDC_LINESTATE_RTS) > 0 +} + +const ( + // these are SAMD51 specific. + usb_DEVICE_PCKSIZE_BYTE_COUNT_Pos = 0 + usb_DEVICE_PCKSIZE_BYTE_COUNT_Mask = 0x3FFF + + usb_DEVICE_PCKSIZE_SIZE_Pos = 28 + usb_DEVICE_PCKSIZE_SIZE_Mask = 0x7 + + usb_DEVICE_PCKSIZE_MULTI_PACKET_SIZE_Pos = 14 + usb_DEVICE_PCKSIZE_MULTI_PACKET_SIZE_Mask = 0x3FFF +) + +var ( + usbEndpointDescriptors [8]usbDeviceDescriptor + + udd_ep_in_cache_buffer [7][128]uint8 + udd_ep_out_cache_buffer [7][128]uint8 + + isEndpointHalt = false + isRemoteWakeUpEnabled = false + endPoints = []uint32{usb_ENDPOINT_TYPE_CONTROL, + (usb_ENDPOINT_TYPE_INTERRUPT | usbEndpointIn), + (usb_ENDPOINT_TYPE_BULK | usbEndpointOut), + (usb_ENDPOINT_TYPE_BULK | usbEndpointIn)} + + usbConfiguration uint8 + usbSetInterface uint8 + usbLineInfo = cdcLineInfo{115200, 0x00, 0x00, 0x08, 0x00} +) + +// Configure the USB CDC interface. The config is here for compatibility with the UART interface. +func (usbcdc USBCDC) Configure(config UARTConfig) { + // reset USB interface + sam.USB_DEVICE.CTRLA.SetBits(sam.USB_DEVICE_CTRLA_SWRST) + for sam.USB_DEVICE.SYNCBUSY.HasBits(sam.USB_DEVICE_SYNCBUSY_SWRST) || + sam.USB_DEVICE.SYNCBUSY.HasBits(sam.USB_DEVICE_SYNCBUSY_ENABLE) { + } + + sam.USB_DEVICE.DESCADD.Set(uint32(uintptr(unsafe.Pointer(&usbEndpointDescriptors)))) + + // configure pins + USBCDC_DM_PIN.Configure(PinConfig{Mode: PinCom}) + USBCDC_DP_PIN.Configure(PinConfig{Mode: PinCom}) + + // performs pad calibration from store fuses + handlePadCalibration() + + // run in standby + sam.USB_DEVICE.CTRLA.SetBits(sam.USB_DEVICE_CTRLA_RUNSTDBY) + + // set full speed + sam.USB_DEVICE.CTRLB.SetBits(sam.USB_DEVICE_CTRLB_SPDCONF_FS << sam.USB_DEVICE_CTRLB_SPDCONF_Pos) + + // attach + sam.USB_DEVICE.CTRLB.ClearBits(sam.USB_DEVICE_CTRLB_DETACH) + + // enable interrupt for end of reset + sam.USB_DEVICE.INTENSET.SetBits(sam.USB_DEVICE_INTENSET_EORST) + + // enable interrupt for start of frame + sam.USB_DEVICE.INTENSET.SetBits(sam.USB_DEVICE_INTENSET_SOF) + + // enable USB + sam.USB_DEVICE.CTRLA.SetBits(sam.USB_DEVICE_CTRLA_ENABLE) + + // enable IRQ + arm.EnableIRQ(sam.IRQ_USB_OTHER) + arm.EnableIRQ(sam.IRQ_USB_SOF_HSOF) + arm.EnableIRQ(sam.IRQ_USB_TRCPT0) + arm.EnableIRQ(sam.IRQ_USB_TRCPT1) +} + +func handlePadCalibration() { + // Load Pad Calibration data from non-volatile memory + // This requires registers that are not included in the SVD file. + // Modeled after defines from samd21g18a.h and nvmctrl.h: + // + // #define NVMCTRL_OTP4 0x00806020 + // + // #define USB_FUSES_TRANSN_ADDR (NVMCTRL_OTP4 + 4) + // #define USB_FUSES_TRANSN_Pos 13 /**< \brief (NVMCTRL_OTP4) USB pad Transn calibration */ + // #define USB_FUSES_TRANSN_Msk (0x1Fu << USB_FUSES_TRANSN_Pos) + // #define USB_FUSES_TRANSN(value) ((USB_FUSES_TRANSN_Msk & ((value) << USB_FUSES_TRANSN_Pos))) + + // #define USB_FUSES_TRANSP_ADDR (NVMCTRL_OTP4 + 4) + // #define USB_FUSES_TRANSP_Pos 18 /**< \brief (NVMCTRL_OTP4) USB pad Transp calibration */ + // #define USB_FUSES_TRANSP_Msk (0x1Fu << USB_FUSES_TRANSP_Pos) + // #define USB_FUSES_TRANSP(value) ((USB_FUSES_TRANSP_Msk & ((value) << USB_FUSES_TRANSP_Pos))) + + // #define USB_FUSES_TRIM_ADDR (NVMCTRL_OTP4 + 4) + // #define USB_FUSES_TRIM_Pos 23 /**< \brief (NVMCTRL_OTP4) USB pad Trim calibration */ + // #define USB_FUSES_TRIM_Msk (0x7u << USB_FUSES_TRIM_Pos) + // #define USB_FUSES_TRIM(value) ((USB_FUSES_TRIM_Msk & ((value) << USB_FUSES_TRIM_Pos))) + // + fuse := *(*uint32)(unsafe.Pointer(uintptr(0x00806020) + 4)) + calibTransN := uint16(fuse>>13) & uint16(0x1f) + calibTransP := uint16(fuse>>18) & uint16(0x1f) + calibTrim := uint16(fuse>>23) & uint16(0x7) + + if calibTransN == 0x1f { + calibTransN = 5 + } + sam.USB_DEVICE.PADCAL.SetBits(calibTransN << sam.USB_DEVICE_PADCAL_TRANSN_Pos) + + if calibTransP == 0x1f { + calibTransP = 29 + } + sam.USB_DEVICE.PADCAL.SetBits(calibTransP << sam.USB_DEVICE_PADCAL_TRANSP_Pos) + + if calibTrim == 0x7 { + calibTransN = 3 + } + sam.USB_DEVICE.PADCAL.SetBits(calibTrim << sam.USB_DEVICE_PADCAL_TRIM_Pos) +} + +//go:export USB_OTHER_IRQHandler +func handleUSBOther() { + handleUSBIRQ() +} + +//go:export USB_SOF_HSOF_IRQHandler +func handleUSBSOFHSOF() { + handleUSBIRQ() +} + +//go:export USB_TRCPT0_IRQHandler +func handleUSBTRCPT0() { + handleUSBIRQ() +} + +//go:export USB_TRCPT1_IRQHandler +func handleUSBTRCPT1() { + handleUSBIRQ() +} + +func handleUSBIRQ() { + // reset all interrupt flags + flags := sam.USB_DEVICE.INTFLAG.Get() + sam.USB_DEVICE.INTFLAG.Set(flags) + + // End of reset + if (flags & sam.USB_DEVICE_INTFLAG_EORST) > 0 { + // Configure control endpoint + initEndpoint(0, usb_ENDPOINT_TYPE_CONTROL) + + // Enable Setup-Received interrupt + setEPINTENSET(0, sam.USB_DEVICE_EPINTENSET_RXSTP) + + usbConfiguration = 0 + + // ack the End-Of-Reset interrupt + sam.USB_DEVICE.INTFLAG.Set(sam.USB_DEVICE_INTFLAG_EORST) + } + + // Start of frame + if (flags & sam.USB_DEVICE_INTFLAG_SOF) > 0 { + // if you want to blink LED showing traffic, this would be the place... + } + + // Endpoint 0 Setup interrupt + if getEPINTFLAG(0)&sam.USB_DEVICE_EPINTFLAG_RXSTP > 0 { + // ack setup received + setEPINTFLAG(0, sam.USB_DEVICE_EPINTFLAG_RXSTP) + + // parse setup + setup := newUSBSetup(udd_ep_out_cache_buffer[0][:]) + + // Clear the Bank 0 ready flag on Control OUT + setEPSTATUSCLR(0, sam.USB_DEVICE_EPSTATUSCLR_BK0RDY) + usbEndpointDescriptors[0].DeviceDescBank[0].PCKSIZE.ClearBits(usb_DEVICE_PCKSIZE_BYTE_COUNT_Mask << usb_DEVICE_PCKSIZE_BYTE_COUNT_Pos) + + ok := false + if (setup.bmRequestType & usb_REQUEST_TYPE) == usb_REQUEST_STANDARD { + // Standard Requests + ok = handleStandardSetup(setup) + } else { + // Class Interface Requests + if setup.wIndex == usb_CDC_ACM_INTERFACE { + ok = cdcSetup(setup) + } + } + + if ok { + // set Bank1 ready + setEPSTATUSSET(0, sam.USB_DEVICE_EPSTATUSSET_BK1RDY) + } else { + // Stall endpoint + setEPSTATUSSET(0, sam.USB_DEVICE_EPINTFLAG_STALL1) + } + + if getEPINTFLAG(0)&sam.USB_DEVICE_EPINTFLAG_STALL1 > 0 { + // ack the stall + setEPINTFLAG(0, sam.USB_DEVICE_EPINTFLAG_STALL1) + + // clear stall request + setEPINTENCLR(0, sam.USB_DEVICE_EPINTENCLR_STALL1) + } + } + + // Now the actual transfer handlers, ignore endpoint number 0 (setup) + var i uint32 + for i = 1; i < uint32(len(endPoints)); i++ { + // Check if endpoint has a pending interrupt + epFlags := getEPINTFLAG(i) + if (epFlags&sam.USB_DEVICE_EPINTFLAG_TRCPT0) > 0 || + (epFlags&sam.USB_DEVICE_EPINTFLAG_TRCPT1) > 0 { + switch i { + case usb_CDC_ENDPOINT_OUT: + handleEndpoint(i) + setEPINTFLAG(i, epFlags) + case usb_CDC_ENDPOINT_IN, usb_CDC_ENDPOINT_ACM: + setEPSTATUSCLR(i, sam.USB_DEVICE_EPSTATUSCLR_BK1RDY) + setEPINTFLAG(i, sam.USB_DEVICE_EPINTFLAG_TRCPT1) + } + } + } +} + +func initEndpoint(ep, config uint32) { + switch config { + case usb_ENDPOINT_TYPE_INTERRUPT | usbEndpointIn: + // set packet size + usbEndpointDescriptors[ep].DeviceDescBank[1].PCKSIZE.SetBits(epPacketSize(64) << usb_DEVICE_PCKSIZE_SIZE_Pos) + + // set data buffer address + usbEndpointDescriptors[ep].DeviceDescBank[1].ADDR.Set(uint32(uintptr(unsafe.Pointer(&udd_ep_in_cache_buffer[ep])))) + + // set endpoint type + setEPCFG(ep, ((usb_ENDPOINT_TYPE_INTERRUPT + 1) << sam.USB_DEVICE_EPCFG_EPTYPE1_Pos)) + + case usb_ENDPOINT_TYPE_BULK | usbEndpointOut: + // set packet size + usbEndpointDescriptors[ep].DeviceDescBank[0].PCKSIZE.SetBits(epPacketSize(64) << usb_DEVICE_PCKSIZE_SIZE_Pos) + + // set data buffer address + usbEndpointDescriptors[ep].DeviceDescBank[0].ADDR.Set(uint32(uintptr(unsafe.Pointer(&udd_ep_out_cache_buffer[ep])))) + + // set endpoint type + setEPCFG(ep, ((usb_ENDPOINT_TYPE_BULK + 1) << sam.USB_DEVICE_EPCFG_EPTYPE0_Pos)) + + // receive interrupts when current transfer complete + setEPINTENSET(ep, sam.USB_DEVICE_EPINTENSET_TRCPT0) + + // set byte count to zero, we have not received anything yet + usbEndpointDescriptors[ep].DeviceDescBank[0].PCKSIZE.ClearBits(usb_DEVICE_PCKSIZE_BYTE_COUNT_Mask << usb_DEVICE_PCKSIZE_BYTE_COUNT_Pos) + + // ready for next transfer + setEPSTATUSCLR(ep, sam.USB_DEVICE_EPSTATUSCLR_BK0RDY) + + case usb_ENDPOINT_TYPE_INTERRUPT | usbEndpointOut: + // TODO: not really anything, seems like... + + case usb_ENDPOINT_TYPE_BULK | usbEndpointIn: + // set packet size + usbEndpointDescriptors[ep].DeviceDescBank[1].PCKSIZE.SetBits(epPacketSize(64) << usb_DEVICE_PCKSIZE_SIZE_Pos) + + // set data buffer address + usbEndpointDescriptors[ep].DeviceDescBank[1].ADDR.Set(uint32(uintptr(unsafe.Pointer(&udd_ep_in_cache_buffer[ep])))) + + // set endpoint type + setEPCFG(ep, ((usb_ENDPOINT_TYPE_BULK + 1) << sam.USB_DEVICE_EPCFG_EPTYPE1_Pos)) + + // NAK on endpoint IN, the bank is not yet filled in. + setEPSTATUSCLR(ep, sam.USB_DEVICE_EPSTATUSCLR_BK1RDY) + + case usb_ENDPOINT_TYPE_CONTROL: + // Control OUT + // set packet size + usbEndpointDescriptors[ep].DeviceDescBank[0].PCKSIZE.SetBits(epPacketSize(64) << usb_DEVICE_PCKSIZE_SIZE_Pos) + + // set data buffer address + usbEndpointDescriptors[ep].DeviceDescBank[0].ADDR.Set(uint32(uintptr(unsafe.Pointer(&udd_ep_out_cache_buffer[ep])))) + + // set endpoint type + setEPCFG(ep, getEPCFG(ep)|((usb_ENDPOINT_TYPE_CONTROL+1)<> + usb_DEVICE_PCKSIZE_BYTE_COUNT_Pos) & usb_DEVICE_PCKSIZE_BYTE_COUNT_Mask) + + data := make([]byte, bytesread) + copy(data, udd_ep_out_cache_buffer[0][:]) + + return data +} + +// sendDescriptor creates and sends the various USB descriptor types that +// can be requested by the host. +func sendDescriptor(setup usbSetup) { + switch setup.wValueH { + case usb_CONFIGURATION_DESCRIPTOR_TYPE: + sendConfiguration(setup) + return + case usb_DEVICE_DESCRIPTOR_TYPE: + if setup.wLength == 8 { + // composite descriptor requested, so only send 8 bytes + dd := NewDeviceDescriptor(0xEF, 0x02, 0x01, 64, usb_VID, usb_PID, 0x100, usb_IMANUFACTURER, usb_IPRODUCT, usb_ISERIAL, 1) + sendUSBPacket(0, dd.Bytes()[:8]) + } else { + // complete descriptor requested so send entire packet + dd := NewDeviceDescriptor(0x00, 0x00, 0x00, 64, usb_VID, usb_PID, 0x100, usb_IMANUFACTURER, usb_IPRODUCT, usb_ISERIAL, 1) + sendUSBPacket(0, dd.Bytes()) + } + return + + case usb_STRING_DESCRIPTOR_TYPE: + switch setup.wValueL { + case 0: + b := make([]byte, 4) + b[0] = byte(usb_STRING_LANGUAGE[0] >> 8) + b[1] = byte(usb_STRING_LANGUAGE[0] & 0xff) + b[2] = byte(usb_STRING_LANGUAGE[1] >> 8) + b[3] = byte(usb_STRING_LANGUAGE[1] & 0xff) + sendUSBPacket(0, b) + + case usb_IPRODUCT: + prod := []byte(usb_STRING_PRODUCT) + b := make([]byte, len(prod)*2+2) + b[0] = byte(len(prod)*2 + 2) + b[1] = 0x03 + + for i, val := range prod { + b[i*2] = 0 + b[i*2+1] = val + } + + sendUSBPacket(0, b) + + case usb_IMANUFACTURER: + prod := []byte(usb_STRING_MANUFACTURER) + b := make([]byte, len(prod)*2+2) + b[0] = byte(len(prod)*2 + 2) + b[1] = 0x03 + + for i, val := range prod { + b[i*2] = 0 + b[i*2+1] = val + } + + sendUSBPacket(0, b) + + case usb_ISERIAL: + // TODO: allow returning a product serial number + sendZlp(0) + } + + // send final zero length packet and return + sendZlp(0) + return + } + + // do not know how to handle this message, so return zero + sendZlp(0) + return +} + +// sendConfiguration creates and sends the configuration packet to the host. +func sendConfiguration(setup usbSetup) { + if setup.wLength == 9 { + sz := uint16(configDescriptorSize + cdcSize) + config := NewConfigDescriptor(sz, 2) + sendUSBPacket(0, config.Bytes()) + } else { + iad := NewIADDescriptor(0, 2, usb_CDC_COMMUNICATION_INTERFACE_CLASS, usb_CDC_ABSTRACT_CONTROL_MODEL, 0) + + cif := NewInterfaceDescriptor(usb_CDC_ACM_INTERFACE, 1, usb_CDC_COMMUNICATION_INTERFACE_CLASS, usb_CDC_ABSTRACT_CONTROL_MODEL, 0) + + header := NewCDCCSInterfaceDescriptor(usb_CDC_HEADER, usb_CDC_V1_10&0xFF, (usb_CDC_V1_10>>8)&0x0FF) + + controlManagement := NewACMFunctionalDescriptor(usb_CDC_ABSTRACT_CONTROL_MANAGEMENT, 6) + + functionalDescriptor := NewCDCCSInterfaceDescriptor(usb_CDC_UNION, usb_CDC_ACM_INTERFACE, usb_CDC_DATA_INTERFACE) + + callManagement := NewCMFunctionalDescriptor(usb_CDC_CALL_MANAGEMENT, 1, 1) + + cifin := NewEndpointDescriptor((usb_CDC_ENDPOINT_ACM | usbEndpointIn), usb_ENDPOINT_TYPE_INTERRUPT, 0x10, 0x10) + + dif := NewInterfaceDescriptor(usb_CDC_DATA_INTERFACE, 2, usb_CDC_DATA_INTERFACE_CLASS, 0, 0) + + out := NewEndpointDescriptor((usb_CDC_ENDPOINT_OUT | usbEndpointOut), usb_ENDPOINT_TYPE_BULK, usbEndpointPacketSize, 0) + + in := NewEndpointDescriptor((usb_CDC_ENDPOINT_IN | usbEndpointIn), usb_ENDPOINT_TYPE_BULK, usbEndpointPacketSize, 0) + + cdc := NewCDCDescriptor(iad, + cif, + header, + controlManagement, + functionalDescriptor, + callManagement, + cifin, + dif, + out, + in) + + sz := uint16(configDescriptorSize + cdcSize) + config := NewConfigDescriptor(sz, 2) + + buf := make([]byte, 0, sz) + buf = append(buf, config.Bytes()...) + buf = append(buf, cdc.Bytes()...) + + sendUSBPacket(0, buf) + } +} + +func handleEndpoint(ep uint32) { + // get data + count := int((usbEndpointDescriptors[ep].DeviceDescBank[0].PCKSIZE.Get() >> + usb_DEVICE_PCKSIZE_BYTE_COUNT_Pos) & usb_DEVICE_PCKSIZE_BYTE_COUNT_Mask) + + // move to ring buffer + for i := 0; i < count; i++ { + UART0.Receive(byte((udd_ep_out_cache_buffer[ep][i] & 0xFF))) + } + + // set byte count to zero + usbEndpointDescriptors[ep].DeviceDescBank[0].PCKSIZE.ClearBits(usb_DEVICE_PCKSIZE_BYTE_COUNT_Mask << usb_DEVICE_PCKSIZE_BYTE_COUNT_Pos) + + // set multi packet size to 64 + usbEndpointDescriptors[ep].DeviceDescBank[0].PCKSIZE.SetBits(64 << usb_DEVICE_PCKSIZE_MULTI_PACKET_SIZE_Pos) + + // set ready for next data + setEPSTATUSCLR(ep, sam.USB_DEVICE_EPSTATUSCLR_BK0RDY) +} + +func sendZlp(ep uint32) { + usbEndpointDescriptors[ep].DeviceDescBank[1].PCKSIZE.ClearBits(usb_DEVICE_PCKSIZE_BYTE_COUNT_Mask << usb_DEVICE_PCKSIZE_BYTE_COUNT_Pos) +} + +func epPacketSize(size uint16) uint32 { + switch size { + case 8: + return 0 + case 16: + return 1 + case 32: + return 2 + case 64: + return 3 + case 128: + return 4 + case 256: + return 5 + case 512: + return 6 + case 1023: + return 7 + default: + return 0 + } +} + +func getEPCFG(ep uint32) uint8 { + switch ep { + case 0: + return sam.USB_DEVICE.EPCFG0.Get() + case 1: + return sam.USB_DEVICE.EPCFG1.Get() + case 2: + return sam.USB_DEVICE.EPCFG2.Get() + case 3: + return sam.USB_DEVICE.EPCFG3.Get() + case 4: + return sam.USB_DEVICE.EPCFG4.Get() + case 5: + return sam.USB_DEVICE.EPCFG5.Get() + case 6: + return sam.USB_DEVICE.EPCFG6.Get() + case 7: + return sam.USB_DEVICE.EPCFG7.Get() + default: + return 0 + } +} + +func setEPCFG(ep uint32, val uint8) { + switch ep { + case 0: + sam.USB_DEVICE.EPCFG0.Set(val) + case 1: + sam.USB_DEVICE.EPCFG1.Set(val) + case 2: + sam.USB_DEVICE.EPCFG2.Set(val) + case 3: + sam.USB_DEVICE.EPCFG3.Set(val) + case 4: + sam.USB_DEVICE.EPCFG4.Set(val) + case 5: + sam.USB_DEVICE.EPCFG5.Set(val) + case 6: + sam.USB_DEVICE.EPCFG6.Set(val) + case 7: + sam.USB_DEVICE.EPCFG7.Set(val) + default: + return + } +} + +func setEPSTATUSCLR(ep uint32, val uint8) { + switch ep { + case 0: + sam.USB_DEVICE.EPSTATUSCLR0.Set(val) + case 1: + sam.USB_DEVICE.EPSTATUSCLR1.Set(val) + case 2: + sam.USB_DEVICE.EPSTATUSCLR2.Set(val) + case 3: + sam.USB_DEVICE.EPSTATUSCLR3.Set(val) + case 4: + sam.USB_DEVICE.EPSTATUSCLR4.Set(val) + case 5: + sam.USB_DEVICE.EPSTATUSCLR5.Set(val) + case 6: + sam.USB_DEVICE.EPSTATUSCLR6.Set(val) + case 7: + sam.USB_DEVICE.EPSTATUSCLR7.Set(val) + default: + return + } +} + +func setEPSTATUSSET(ep uint32, val uint8) { + switch ep { + case 0: + sam.USB_DEVICE.EPSTATUSSET0.Set(val) + case 1: + sam.USB_DEVICE.EPSTATUSSET1.Set(val) + case 2: + sam.USB_DEVICE.EPSTATUSSET2.Set(val) + case 3: + sam.USB_DEVICE.EPSTATUSSET3.Set(val) + case 4: + sam.USB_DEVICE.EPSTATUSSET4.Set(val) + case 5: + sam.USB_DEVICE.EPSTATUSSET5.Set(val) + case 6: + sam.USB_DEVICE.EPSTATUSSET6.Set(val) + case 7: + sam.USB_DEVICE.EPSTATUSSET7.Set(val) + default: + return + } +} + +func getEPSTATUS(ep uint32) uint8 { + switch ep { + case 0: + return sam.USB_DEVICE.EPSTATUS0.Get() + case 1: + return sam.USB_DEVICE.EPSTATUS1.Get() + case 2: + return sam.USB_DEVICE.EPSTATUS2.Get() + case 3: + return sam.USB_DEVICE.EPSTATUS3.Get() + case 4: + return sam.USB_DEVICE.EPSTATUS4.Get() + case 5: + return sam.USB_DEVICE.EPSTATUS5.Get() + case 6: + return sam.USB_DEVICE.EPSTATUS6.Get() + case 7: + return sam.USB_DEVICE.EPSTATUS7.Get() + default: + return 0 + } +} + +func getEPINTFLAG(ep uint32) uint8 { + switch ep { + case 0: + return sam.USB_DEVICE.EPINTFLAG0.Get() + case 1: + return sam.USB_DEVICE.EPINTFLAG1.Get() + case 2: + return sam.USB_DEVICE.EPINTFLAG2.Get() + case 3: + return sam.USB_DEVICE.EPINTFLAG3.Get() + case 4: + return sam.USB_DEVICE.EPINTFLAG4.Get() + case 5: + return sam.USB_DEVICE.EPINTFLAG5.Get() + case 6: + return sam.USB_DEVICE.EPINTFLAG6.Get() + case 7: + return sam.USB_DEVICE.EPINTFLAG7.Get() + default: + return 0 + } +} + +func setEPINTFLAG(ep uint32, val uint8) { + switch ep { + case 0: + sam.USB_DEVICE.EPINTFLAG0.Set(val) + case 1: + sam.USB_DEVICE.EPINTFLAG1.Set(val) + case 2: + sam.USB_DEVICE.EPINTFLAG2.Set(val) + case 3: + sam.USB_DEVICE.EPINTFLAG3.Set(val) + case 4: + sam.USB_DEVICE.EPINTFLAG4.Set(val) + case 5: + sam.USB_DEVICE.EPINTFLAG5.Set(val) + case 6: + sam.USB_DEVICE.EPINTFLAG6.Set(val) + case 7: + sam.USB_DEVICE.EPINTFLAG7.Set(val) + default: + return + } +} + +func setEPINTENCLR(ep uint32, val uint8) { + switch ep { + case 0: + sam.USB_DEVICE.EPINTENCLR0.Set(val) + case 1: + sam.USB_DEVICE.EPINTENCLR1.Set(val) + case 2: + sam.USB_DEVICE.EPINTENCLR2.Set(val) + case 3: + sam.USB_DEVICE.EPINTENCLR3.Set(val) + case 4: + sam.USB_DEVICE.EPINTENCLR4.Set(val) + case 5: + sam.USB_DEVICE.EPINTENCLR5.Set(val) + case 6: + sam.USB_DEVICE.EPINTENCLR6.Set(val) + case 7: + sam.USB_DEVICE.EPINTENCLR7.Set(val) + default: + return + } +} + +func setEPINTENSET(ep uint32, val uint8) { + switch ep { + case 0: + sam.USB_DEVICE.EPINTENSET0.Set(val) + case 1: + sam.USB_DEVICE.EPINTENSET1.Set(val) + case 2: + sam.USB_DEVICE.EPINTENSET2.Set(val) + case 3: + sam.USB_DEVICE.EPINTENSET3.Set(val) + case 4: + sam.USB_DEVICE.EPINTENSET4.Set(val) + case 5: + sam.USB_DEVICE.EPINTENSET5.Set(val) + case 6: + sam.USB_DEVICE.EPINTENSET6.Set(val) + case 7: + sam.USB_DEVICE.EPINTENSET7.Set(val) + default: + return + } +} + +// ResetProcessor should perform a system reset in preperation +// to switch to the bootloader to flash new firmware. +func ResetProcessor() { + arm.DisableInterrupts() + + // Perform magic reset into bootloader, as mentioned in + // https://github.com/arduino/ArduinoCore-samd/issues/197 + *(*uint32)(unsafe.Pointer(uintptr(0x20000000 + 0x00030000 - 4))) = RESET_MAGIC_VALUE + + arm.SystemReset() +} diff --git a/src/machine/machine_atsamd51g19.go b/src/machine/machine_atsamd51g19.go new file mode 100644 index 00000000..fa4ddbc8 --- /dev/null +++ b/src/machine/machine_atsamd51g19.go @@ -0,0 +1,569 @@ +// +build sam,atsamd51,atsamd51g19 + +// Peripheral abstraction layer for the atsamd51. +// +// Datasheet: +// http://ww1.microchip.com/downloads/en/DeviceDoc/60001507C.pdf +// +package machine + +import ( + "device/sam" +) + +// Return the register and mask to enable a given GPIO pin. This can be used to +// implement bit-banged drivers. +func (p Pin) PortMaskSet() (*uint32, uint32) { + if p < 32 { + return &sam.PORT.OUTSET0.Reg, 1 << uint8(p) + } else { + return &sam.PORT.OUTSET1.Reg, 1 << uint8(p-32) + } +} + +// Return the register and mask to disable a given port. This can be used to +// implement bit-banged drivers. +func (p Pin) PortMaskClear() (*uint32, uint32) { + if p < 32 { + return &sam.PORT.OUTCLR0.Reg, 1 << uint8(p) + } else { + return &sam.PORT.OUTCLR1.Reg, 1 << uint8(p-32) + } +} + +// Set the pin to high or low. +// Warning: only use this on an output pin! +func (p Pin) Set(high bool) { + if p < 32 { + if high { + sam.PORT.OUTSET0.Set(1 << uint8(p)) + } else { + sam.PORT.OUTCLR0.Set(1 << uint8(p)) + } + } else { + if high { + sam.PORT.OUTSET1.Set(1 << uint8(p-32)) + } else { + sam.PORT.OUTCLR1.Set(1 << uint8(p-32)) + } + } +} + +// Get returns the current value of a GPIO pin. +func (p Pin) Get() bool { + if p < 32 { + return (sam.PORT.IN0.Get()>>uint8(p))&1 > 0 + } else { + return (sam.PORT.IN1.Get()>>(uint8(p)-32))&1 > 0 + } +} + +// Configure this pin with the given configuration. +func (p Pin) Configure(config PinConfig) { + switch config.Mode { + case PinOutput: + if p < 32 { + sam.PORT.DIRSET0.Set(1 << uint8(p)) + // output is also set to input enable so pin can read back its own value + p.setPinCfg(sam.PORT_PINCFG0_INEN) + } else { + sam.PORT.DIRSET1.Set(1 << uint8(p-32)) + // output is also set to input enable so pin can read back its own value + p.setPinCfg(sam.PORT_PINCFG0_INEN) + } + + case PinInput: + if p < 32 { + sam.PORT.DIRCLR0.Set(1 << uint8(p)) + p.setPinCfg(sam.PORT_PINCFG0_INEN) + } else { + sam.PORT.DIRCLR1.Set(1< 0 { + // odd pin, so save the even pins + val := p.getPMux() & sam.PORT_PMUX0_PMUXE_Msk + p.setPMux(val | (uint8(PinSERCOM) << sam.PORT_PMUX0_PMUXO_Pos)) + } else { + // even pin, so save the odd pins + val := p.getPMux() & sam.PORT_PMUX0_PMUXO_Msk + p.setPMux(val | (uint8(PinSERCOM) << sam.PORT_PMUX0_PMUXE_Pos)) + } + // enable port config + p.setPinCfg(sam.PORT_PINCFG0_PMUXEN | sam.PORT_PINCFG0_DRVSTR | sam.PORT_PINCFG0_INEN) + + case PinSERCOMAlt: + if p&1 > 0 { + // odd pin, so save the even pins + val := p.getPMux() & sam.PORT_PMUX0_PMUXE_Msk + p.setPMux(val | (uint8(PinSERCOMAlt) << sam.PORT_PMUX0_PMUXO_Pos)) + } else { + // even pin, so save the odd pins + val := p.getPMux() & sam.PORT_PMUX0_PMUXO_Msk + p.setPMux(val | (uint8(PinSERCOMAlt) << sam.PORT_PMUX0_PMUXE_Pos)) + } + // enable port config + p.setPinCfg(sam.PORT_PINCFG0_PMUXEN | sam.PORT_PINCFG0_DRVSTR) + + case PinCom: + if p&1 > 0 { + // odd pin, so save the even pins + val := p.getPMux() & sam.PORT_PMUX0_PMUXE_Msk + p.setPMux(val | (uint8(PinCom) << sam.PORT_PMUX0_PMUXO_Pos)) + } else { + // even pin, so save the odd pins + val := p.getPMux() & sam.PORT_PMUX0_PMUXO_Msk + p.setPMux(val | (uint8(PinCom) << sam.PORT_PMUX0_PMUXE_Pos)) + } + // enable port config + p.setPinCfg(sam.PORT_PINCFG0_PMUXEN) + case PinAnalog: + if p&1 > 0 { + // odd pin, so save the even pins + val := p.getPMux() & sam.PORT_PMUX0_PMUXE_Msk + p.setPMux(val | (uint8(PinAnalog) << sam.PORT_PMUX0_PMUXO_Pos)) + } else { + // even pin, so save the odd pins + val := p.getPMux() & sam.PORT_PMUX0_PMUXO_Msk + p.setPMux(val | (uint8(PinAnalog) << sam.PORT_PMUX0_PMUXE_Pos)) + } + // enable port config + p.setPinCfg(sam.PORT_PINCFG0_PMUXEN | sam.PORT_PINCFG0_DRVSTR) + } +} + +// getPMux returns the value for the correct PMUX register for this pin. +func (p Pin) getPMux() uint8 { + switch uint8(p) >> 1 { + case 0: + return sam.PORT.PMUX0_0.Get() + case 1: + return sam.PORT.PMUX0_1.Get() + case 2: + return sam.PORT.PMUX0_2.Get() + case 3: + return sam.PORT.PMUX0_3.Get() + case 4: + return sam.PORT.PMUX0_4.Get() + case 5: + return sam.PORT.PMUX0_5.Get() + case 6: + return sam.PORT.PMUX0_6.Get() + case 7: + return sam.PORT.PMUX0_7.Get() + case 8: + return sam.PORT.PMUX0_8.Get() + case 9: + return sam.PORT.PMUX0_9.Get() + case 10: + return sam.PORT.PMUX0_10.Get() + case 11: + return sam.PORT.PMUX0_11.Get() + case 12: + return sam.PORT.PMUX0_12.Get() + case 13: + return sam.PORT.PMUX0_13.Get() + case 14: + return sam.PORT.PMUX0_14.Get() + case 15: + return sam.PORT.PMUX0_15.Get() + case 16: + return uint8(sam.PORT.PMUX1_0.Get()>>0) & 0xff + case 17: + return uint8(sam.PORT.PMUX1_0.Get()>>8) & 0xff + case 18: + return uint8(sam.PORT.PMUX1_0.Get()>>16) & 0xff + case 19: + return uint8(sam.PORT.PMUX1_0.Get()>>24) & 0xff + case 20: + return uint8(sam.PORT.PMUX1_4.Get()>>0) & 0xff + case 21: + return uint8(sam.PORT.PMUX1_4.Get()>>8) & 0xff + case 22: + return uint8(sam.PORT.PMUX1_4.Get()>>16) & 0xff + case 23: + return uint8(sam.PORT.PMUX1_4.Get()>>24) & 0xff + case 24: + return uint8(sam.PORT.PMUX1_8.Get()>>0) & 0xff + case 25: + return uint8(sam.PORT.PMUX1_8.Get()>>8) & 0xff + case 26: + return uint8(sam.PORT.PMUX1_8.Get()>>16) & 0xff + case 27: + return uint8(sam.PORT.PMUX1_8.Get()>>24) & 0xff + case 28: + return uint8(sam.PORT.PMUX1_12.Get()>>0) & 0xff + case 29: + return uint8(sam.PORT.PMUX1_12.Get()>>8) & 0xff + case 30: + return uint8(sam.PORT.PMUX1_12.Get()>>16) & 0xff + case 31: + return uint8(sam.PORT.PMUX1_12.Get()>>24) & 0xff + default: + return 0 + } +} + +// setPMux sets the value for the correct PMUX register for this pin. +func (p Pin) setPMux(val uint8) { + switch uint8(p) >> 1 { + case 0: + sam.PORT.PMUX0_0.Set(val) + case 1: + sam.PORT.PMUX0_1.Set(val) + case 2: + sam.PORT.PMUX0_2.Set(val) + case 3: + sam.PORT.PMUX0_3.Set(val) + case 4: + sam.PORT.PMUX0_4.Set(val) + case 5: + sam.PORT.PMUX0_5.Set(val) + case 6: + sam.PORT.PMUX0_6.Set(val) + case 7: + sam.PORT.PMUX0_7.Set(val) + case 8: + sam.PORT.PMUX0_8.Set(val) + case 9: + sam.PORT.PMUX0_9.Set(val) + case 10: + sam.PORT.PMUX0_10.Set(val) + case 11: + sam.PORT.PMUX0_11.Set(val) + case 12: + sam.PORT.PMUX0_12.Set(val) + case 13: + sam.PORT.PMUX0_13.Set(val) + case 14: + sam.PORT.PMUX0_14.Set(val) + case 15: + sam.PORT.PMUX0_15.Set(val) + case 16: + sam.PORT.PMUX1_0.Set(sam.PORT.PMUX1_0.Get()&^(0xff<<0) | (uint32(val) << 0)) + case 17: + sam.PORT.PMUX1_0.Set(sam.PORT.PMUX1_0.Get()&^(0xff<<8) | (uint32(val) << 8)) + case 18: + sam.PORT.PMUX1_0.Set(sam.PORT.PMUX1_0.Get()&^(0xff<<16) | (uint32(val) << 16)) + case 19: + sam.PORT.PMUX1_0.Set(sam.PORT.PMUX1_0.Get()&^(0xff<<24) | (uint32(val) << 24)) + case 20: + sam.PORT.PMUX1_4.Set(sam.PORT.PMUX1_4.Get()&^(0xff<<0) | (uint32(val) << 0)) + case 21: + sam.PORT.PMUX1_4.Set(sam.PORT.PMUX1_4.Get()&^(0xff<<8) | (uint32(val) << 8)) + case 22: + sam.PORT.PMUX1_4.Set(sam.PORT.PMUX1_4.Get()&^(0xff<<16) | (uint32(val) << 16)) + case 23: + sam.PORT.PMUX1_4.Set(sam.PORT.PMUX1_4.Get()&^(0xff<<24) | (uint32(val) << 24)) + case 24: + sam.PORT.PMUX1_8.Set(sam.PORT.PMUX1_8.Get()&^(0xff<<0) | (uint32(val) << 0)) + case 25: + sam.PORT.PMUX1_8.Set(sam.PORT.PMUX1_8.Get()&^(0xff<<8) | (uint32(val) << 8)) + case 26: + sam.PORT.PMUX1_8.Set(sam.PORT.PMUX1_8.Get()&^(0xff<<16) | (uint32(val) << 16)) + case 27: + sam.PORT.PMUX1_8.Set(sam.PORT.PMUX1_8.Get()&^(0xff<<24) | (uint32(val) << 24)) + case 28: + sam.PORT.PMUX1_12.Set(sam.PORT.PMUX1_12.Get()&^(0xff<<0) | (uint32(val) << 0)) + case 29: + sam.PORT.PMUX1_12.Set(sam.PORT.PMUX1_12.Get()&^(0xff<<8) | (uint32(val) << 8)) + case 30: + sam.PORT.PMUX1_12.Set(sam.PORT.PMUX1_12.Get()&^(0xff<<16) | (uint32(val) << 16)) + case 31: + sam.PORT.PMUX1_12.Set(sam.PORT.PMUX1_12.Get()&^(0xff<<24) | (uint32(val) << 24)) + } +} + +// getPinCfg returns the value for the correct PINCFG register for this pin. +func (p Pin) getPinCfg() uint8 { + switch p { + case 0: + return sam.PORT.PINCFG0_0.Get() + case 1: + return sam.PORT.PINCFG0_1.Get() + case 2: + return sam.PORT.PINCFG0_2.Get() + case 3: + return sam.PORT.PINCFG0_3.Get() + case 4: + return sam.PORT.PINCFG0_4.Get() + case 5: + return sam.PORT.PINCFG0_5.Get() + case 6: + return sam.PORT.PINCFG0_6.Get() + case 7: + return sam.PORT.PINCFG0_7.Get() + case 8: + return sam.PORT.PINCFG0_8.Get() + case 9: + return sam.PORT.PINCFG0_9.Get() + case 10: + return sam.PORT.PINCFG0_10.Get() + case 11: + return sam.PORT.PINCFG0_11.Get() + case 12: + return sam.PORT.PINCFG0_12.Get() + case 13: + return sam.PORT.PINCFG0_13.Get() + case 14: + return sam.PORT.PINCFG0_14.Get() + case 15: + return sam.PORT.PINCFG0_15.Get() + case 16: + return sam.PORT.PINCFG0_16.Get() + case 17: + return sam.PORT.PINCFG0_17.Get() + case 18: + return sam.PORT.PINCFG0_18.Get() + case 19: + return sam.PORT.PINCFG0_19.Get() + case 20: + return sam.PORT.PINCFG0_20.Get() + case 21: + return sam.PORT.PINCFG0_21.Get() + case 22: + return sam.PORT.PINCFG0_22.Get() + case 23: + return sam.PORT.PINCFG0_23.Get() + case 24: + return sam.PORT.PINCFG0_24.Get() + case 25: + return sam.PORT.PINCFG0_25.Get() + case 26: + return sam.PORT.PINCFG0_26.Get() + case 27: + return sam.PORT.PINCFG0_27.Get() + case 28: + return sam.PORT.PINCFG0_28.Get() + case 29: + return sam.PORT.PINCFG0_29.Get() + case 30: + return sam.PORT.PINCFG0_30.Get() + case 31: + return sam.PORT.PINCFG0_31.Get() + case 32: // PB00 + return uint8(sam.PORT.PINCFG1_0.Get()>>0) & 0xff + case 33: // PB01 + return uint8(sam.PORT.PINCFG1_0.Get()>>8) & 0xff + case 34: // PB02 + return uint8(sam.PORT.PINCFG1_0.Get()>>16) & 0xff + case 35: // PB03 + return uint8(sam.PORT.PINCFG1_0.Get()>>24) & 0xff + case 37: // PB04 + return uint8(sam.PORT.PINCFG1_4.Get()>>0) & 0xff + case 38: // PB05 + return uint8(sam.PORT.PINCFG1_4.Get()>>8) & 0xff + case 39: // PB06 + return uint8(sam.PORT.PINCFG1_4.Get()>>16) & 0xff + case 40: // PB07 + return uint8(sam.PORT.PINCFG1_4.Get()>>24) & 0xff + case 41: // PB08 + return uint8(sam.PORT.PINCFG1_8.Get()>>0) & 0xff + case 42: // PB09 + return uint8(sam.PORT.PINCFG1_8.Get()>>8) & 0xff + case 43: // PB10 + return uint8(sam.PORT.PINCFG1_8.Get()>>16) & 0xff + case 44: // PB11 + return uint8(sam.PORT.PINCFG1_8.Get()>>24) & 0xff + case 45: // PB12 + return uint8(sam.PORT.PINCFG1_12.Get()>>0) & 0xff + case 46: // PB13 + return uint8(sam.PORT.PINCFG1_12.Get()>>8) & 0xff + case 47: // PB14 + return uint8(sam.PORT.PINCFG1_12.Get()>>16) & 0xff + case 48: // PB15 + return uint8(sam.PORT.PINCFG1_12.Get()>>24) & 0xff + case 49: // PB16 + return uint8(sam.PORT.PINCFG1_16.Get()>>0) & 0xff + case 50: // PB17 + return uint8(sam.PORT.PINCFG1_16.Get()>>8) & 0xff + case 51: // PB18 + return uint8(sam.PORT.PINCFG1_16.Get()>>16) & 0xff + case 52: // PB19 + return uint8(sam.PORT.PINCFG1_16.Get()>>24) & 0xff + case 53: // PB20 + return uint8(sam.PORT.PINCFG1_20.Get()>>0) & 0xff + case 54: // PB21 + return uint8(sam.PORT.PINCFG1_20.Get()>>8) & 0xff + case 55: // PB22 + return uint8(sam.PORT.PINCFG1_20.Get()>>16) & 0xff + case 56: // PB23 + return uint8(sam.PORT.PINCFG1_20.Get()>>24) & 0xff + case 57: // PB24 + return uint8(sam.PORT.PINCFG1_24.Get()>>0) & 0xff + case 58: // PB25 + return uint8(sam.PORT.PINCFG1_24.Get()>>8) & 0xff + case 59: // PB26 + return uint8(sam.PORT.PINCFG1_24.Get()>>16) & 0xff + case 60: // PB27 + return uint8(sam.PORT.PINCFG1_24.Get()>>24) & 0xff + case 61: // PB28 + return uint8(sam.PORT.PINCFG1_28.Get()>>0) & 0xff + case 62: // PB29 + return uint8(sam.PORT.PINCFG1_28.Get()>>8) & 0xff + case 63: // PB30 + return uint8(sam.PORT.PINCFG1_28.Get()>>16) & 0xff + case 64: // PB31 + return uint8(sam.PORT.PINCFG1_28.Get()>>24) & 0xff + default: + return 0 + } +} + +// setPinCfg sets the value for the correct PINCFG register for this pin. +func (p Pin) setPinCfg(val uint8) { + switch p { + case 0: + sam.PORT.PINCFG0_0.Set(val) + case 1: + sam.PORT.PINCFG0_1.Set(val) + case 2: + sam.PORT.PINCFG0_2.Set(val) + case 3: + sam.PORT.PINCFG0_3.Set(val) + case 4: + sam.PORT.PINCFG0_4.Set(val) + case 5: + sam.PORT.PINCFG0_5.Set(val) + case 6: + sam.PORT.PINCFG0_6.Set(val) + case 7: + sam.PORT.PINCFG0_7.Set(val) + case 8: + sam.PORT.PINCFG0_8.Set(val) + case 9: + sam.PORT.PINCFG0_9.Set(val) + case 10: + sam.PORT.PINCFG0_10.Set(val) + case 11: + sam.PORT.PINCFG0_11.Set(val) + case 12: + sam.PORT.PINCFG0_12.Set(val) + case 13: + sam.PORT.PINCFG0_13.Set(val) + case 14: + sam.PORT.PINCFG0_14.Set(val) + case 15: + sam.PORT.PINCFG0_15.Set(val) + case 16: + sam.PORT.PINCFG0_16.Set(val) + case 17: + sam.PORT.PINCFG0_17.Set(val) + case 18: + sam.PORT.PINCFG0_18.Set(val) + case 19: + sam.PORT.PINCFG0_19.Set(val) + case 20: + sam.PORT.PINCFG0_20.Set(val) + case 21: + sam.PORT.PINCFG0_21.Set(val) + case 22: + sam.PORT.PINCFG0_22.Set(val) + case 23: + sam.PORT.PINCFG0_23.Set(val) + case 24: + sam.PORT.PINCFG0_24.Set(val) + case 25: + sam.PORT.PINCFG0_25.Set(val) + case 26: + sam.PORT.PINCFG0_26.Set(val) + case 27: + sam.PORT.PINCFG0_27.Set(val) + case 28: + sam.PORT.PINCFG0_28.Set(val) + case 29: + sam.PORT.PINCFG0_29.Set(val) + case 30: + sam.PORT.PINCFG0_30.Set(val) + case 31: + sam.PORT.PINCFG0_31.Set(val) + case 32: // PB00 + sam.PORT.PINCFG1_0.Set(sam.PORT.PINCFG1_0.Get()&^(0xff<<0) | (uint32(val) << 0)) + case 33: // PB01 + sam.PORT.PINCFG1_0.Set(sam.PORT.PINCFG1_0.Get()&^(0xff<<8) | (uint32(val) << 8)) + case 34: // PB02 + sam.PORT.PINCFG1_0.Set(sam.PORT.PINCFG1_0.Get()&^(0xff<<16) | (uint32(val) << 16)) + case 35: // PB03 + sam.PORT.PINCFG1_0.Set(sam.PORT.PINCFG1_0.Get()&^(0xff<<24) | (uint32(val) << 24)) + case 36: // PB04 + sam.PORT.PINCFG1_4.Set(sam.PORT.PINCFG1_4.Get()&^(0xff<<0) | (uint32(val) << 0)) + case 37: // PB05 + sam.PORT.PINCFG1_4.Set(sam.PORT.PINCFG1_4.Get()&^(0xff<<8) | (uint32(val) << 8)) + case 38: // PB06 + sam.PORT.PINCFG1_4.Set(sam.PORT.PINCFG1_4.Get()&^(0xff<<16) | (uint32(val) << 16)) + case 39: // PB07 + sam.PORT.PINCFG1_4.Set(sam.PORT.PINCFG1_4.Get()&^(0xff<<24) | (uint32(val) << 24)) + case 40: // PB08 + sam.PORT.PINCFG1_8.Set(sam.PORT.PINCFG1_8.Get()&^(0xff<<0) | (uint32(val) << 0)) + case 41: // PB09 + sam.PORT.PINCFG1_8.Set(sam.PORT.PINCFG1_8.Get()&^(0xff<<8) | (uint32(val) << 8)) + case 42: // PB10 + sam.PORT.PINCFG1_8.Set(sam.PORT.PINCFG1_8.Get()&^(0xff<<16) | (uint32(val) << 16)) + case 43: // PB11 + sam.PORT.PINCFG1_8.Set(sam.PORT.PINCFG1_8.Get()&^(0xff<<24) | (uint32(val) << 24)) + case 44: // PB12 + sam.PORT.PINCFG1_12.Set(sam.PORT.PINCFG1_12.Get()&^(0xff<<0) | (uint32(val) << 0)) + case 45: // PB13 + sam.PORT.PINCFG1_12.Set(sam.PORT.PINCFG1_12.Get()&^(0xff<<8) | (uint32(val) << 8)) + case 46: // PB14 + sam.PORT.PINCFG1_12.Set(sam.PORT.PINCFG1_12.Get()&^(0xff<<16) | (uint32(val) << 16)) + case 47: // PB15 + sam.PORT.PINCFG1_12.Set(sam.PORT.PINCFG1_12.Get()&^(0xff<<24) | (uint32(val) << 24)) + case 48: // PB16 + sam.PORT.PINCFG1_16.Set(sam.PORT.PINCFG1_16.Get()&^(0xff<<0) | (uint32(val) << 0)) + case 49: // PB17 + sam.PORT.PINCFG1_16.Set(sam.PORT.PINCFG1_16.Get()&^(0xff<<8) | (uint32(val) << 8)) + case 50: // PB18 + sam.PORT.PINCFG1_16.Set(sam.PORT.PINCFG1_16.Get()&^(0xff<<16) | (uint32(val) << 16)) + case 51: // PB19 + sam.PORT.PINCFG1_16.Set(sam.PORT.PINCFG1_16.Get()&^(0xff<<24) | (uint32(val) << 24)) + case 52: // PB20 + sam.PORT.PINCFG1_20.Set(sam.PORT.PINCFG1_20.Get()&^(0xff<<0) | (uint32(val) << 0)) + case 53: // PB21 + sam.PORT.PINCFG1_20.Set(sam.PORT.PINCFG1_20.Get()&^(0xff<<8) | (uint32(val) << 8)) + case 54: // PB22 + sam.PORT.PINCFG1_20.Set(sam.PORT.PINCFG1_20.Get()&^(0xff<<16) | (uint32(val) << 16)) + case 55: // PB23 + sam.PORT.PINCFG1_20.Set(sam.PORT.PINCFG1_20.Get()&^(0xff<<24) | (uint32(val) << 24)) + case 56: // PB24 + sam.PORT.PINCFG1_24.Set(sam.PORT.PINCFG1_24.Get()&^(0xff<<0) | (uint32(val) << 0)) + case 57: // PB25 + sam.PORT.PINCFG1_24.Set(sam.PORT.PINCFG1_24.Get()&^(0xff<<8) | (uint32(val) << 8)) + case 58: // PB26 + sam.PORT.PINCFG1_24.Set(sam.PORT.PINCFG1_24.Get()&^(0xff<<16) | (uint32(val) << 16)) + case 59: // PB27 + sam.PORT.PINCFG1_24.Set(sam.PORT.PINCFG1_24.Get()&^(0xff<<24) | (uint32(val) << 24)) + case 60: // PB28 + sam.PORT.PINCFG1_28.Set(sam.PORT.PINCFG1_28.Get()&^(0xff<<0) | (uint32(val) << 0)) + case 61: // PB29 + sam.PORT.PINCFG1_28.Set(sam.PORT.PINCFG1_28.Get()&^(0xff<<8) | (uint32(val) << 8)) + case 62: // PB30 + sam.PORT.PINCFG1_28.Set(sam.PORT.PINCFG1_28.Get()&^(0xff<<16) | (uint32(val) << 16)) + case 63: // PB31 + sam.PORT.PINCFG1_28.Set(sam.PORT.PINCFG1_28.Get()&^(0xff<<24) | (uint32(val) << 24)) + } +} diff --git a/src/runtime/runtime_atsamd51.go b/src/runtime/runtime_atsamd51.go new file mode 100644 index 00000000..fceccefb --- /dev/null +++ b/src/runtime/runtime_atsamd51.go @@ -0,0 +1,302 @@ +// +build sam,atsamd51 + +package runtime + +import ( + "device/arm" + "device/sam" + "machine" +) + +type timeUnit int64 + +//go:export Reset_Handler +func main() { + preinit() + initAll() + callMain() + abort() +} + +func init() { + initClocks() + initRTC() + initSERCOMClocks() + initUSBClock() + initADCClock() + + // connect to USB CDC interface + machine.UART0.Configure(machine.UARTConfig{}) +} + +func putchar(c byte) { + machine.UART0.WriteByte(c) +} + +func initClocks() { + // set flash wait state + sam.NVMCTRL.CTRLA.SetBits(0 << sam.NVMCTRL_CTRLA_RWS_Pos) + + // software reset + sam.GCLK.CTRLA.SetBits(sam.GCLK_CTRLA_SWRST) + for sam.GCLK.SYNCBUSY.HasBits(sam.GCLK_SYNCBUSY_SWRST) { + } + + // Set OSCULP32K as source of Generic Clock Generator 3 + // GCLK->GENCTRL[GENERIC_CLOCK_GENERATOR_XOSC32K].reg = GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_OSCULP32K) | GCLK_GENCTRL_GENEN; //generic clock gen 3 + sam.GCLK.GENCTRL3.Set((sam.GCLK_GENCTRL_SRC_OSCULP32K << sam.GCLK_GENCTRL_SRC_Pos) | + sam.GCLK_GENCTRL_GENEN) + for sam.GCLK.SYNCBUSY.HasBits(sam.GCLK_SYNCBUSY_GENCTRL3) { + } + + // Set OSCULP32K as source of Generic Clock Generator 0 + sam.GCLK.GENCTRL0.Set((sam.GCLK_GENCTRL_SRC_OSCULP32K << sam.GCLK_GENCTRL_SRC_Pos) | + sam.GCLK_GENCTRL_GENEN) + for sam.GCLK.SYNCBUSY.HasBits(sam.GCLK_SYNCBUSY_GENCTRL0) { + } + + // Enable DFLL48M clock + sam.OSCCTRL.DFLLCTRLA.Set(0) + sam.OSCCTRL.DFLLMUL.Set((0x1 << sam.OSCCTRL_DFLLMUL_CSTEP_Pos) | + (0x1 << sam.OSCCTRL_DFLLMUL_FSTEP_Pos) | + (0x0 << sam.OSCCTRL_DFLLMUL_MUL_Pos)) + for sam.OSCCTRL.DFLLSYNC.HasBits(sam.OSCCTRL_DFLLSYNC_DFLLMUL) { + } + + sam.OSCCTRL.DFLLCTRLB.Set(0) + for sam.OSCCTRL.DFLLSYNC.HasBits(sam.OSCCTRL_DFLLSYNC_DFLLCTRLB) { + } + + sam.OSCCTRL.DFLLCTRLA.SetBits(sam.OSCCTRL_DFLLCTRLA_ENABLE) + for sam.OSCCTRL.DFLLSYNC.HasBits(sam.OSCCTRL_DFLLSYNC_ENABLE) { + } + + sam.OSCCTRL.DFLLVAL.Set(sam.OSCCTRL.DFLLVAL.Get()) + for sam.OSCCTRL.DFLLSYNC.HasBits(sam.OSCCTRL_DFLLSYNC_DFLLVAL) { + } + + sam.OSCCTRL.DFLLCTRLB.Set(sam.OSCCTRL_DFLLCTRLB_WAITLOCK | + sam.OSCCTRL_DFLLCTRLB_CCDIS | + sam.OSCCTRL_DFLLCTRLB_USBCRM) + for !sam.OSCCTRL.STATUS.HasBits(sam.OSCCTRL_STATUS_DFLLRDY) { + } + + // set GCLK7 to use DFLL48M as clock source + sam.GCLK.GENCTRL7.Set((sam.GCLK_GENCTRL_SRC_DFLL << sam.GCLK_GENCTRL_SRC_Pos) | + (24 << sam.GCLK_GENCTRL_DIVSEL_Pos) | + sam.GCLK_GENCTRL_GENEN) + for sam.GCLK.SYNCBUSY.HasBits(sam.GCLK_SYNCBUSY_GENCTRL7) { + } + + // Set up the PLLs + + // Set PLL0 at 120MHz + sam.GCLK.PCHCTRL1.Set(sam.GCLK_PCHCTRL_CHEN | + (sam.GCLK_PCHCTRL_GEN_GCLK7 << sam.GCLK_PCHCTRL_GEN_Pos)) + + sam.OSCCTRL.DPLLRATIO0.Set((0x0 << sam.OSCCTRL_DPLLRATIO_LDRFRAC_Pos) | + (59 << sam.OSCCTRL_DPLLRATIO_LDR_Pos)) + for sam.OSCCTRL.DPLLSYNCBUSY0.HasBits(sam.OSCCTRL_DPLLSYNCBUSY_DPLLRATIO) { + } + + // MUST USE LBYPASS DUE TO BUG IN REV A OF SAMD51, via Adafruit lib. + sam.OSCCTRL.DPLLCTRLB0.Set((sam.OSCCTRL_DPLLCTRLB_REFCLK_GCLK << sam.OSCCTRL_DPLLCTRLB_REFCLK_Pos) | + sam.OSCCTRL_DPLLCTRLB_LBYPASS) + + sam.OSCCTRL.DPLLCTRLA0.Set(sam.OSCCTRL_DPLLCTRLA_ENABLE) + for !sam.OSCCTRL.DPLLSTATUS0.HasBits(sam.OSCCTRL_DPLLSTATUS_CLKRDY) || + !sam.OSCCTRL.DPLLSTATUS0.HasBits(sam.OSCCTRL_DPLLSTATUS_LOCK) { + } + + // // Set PLL1 to 100MHz + sam.GCLK.PCHCTRL2.Set(sam.GCLK_PCHCTRL_CHEN | + (sam.GCLK_PCHCTRL_GEN_GCLK7 << sam.GCLK_PCHCTRL_GEN_Pos)) + + sam.OSCCTRL.DPLLRATIO1.Set((0x0 << sam.OSCCTRL_DPLLRATIO_LDRFRAC_Pos) | + (49 << sam.OSCCTRL_DPLLRATIO_LDR_Pos)) // this means 100 Mhz? + for sam.OSCCTRL.DPLLSYNCBUSY1.HasBits(sam.OSCCTRL_DPLLSYNCBUSY_DPLLRATIO) { + } + + // // MUST USE LBYPASS DUE TO BUG IN REV A OF SAMD51 + sam.OSCCTRL.DPLLCTRLB1.Set((sam.OSCCTRL_DPLLCTRLB_REFCLK_GCLK << sam.OSCCTRL_DPLLCTRLB_REFCLK_Pos) | + sam.OSCCTRL_DPLLCTRLB_LBYPASS) + + sam.OSCCTRL.DPLLCTRLA1.Set(sam.OSCCTRL_DPLLCTRLA_ENABLE) + // for !sam.OSCCTRL.DPLLSTATUS1.HasBits(sam.OSCCTRL_DPLLSTATUS_CLKRDY) || + // !sam.OSCCTRL.DPLLSTATUS1.HasBits(sam.OSCCTRL_DPLLSTATUS_LOCK) { + // } + + // Set up the peripheral clocks + // Set 48MHZ CLOCK FOR USB + sam.GCLK.GENCTRL1.Set((sam.GCLK_GENCTRL_SRC_DFLL << sam.GCLK_GENCTRL_SRC_Pos) | + sam.GCLK_GENCTRL_IDC | + sam.GCLK_GENCTRL_GENEN) + for sam.GCLK.SYNCBUSY.HasBits(sam.GCLK_SYNCBUSY_GENCTRL1) { + } + + // // Set 100MHZ CLOCK FOR OTHER PERIPHERALS + // sam.GCLK.GENCTRL2.Set((sam.GCLK_GENCTRL_SRC_DPLL1 << sam.GCLK_GENCTRL_SRC_Pos) | + // sam.GCLK_GENCTRL_IDC | + // sam.GCLK_GENCTRL_GENEN) + // for sam.GCLK.SYNCBUSY.HasBits(sam.GCLK_SYNCBUSY_GENCTRL2) { + // } + + // // Set 12MHZ CLOCK FOR DAC + sam.GCLK.GENCTRL4.Set((sam.GCLK_GENCTRL_SRC_DFLL << sam.GCLK_GENCTRL_SRC_Pos) | + sam.GCLK_GENCTRL_IDC | + (4 << sam.GCLK_GENCTRL_DIVSEL_Pos) | + sam.GCLK_GENCTRL_GENEN) + for sam.GCLK.SYNCBUSY.HasBits(sam.GCLK_SYNCBUSY_GENCTRL4) { + } + + // // Set up main clock + sam.GCLK.GENCTRL0.Set((sam.GCLK_GENCTRL_SRC_DPLL0 << sam.GCLK_GENCTRL_SRC_Pos) | + sam.GCLK_GENCTRL_IDC | + sam.GCLK_GENCTRL_GENEN) + for sam.GCLK.SYNCBUSY.HasBits(sam.GCLK_SYNCBUSY_GENCTRL0) { + } + + sam.MCLK.CPUDIV.Set(sam.MCLK_CPUDIV_DIV_DIV1) + + // Use the LDO regulator by default + sam.SUPC.VREG.ClearBits(sam.SUPC_VREG_SEL) + + // Start up the "Debug Watchpoint and Trace" unit, so that we can use + // it's 32bit cycle counter for timing. + //CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; + //DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk; +} + +func initRTC() { + // turn on digital interface clock + sam.MCLK.APBAMASK.SetBits(sam.MCLK_APBAMASK_RTC_) + + // disable RTC + sam.RTC_MODE0.CTRLA.ClearBits(sam.RTC_MODE0_CTRLA_ENABLE) + //sam.RTC_MODE0.CTRLA.Set(0) + for sam.RTC_MODE0.SYNCBUSY.HasBits(sam.RTC_MODE0_SYNCBUSY_ENABLE) { + } + + // reset RTC + sam.RTC_MODE0.CTRLA.SetBits(sam.RTC_MODE0_CTRLA_SWRST) + for sam.RTC_MODE0.SYNCBUSY.HasBits(sam.RTC_MODE0_SYNCBUSY_SWRST) { + } + + // set to use ulp 32k oscillator + sam.OSC32KCTRL.OSCULP32K.Set(sam.OSC32KCTRL_OSCULP32K_EN32K) + sam.OSC32KCTRL.RTCCTRL.Set(sam.OSC32KCTRL_RTCCTRL_RTCSEL_ULP32K) + + // set Mode0 to 32-bit counter (mode 0) with prescaler 1 and GCLK2 is 32KHz/1 + sam.RTC_MODE0.CTRLA.Set((sam.RTC_MODE0_CTRLA_MODE_COUNT32 << sam.RTC_MODE0_CTRLA_MODE_Pos) | + (sam.RTC_MODE0_CTRLA_PRESCALER_DIV1 << sam.RTC_MODE0_CTRLA_PRESCALER_Pos) | + (sam.RTC_MODE0_CTRLA_COUNTSYNC)) + + // re-enable RTC + sam.RTC_MODE0.CTRLA.SetBits(sam.RTC_MODE0_CTRLA_ENABLE) + for sam.RTC_MODE0.SYNCBUSY.HasBits(sam.RTC_MODE0_SYNCBUSY_ENABLE) { + } + + arm.SetPriority(sam.IRQ_RTC, 0xc0) + arm.EnableIRQ(sam.IRQ_RTC) +} + +func waitForSync() { + // for sam.GCLK.STATUS.HasBits(sam.GCLK_STATUS_SYNCBUSY) { + // } +} + +// treat all ticks params coming from runtime as being in microseconds +const tickMicros = 1000 + +var ( + timestamp timeUnit // ticks since boottime + timerLastCounter uint64 +) + +//go:volatile +type isrFlag bool + +var timerWakeup isrFlag + +const asyncScheduler = false + +// sleepTicks should sleep for d number of microseconds. +func sleepTicks(d timeUnit) { + for d != 0 { + ticks() // update timestamp + ticks := uint32(d) + timerSleep(ticks) + d -= timeUnit(ticks) + } +} + +// ticks returns number of microseconds since start. +func ticks() timeUnit { + // request read of count + // sam.RTC_MODE0.READREQ.Set(sam.RTC_MODE0_READREQ_RREQ) + // waitForSync() + + rtcCounter := (uint64(sam.RTC_MODE0.COUNT.Get()) * 305) / 10 // each counter tick == 30.5us + offset := (rtcCounter - timerLastCounter) // change since last measurement + timerLastCounter = rtcCounter + timestamp += timeUnit(offset) // TODO: not precise + return timestamp +} + +// ticks are in microseconds +func timerSleep(ticks uint32) { + timerWakeup = false + if ticks < 30 { + // have to have at least one clock count + ticks = 30 + } + + // request read of count + // sam.RTC_MODE0.READREQ.Set(sam.RTC_MODE0_READREQ_RREQ) + // waitForSync() + + // set compare value + cnt := sam.RTC_MODE0.COUNT.Get() + sam.RTC_MODE0.COMP0.Set(uint32(cnt) + (ticks * 10 / 305)) // each counter tick == 30.5us + waitForSync() + + // enable IRQ for CMP0 compare + sam.RTC_MODE0.INTENSET.SetBits(sam.RTC_MODE0_INTENSET_CMP0) + + for !timerWakeup { + arm.Asm("wfi") + } +} + +//go:export RTC_IRQHandler +func handleRTC() { + // disable IRQ for CMP0 compare + sam.RTC_MODE0.INTFLAG.SetBits(sam.RTC_MODE0_INTENSET_CMP0) + + timerWakeup = true +} + +func initUSBClock() { + // Turn on clock(s) for USB + //MCLK->APBBMASK.reg |= MCLK_APBBMASK_USB; + //MCLK->AHBMASK.reg |= MCLK_AHBMASK_USB; + sam.MCLK.APBBMASK.SetBits(sam.MCLK_APBBMASK_USB_) + sam.MCLK.AHBMASK.SetBits(sam.MCLK_AHBMASK_USB_) + + // Put Generic Clock Generator 1 as source for USB + //GCLK->PCHCTRL[USB_GCLK_ID].reg = GCLK_PCHCTRL_GEN_GCLK1_Val | (1 << GCLK_PCHCTRL_CHEN_Pos); + sam.GCLK.PCHCTRL10.Set((sam.GCLK_PCHCTRL_GEN_GCLK1 << sam.GCLK_PCHCTRL_GEN_Pos) | + sam.GCLK_PCHCTRL_CHEN) +} + +func initADCClock() { + // Turn on clocks for ADC0/ADC1. + sam.MCLK.APBDMASK.SetBits(sam.MCLK_APBDMASK_ADC0_) + sam.MCLK.APBDMASK.SetBits(sam.MCLK_APBDMASK_ADC1_) + + // Put Generic Clock Generator 1 as source for ADC0 and ADC1. + sam.GCLK.PCHCTRL40.Set((sam.GCLK_PCHCTRL_GEN_GCLK1 << sam.GCLK_PCHCTRL_GEN_Pos) | + sam.GCLK_PCHCTRL_CHEN) + sam.GCLK.PCHCTRL41.Set((sam.GCLK_PCHCTRL_GEN_GCLK1 << sam.GCLK_PCHCTRL_GEN_Pos) | + sam.GCLK_PCHCTRL_CHEN) +} diff --git a/src/runtime/runtime_atsamd51g19.go b/src/runtime/runtime_atsamd51g19.go new file mode 100644 index 00000000..ff425d6d --- /dev/null +++ b/src/runtime/runtime_atsamd51g19.go @@ -0,0 +1,43 @@ +// +build sam,atsamd51,atsamd51g19 + +package runtime + +import ( + "device/sam" +) + +func initSERCOMClocks() { + // Turn on clock to SERCOM0 for UART0 + sam.MCLK.APBAMASK.SetBits(sam.MCLK_APBAMASK_SERCOM0_) + sam.GCLK.PCHCTRL7.Set((sam.GCLK_PCHCTRL_GEN_GCLK1 << sam.GCLK_PCHCTRL_GEN_Pos) | + sam.GCLK_PCHCTRL_CHEN) + + // sets the "slow" clock shared by all SERCOM + sam.GCLK.PCHCTRL3.Set((sam.GCLK_PCHCTRL_GEN_GCLK1 << sam.GCLK_PCHCTRL_GEN_Pos) | + sam.GCLK_PCHCTRL_CHEN) + + // Turn on clock to SERCOM1 + sam.MCLK.APBAMASK.SetBits(sam.MCLK_APBAMASK_SERCOM1_) + sam.GCLK.PCHCTRL8.Set((sam.GCLK_PCHCTRL_GEN_GCLK1 << sam.GCLK_PCHCTRL_GEN_Pos) | + sam.GCLK_PCHCTRL_CHEN) + + // Turn on clock to SERCOM2 + sam.MCLK.APBBMASK.SetBits(sam.MCLK_APBBMASK_SERCOM2_) + sam.GCLK.PCHCTRL23.Set((sam.GCLK_PCHCTRL_GEN_GCLK1 << sam.GCLK_PCHCTRL_GEN_Pos) | + sam.GCLK_PCHCTRL_CHEN) + + // Turn on clock to SERCOM3 + sam.MCLK.APBBMASK.SetBits(sam.MCLK_APBBMASK_SERCOM3_) + sam.GCLK.PCHCTRL24.Set((sam.GCLK_PCHCTRL_GEN_GCLK1 << sam.GCLK_PCHCTRL_GEN_Pos) | + sam.GCLK_PCHCTRL_CHEN) + + // Turn on clock to SERCOM4 + sam.MCLK.APBDMASK.SetBits(sam.MCLK_APBDMASK_SERCOM4_) + sam.GCLK.PCHCTRL34.Set((sam.GCLK_PCHCTRL_GEN_GCLK1 << sam.GCLK_PCHCTRL_GEN_Pos) | + sam.GCLK_PCHCTRL_CHEN) + + // Turn on clock to SERCOM5 + sam.MCLK.APBDMASK.SetBits(sam.MCLK_APBDMASK_SERCOM5_) + sam.GCLK.PCHCTRL35.Set((sam.GCLK_PCHCTRL_GEN_GCLK1 << sam.GCLK_PCHCTRL_GEN_Pos) | + sam.GCLK_PCHCTRL_CHEN) +} diff --git a/targets/atsamd51.ld b/targets/atsamd51.ld new file mode 100644 index 00000000..908ce6a8 --- /dev/null +++ b/targets/atsamd51.ld @@ -0,0 +1,10 @@ + +MEMORY +{ + FLASH_TEXT (rw) : ORIGIN = 0x00000000+0x4000, LENGTH = 0x00080000-0x4000 /* First 16KB used by bootloader */ + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 0x00030000 +} + +_stack_size = 4K; + +INCLUDE "targets/arm.ld" diff --git a/targets/atsamd51g19a.json b/targets/atsamd51g19a.json new file mode 100644 index 00000000..31e25ee4 --- /dev/null +++ b/targets/atsamd51g19a.json @@ -0,0 +1,15 @@ +{ + "inherits": ["cortex-m"], + "llvm-target": "armv7em-none-eabi", + "build-tags": ["atsamd51g19", "atsamd51", "sam"], + "cflags": [ + "--target=armv7em-none-eabi", + "-Qunused-arguments" + ], + "ldflags": [ + "-T", "targets/atsamd51.ld" + ], + "extra-files": [ + "src/device/sam/atsamd51g19a.s" + ] +} diff --git a/targets/itsybitsy-m4.json b/targets/itsybitsy-m4.json new file mode 100644 index 00000000..24e90187 --- /dev/null +++ b/targets/itsybitsy-m4.json @@ -0,0 +1,5 @@ +{ + "inherits": ["atsamd51g19a"], + "build-tags": ["sam", "atsamd51g19a", "itsybitsy_m4"], + "flash": "bossac -d -i -e -w -v -R --offset=0x4000 {bin}" +}