From c055ff1812aef92248d64ac45634a4c89655c07f Mon Sep 17 00:00:00 2001 From: Eric Callahan Date: Mon, 16 May 2022 16:42:13 -0400 Subject: [PATCH] lpc176x: add source from Klipper Signed-off-by: Eric Callahan --- src/lpc176x/Kconfig | 89 +++++++++++ src/lpc176x/Makefile | 31 ++++ src/lpc176x/chipid.c | 46 ++++++ src/lpc176x/gpio.c | 144 +++++++++++++++++ src/lpc176x/gpio.h | 24 +++ src/lpc176x/internal.h | 27 ++++ src/lpc176x/main.c | 67 ++++++++ src/lpc176x/serial.c | 98 ++++++++++++ src/lpc176x/usb_cdc_ep.h | 10 ++ src/lpc176x/usbserial.c | 330 +++++++++++++++++++++++++++++++++++++++ 10 files changed, 866 insertions(+) create mode 100644 src/lpc176x/Kconfig create mode 100644 src/lpc176x/Makefile create mode 100644 src/lpc176x/chipid.c create mode 100644 src/lpc176x/gpio.c create mode 100644 src/lpc176x/gpio.h create mode 100644 src/lpc176x/internal.h create mode 100644 src/lpc176x/main.c create mode 100644 src/lpc176x/serial.c create mode 100644 src/lpc176x/usb_cdc_ep.h create mode 100644 src/lpc176x/usbserial.c diff --git a/src/lpc176x/Kconfig b/src/lpc176x/Kconfig new file mode 100644 index 0000000..d0a18fa --- /dev/null +++ b/src/lpc176x/Kconfig @@ -0,0 +1,89 @@ +# Kconfig settings for LPC176x processors + +if MACH_LPC176X + +config LPC_SELECT + bool + default y + select HAVE_GPIO + select HAVE_GPIO_ADC + select HAVE_GPIO_I2C + select HAVE_GPIO_SPI + select HAVE_GPIO_BITBANGING + select HAVE_STRICT_TIMING + select HAVE_CHIPID + select HAVE_GPIO_HARD_PWM + select HAVE_STEPPER_BOTH_EDGE + +config BOARD_DIRECTORY + string + default "lpc176x" + +choice + prompt "Processor model" + config MACH_LPC1768 + bool "lpc1768 (100 MHz)" + config MACH_LPC1769 + bool "lpc1769 (120 MHz)" +endchoice + +config MCU + string + default "lpc1768" if MACH_LPC1768 + default "lpc1769" if MACH_LPC1769 + +config CLOCK_FREQ + int + default 100000000 if MACH_LPC1768 + default 120000000 if MACH_LPC1769 + +config FLASH_SIZE + hex + default 0x80000 + +config RAM_START + hex + default 0x10000000 + +config RAM_SIZE + hex + default 0x7fe0 # (0x8000 - 32) - top 32 bytes used by IAP functions + +config STACK_SIZE + int + default 512 + +config FLASH_START + hex + default 0x0000 + +config USBSERIAL + bool +config SERIAL + bool +choice + prompt "Communication interface" + config LPC_USB + bool "USB" + select USBSERIAL + config LPC_SERIAL_UART0_P03_P02 + bool "Serial (on UART0 P0.3/P0.2)" + select SERIAL + config LPC_SERIAL_UART3_P429_P428 + bool "Serial (on UART3 P4.29/P4.28)" if LOW_LEVEL_OPTIONS + select SERIAL +endchoice + +###################################################################### +# Flash settings +###################################################################### + +config APPLICATION_START + hex + default 0x4000 + +config BLOCK_SIZE + int + default 64 + +endif diff --git a/src/lpc176x/Makefile b/src/lpc176x/Makefile new file mode 100644 index 0000000..bf80a36 --- /dev/null +++ b/src/lpc176x/Makefile @@ -0,0 +1,31 @@ +# lpc176x build rules + +# Setup the toolchain +CROSS_PREFIX=arm-none-eabi- + +dirs-y += src/lpc176x src/generic lib/lpc176x/device + +CFLAGS += -mthumb -mcpu=cortex-m3 -Ilib/lpc176x/device -Ilib/cmsis-core + +CFLAGS_canboot.elf += --specs=nano.specs --specs=nosys.specs +CFLAGS_canboot.elf += -T $(OUT)src/generic/armcm_link.ld +$(OUT)canboot.elf: $(OUT)src/generic/armcm_link.ld + +# Add source files +src-y += lpc176x/main.c lpc176x/gpio.c +src-y += generic/armcm_boot.c generic/armcm_irq.c +src-y += generic/armcm_timer.c generic/crc16_ccitt.c +src-y += ../lib/lpc176x/device/system_LPC17xx.c + +src-$(CONFIG_USBSERIAL) += lpc176x/usbserial.c lpc176x/chipid.c +src-$(CONFIG_USBSERIAL) += generic/usb_cdc.c +src-$(CONFIG_SERIAL) += lpc176x/serial.c generic/serial_irq.c + + +# Build the additional bin output file +target-y += $(OUT)canboot.bin + +$(OUT)canboot.bin: $(OUT)canboot.elf + @echo " Creating hex file $@" + $(Q)$(OBJCOPY) -O binary $< $(OUT)canboot.work + $(Q)$(PYTHON) ./scripts/buildbinary.py -b $(CONFIG_FLASH_START) -s $(CONFIG_APPLICATION_START) $(OUT)canboot.work $@ diff --git a/src/lpc176x/chipid.c b/src/lpc176x/chipid.c new file mode 100644 index 0000000..80b8061 --- /dev/null +++ b/src/lpc176x/chipid.c @@ -0,0 +1,46 @@ +// Support for extracting the hardware chip id on lpc176x +// +// Copyright (C) 2019 Kevin O'Connor +// +// This file may be distributed under the terms of the GNU GPLv3 license. + +#include "autoconf.h" // CONFIG_USB_SERIAL_NUMBER_CHIPID +#include "generic/irq.h" // irq_disable +#include "generic/usb_cdc.h" // usb_fill_serial +#include "generic/usbstd.h" // usb_string_descriptor +#include "sched.h" // DECL_INIT + +// IAP interface +#define IAP_LOCATION 0x1fff1ff1 +#define IAP_CMD_READ_UID 58 +#define IAP_UID_LEN 16 +typedef void (*IAP)(uint32_t *, uint32_t *); + +static struct { + struct usb_string_descriptor desc; + uint16_t data[IAP_UID_LEN * 2]; +} cdc_chipid; + +struct usb_string_descriptor * +usbserial_get_serialid(void) +{ + return &cdc_chipid.desc; +} + +void +chipid_init(void) +{ + if (!CONFIG_USB_SERIAL_NUMBER_CHIPID) + return; + + uint32_t iap_cmd_uid[5] = {IAP_CMD_READ_UID, 0, 0, 0, 0}; + uint32_t iap_resp[5]; + IAP iap_entry = (IAP)IAP_LOCATION; + irq_disable(); + iap_entry(iap_cmd_uid, iap_resp); + irq_enable(); + + usb_fill_serial(&cdc_chipid.desc, ARRAY_SIZE(cdc_chipid.data) + , &iap_resp[1]); +} +DECL_INIT(chipid_init); diff --git a/src/lpc176x/gpio.c b/src/lpc176x/gpio.c new file mode 100644 index 0000000..0b6d034 --- /dev/null +++ b/src/lpc176x/gpio.c @@ -0,0 +1,144 @@ +// GPIO functions on lpc176x +// +// Copyright (C) 2018 Kevin O'Connor +// +// This file may be distributed under the terms of the GNU GPLv3 license. + +#include // ffs +#include "board/irq.h" // irq_save +#include "command.h" // shutdown +#include "gpio.h" // gpio_out_setup +#include "internal.h" // gpio_peripheral +#include "sched.h" // sched_shutdown + + +/**************************************************************** + * Pin mappings + ****************************************************************/ + +DECL_ENUMERATION_RANGE("pin", "P0.0", GPIO(0, 0), 32); +DECL_ENUMERATION_RANGE("pin", "P1.0", GPIO(1, 0), 32); +DECL_ENUMERATION_RANGE("pin", "P2.0", GPIO(2, 0), 32); +DECL_ENUMERATION_RANGE("pin", "P3.0", GPIO(3, 0), 32); +DECL_ENUMERATION_RANGE("pin", "P4.0", GPIO(4, 0), 32); + +static LPC_GPIO_TypeDef * const digital_regs[] = { + LPC_GPIO0, LPC_GPIO1, LPC_GPIO2, LPC_GPIO3, LPC_GPIO4 +}; + +// Set the mode and extended function of a pin +void +gpio_peripheral(uint32_t gpio, int func, int pull_up) +{ + uint32_t bank_pos = GPIO2PORT(gpio) * 2, pin_pos = (gpio % 32) * 2; + if (pin_pos >= 32) { + pin_pos -= 32; + bank_pos++; + } + uint32_t sel_bits = (func & 0x03) << pin_pos, mask = ~(0x03 << pin_pos); + uint32_t mode = (pull_up ? (pull_up > 0 ? 0x00 : 0x03) : 0x02) << pin_pos; + volatile uint32_t *pinsel = &LPC_PINCON->PINSEL0; + volatile uint32_t *pinmode = &LPC_PINCON->PINMODE0; + irqstatus_t flag = irq_save(); + pinsel[bank_pos] = (pinsel[bank_pos] & mask) | sel_bits; + pinmode[bank_pos] = (pinmode[bank_pos] & mask) | mode; + irq_restore(flag); +} + +// Convert a register and bit location back to an integer pin identifier +static int +regs_to_pin(LPC_GPIO_TypeDef *regs, uint32_t bit) +{ + int i; + for (i=0; i= ARRAY_SIZE(digital_regs)) + goto fail; + LPC_GPIO_TypeDef *regs = digital_regs[GPIO2PORT(pin)]; + struct gpio_out g = { .regs=regs, .bit=GPIO2BIT(pin) }; + gpio_out_reset(g, val); + return g; +fail: + shutdown("Not an output pin"); +} + +void +gpio_out_reset(struct gpio_out g, uint8_t val) +{ + LPC_GPIO_TypeDef *regs = g.regs; + int pin = regs_to_pin(regs, g.bit); + irqstatus_t flag = irq_save(); + regs->FIOPIN = (regs->FIOSET & ~g.bit) | (val ? g.bit : 0); + regs->FIODIR |= g.bit; + gpio_peripheral(pin, 0, 0); + irq_restore(flag); +} + +void +gpio_out_toggle_noirq(struct gpio_out g) +{ + LPC_GPIO_TypeDef *regs = g.regs; + regs->FIOPIN = regs->FIOSET ^ g.bit; +} + +void +gpio_out_toggle(struct gpio_out g) +{ + irqstatus_t flag = irq_save(); + gpio_out_toggle_noirq(g); + irq_restore(flag); +} + +void +gpio_out_write(struct gpio_out g, uint8_t val) +{ + LPC_GPIO_TypeDef *regs = g.regs; + if (val) + regs->FIOSET = g.bit; + else + regs->FIOCLR = g.bit; +} + + +struct gpio_in +gpio_in_setup(uint8_t pin, int8_t pull_up) +{ + if (GPIO2PORT(pin) >= ARRAY_SIZE(digital_regs)) + goto fail; + LPC_GPIO_TypeDef *regs = digital_regs[GPIO2PORT(pin)]; + struct gpio_in g = { .regs=regs, .bit=GPIO2BIT(pin) }; + gpio_in_reset(g, pull_up); + return g; +fail: + shutdown("Not an input pin"); +} + +void +gpio_in_reset(struct gpio_in g, int8_t pull_up) +{ + LPC_GPIO_TypeDef *regs = g.regs; + int pin = regs_to_pin(regs, g.bit); + irqstatus_t flag = irq_save(); + gpio_peripheral(pin, 0, pull_up); + regs->FIODIR &= ~g.bit; + irq_restore(flag); +} + +uint8_t +gpio_in_read(struct gpio_in g) +{ + LPC_GPIO_TypeDef *regs = g.regs; + return !!(regs->FIOPIN & g.bit); +} diff --git a/src/lpc176x/gpio.h b/src/lpc176x/gpio.h new file mode 100644 index 0000000..b0e5e64 --- /dev/null +++ b/src/lpc176x/gpio.h @@ -0,0 +1,24 @@ +#ifndef __LPC176X_GPIO_H +#define __LPC176X_GPIO_H + +#include + +struct gpio_out { + void *regs; + uint32_t bit; +}; +struct gpio_out gpio_out_setup(uint8_t pin, uint8_t val); +void gpio_out_reset(struct gpio_out g, uint8_t val); +void gpio_out_toggle_noirq(struct gpio_out g); +void gpio_out_toggle(struct gpio_out g); +void gpio_out_write(struct gpio_out g, uint8_t val); + +struct gpio_in { + void *regs; + uint32_t bit; +}; +struct gpio_in gpio_in_setup(uint8_t pin, int8_t pull_up); +void gpio_in_reset(struct gpio_in g, int8_t pull_up); +uint8_t gpio_in_read(struct gpio_in g); + +#endif // gpio.h diff --git a/src/lpc176x/internal.h b/src/lpc176x/internal.h new file mode 100644 index 0000000..3adb7e1 --- /dev/null +++ b/src/lpc176x/internal.h @@ -0,0 +1,27 @@ +#ifndef __LPC176X_INTERNAL_H +#define __LPC176X_INTERNAL_H +// Local definitions for lpc176x code + +#include "LPC17xx.h" + +#define GPIO(PORT, NUM) ((PORT) * 32 + (NUM)) +#define GPIO2PORT(PIN) ((PIN) / 32) +#define GPIO2BIT(PIN) (1<<((PIN) % 32)) + +#define PCLK_TIMER0 1 +#define PCLK_UART0 3 +#define PCLK_PWM1 6 +#define PCLK_I2C0 7 +#define PCLK_SSP1 10 +#define PCLK_ADC 12 +#define PCLK_I2C1 19 +#define PCLK_SSP0 21 +#define PCLK_UART3 25 +#define PCLK_I2C2 26 +#define PCLK_USB 31 +int is_enabled_pclock(uint32_t pclk); +void enable_pclock(uint32_t pclk); +uint32_t get_pclock_frequency(uint32_t pclk); +void gpio_peripheral(uint32_t gpio, int func, int pullup); + +#endif // internal.h diff --git a/src/lpc176x/main.c b/src/lpc176x/main.c new file mode 100644 index 0000000..f0fc6cd --- /dev/null +++ b/src/lpc176x/main.c @@ -0,0 +1,67 @@ +// Main starting point for LPC176x boards. +// +// Copyright (C) 2018-2021 Kevin O'Connor +// +// This file may be distributed under the terms of the GNU GPLv3 license. + +#include "autoconf.h" // CONFIG_CLOCK_FREQ +#include "board/armcm_boot.h" // armcm_main +#include "internal.h" // enable_pclock +#include "sched.h" // sched_main + + +/**************************************************************** + * watchdog handler + ****************************************************************/ + +void +watchdog_reset(void) +{ + LPC_WDT->WDFEED = 0xaa; + LPC_WDT->WDFEED = 0x55; +} +DECL_TASK(watchdog_reset); + +void +watchdog_init(void) +{ + LPC_WDT->WDTC = 4000000 / 2; // 500ms timeout + LPC_WDT->WDCLKSEL = 1<<31; // Lock to internal RC + LPC_WDT->WDMOD = 0x03; // select reset and enable + watchdog_reset(); +} +DECL_INIT(watchdog_init); + + +/**************************************************************** + * misc functions + ****************************************************************/ + +// Check if a peripheral clock has been enabled +int +is_enabled_pclock(uint32_t pclk) +{ + return !!(LPC_SC->PCONP & (1<PCONP |= 1< +// +// This file may be distributed under the terms of the GNU GPLv3 license. + +#include "board/armcm_boot.h" // armcm_enable_irq +#include "autoconf.h" // CONFIG_SERIAL_BAUD +#include "board/irq.h" // irq_save +#include "board/serial_irq.h" // serial_rx_data +#include "command.h" // DECL_CONSTANT_STR +#include "internal.h" // gpio_peripheral +#include "sched.h" // DECL_INIT + +#if CONFIG_LPC_SERIAL_UART0_P03_P02 + DECL_CONSTANT_STR("RESERVE_PINS_serial", "P0.3,P0.2"); + #define GPIO_Rx GPIO(0, 3) + #define GPIO_Tx GPIO(0, 2) + #define GPIO_FUNCTION_UARTx 1 + #define LPC_UARTx LPC_UART0 + #define UARTx_IRQn UART0_IRQn + #define PCLK_UARTx PCLK_UART0 +#elif CONFIG_LPC_SERIAL_UART3_P429_P428 + DECL_CONSTANT_STR("RESERVE_PINS_serial", "P4.29,P4.28"); + #define GPIO_Rx GPIO(4, 29) + #define GPIO_Tx GPIO(4, 28) + #define GPIO_FUNCTION_UARTx 3 + #define LPC_UARTx LPC_UART3 + #define UARTx_IRQn UART3_IRQn + #define PCLK_UARTx PCLK_UART3 +#endif + +// Write tx bytes to the serial port +static void +kick_tx(void) +{ + for (;;) { + if (!(LPC_UARTx->LSR & (1<<5))) { + // Output fifo full - enable tx irq + LPC_UARTx->IER = 0x03; + break; + } + uint8_t data; + int ret = serial_get_tx_byte(&data); + if (ret) { + // No more data to send - disable tx irq + LPC_UARTx->IER = 0x01; + break; + } + LPC_UARTx->THR = data; + } +} + +void +UARTx_IRQHandler(void) +{ + uint32_t iir = LPC_UARTx->IIR, status = iir & 0x0f; + if (status == 0x04) + serial_rx_byte(LPC_UARTx->RBR); + else if (status == 0x02) + kick_tx(); +} + +void +serial_enable_tx_irq(void) +{ + if (LPC_UARTx->LSR & (1<<5)) { + irqstatus_t flag = irq_save(); + kick_tx(); + irq_restore(flag); + } +} + +void +serial_init(void) +{ + // Setup baud + enable_pclock(PCLK_UARTx); + LPC_UARTx->LCR = (1<<7); // set DLAB bit + uint32_t pclk = get_pclock_frequency(PCLK_UARTx); + uint32_t div = pclk / (CONFIG_SERIAL_BAUD * 16); + LPC_UARTx->DLL = div & 0xff; + LPC_UARTx->DLM = (div >> 8) & 0xff; + LPC_UARTx->FDR = 0x10; + LPC_UARTx->LCR = 3; // 8N1 ; clear DLAB bit + + // Enable fifo + LPC_UARTx->FCR = 0x01; + + // Setup pins + gpio_peripheral(GPIO_Rx, GPIO_FUNCTION_UARTx, 0); + gpio_peripheral(GPIO_Tx, GPIO_FUNCTION_UARTx, 0); + + // Enable receive irq + armcm_enable_irq(UARTx_IRQHandler, UARTx_IRQn, 0); + LPC_UARTx->IER = 0x01; +} +DECL_INIT(serial_init); diff --git a/src/lpc176x/usb_cdc_ep.h b/src/lpc176x/usb_cdc_ep.h new file mode 100644 index 0000000..d657f3c --- /dev/null +++ b/src/lpc176x/usb_cdc_ep.h @@ -0,0 +1,10 @@ +#ifndef __LPC176X_USB_CDC_EP_H +#define __LPC176X_USB_CDC_EP_H + +enum { + USB_CDC_EP_ACM = 1, + USB_CDC_EP_BULK_OUT = 2, + USB_CDC_EP_BULK_IN = 5, +}; + +#endif // usb_cdc_ep.h diff --git a/src/lpc176x/usbserial.c b/src/lpc176x/usbserial.c new file mode 100644 index 0000000..777f77e --- /dev/null +++ b/src/lpc176x/usbserial.c @@ -0,0 +1,330 @@ +// Hardware interface to USB on lpc176x +// +// Copyright (C) 2018 Kevin O'Connor +// +// This file may be distributed under the terms of the GNU GPLv3 license. + +#include // memcpy +#include "autoconf.h" // CONFIG_SMOOTHIEWARE_BOOTLOADER +#include "board/armcm_boot.h" // armcm_enable_irq +#include "board/irq.h" // irq_disable +#include "board/misc.h" // timer_read_time +#include "generic/usb_cdc.h" // usb_notify_ep0 +#include "byteorder.h" // cpu_to_le32 +#include "command.h" // DECL_CONSTANT_STR +#include "internal.h" // gpio_peripheral +#include "sched.h" // DECL_INIT +#include "usb_cdc_ep.h" // USB_CDC_EP_BULK_IN + +// Internal endpoint addresses +#define EP0OUT 0x00 +#define EP0IN 0x01 +#define EP1IN 0x03 +#define EP2OUT 0x04 +#define EP5IN 0x0b + +// USB device interupt status flags +#define EP_SLOW (1<<2) +#define DEV_STAT (1<<3) +#define CCEMPTY (1<<4) +#define CDFULL (1<<5) +#define EP_RLZED (1<<8) + +#define RD_EN (1<<0) +#define WR_EN (1<<1) + +static void +usb_irq_disable(void) +{ + NVIC_DisableIRQ(USB_IRQn); +} + +static void +usb_irq_enable(void) +{ + NVIC_EnableIRQ(USB_IRQn); +} + +static void +usb_wait(uint32_t flag) +{ + while (!(LPC_USB->USBDevIntSt & flag)) + ; + LPC_USB->USBDevIntClr = flag; +} + + +/**************************************************************** + * Serial Interface Engine (SIE) functions + ****************************************************************/ + +#define SIE_CMD_SELECT 0x00 +#define SIE_CMD_SET_ENDPOINT_STATUS 0x40 +#define SIE_CMD_SET_ADDRESS 0xD0 +#define SIE_CMD_CONFIGURE 0xD8 +#define SIE_CMD_SET_DEVICE_STATUS 0xFE +#define SIE_CMD_CLEAR_BUFFER 0xF2 +#define SIE_CMD_VALIDATE_BUFFER 0xFA + +static void +sie_cmd(uint32_t cmd) +{ + LPC_USB->USBDevIntClr = CDFULL | CCEMPTY; + LPC_USB->USBCmdCode = 0x00000500 | (cmd << 16); + usb_wait(CCEMPTY); +} + +static void +sie_cmd_write(uint32_t cmd, uint32_t data) +{ + sie_cmd(cmd); + LPC_USB->USBCmdCode = 0x00000100 | (data << 16); + usb_wait(CCEMPTY); +} + +static uint32_t +sie_cmd_read(uint32_t cmd) +{ + sie_cmd(cmd); + LPC_USB->USBCmdCode = 0x00000200 | (cmd << 16); + usb_wait(CDFULL); + return LPC_USB->USBCmdData; +} + +static uint32_t +sie_select_and_clear(uint32_t idx) +{ + LPC_USB->USBEpIntClr = 1<USBCmdData; +} + + +/**************************************************************** + * Interface + ****************************************************************/ + +static int_fast8_t +usb_write_packet(uint32_t ep, const void *data, uint_fast8_t len) +{ + usb_irq_disable(); + uint32_t sts = sie_cmd_read(SIE_CMD_SELECT | ep); + if (sts & 0x01) { + // Output buffers full + usb_irq_enable(); + return -1; + } + + LPC_USB->USBCtrl = WR_EN | ((ep/2) << 2); + LPC_USB->USBTxPLen = len; + if (!len) + LPC_USB->USBTxData = 0; + int i; + for (i = 0; iUSBTxData = cpu_to_le32(d); + } + sie_cmd(SIE_CMD_VALIDATE_BUFFER); + usb_irq_enable(); + + return len; +} + +static int_fast8_t +usb_read_packet(uint32_t ep, void *data, uint_fast8_t max_len) +{ + usb_irq_disable(); + uint32_t sts = sie_cmd_read(SIE_CMD_SELECT | ep); + if (!(sts & 0x01)) { + // No data available + usb_irq_enable(); + return -1; + } + + // Determine packet size + LPC_USB->USBCtrl = RD_EN | ((ep/2) << 2); + uint32_t plen = LPC_USB->USBRxPLen; + while (!(plen & (1<<11))) + plen = LPC_USB->USBRxPLen; + plen &= 0x3FF; + if (plen > max_len) + // XXX - return error code? must keep reading? + plen = max_len; + // Copy data + uint32_t xfer = plen; + for (;;) { + uint32_t d = le32_to_cpu(LPC_USB->USBRxData); + if (xfer <= sizeof(d)) { + memcpy(data, &d, xfer); + break; + } + memcpy(data, &d, sizeof(d)); + data += sizeof(d); + xfer -= sizeof(d); + } + // Clear space for next packet + sts = sie_cmd_read(SIE_CMD_CLEAR_BUFFER); + usb_irq_enable(); + if (sts & 0x01) + // Packet overwritten + return -1; + + return plen; +} + +int_fast8_t +usb_read_bulk_out(void *data, uint_fast8_t max_len) +{ + return usb_read_packet(EP2OUT, data, max_len); +} + +int_fast8_t +usb_send_bulk_in(void *data, uint_fast8_t len) +{ + return usb_write_packet(EP5IN, data, len); +} + +int_fast8_t +usb_read_ep0(void *data, uint_fast8_t max_len) +{ + return usb_read_packet(EP0OUT, data, max_len); +} + +int_fast8_t +usb_read_ep0_setup(void *data, uint_fast8_t max_len) +{ + return usb_read_ep0(data, max_len); +} + +int_fast8_t +usb_send_ep0(const void *data, uint_fast8_t len) +{ + return usb_write_packet(EP0IN, data, len); +} + +void +usb_stall_ep0(void) +{ + usb_irq_disable(); + sie_cmd_write(SIE_CMD_SET_ENDPOINT_STATUS | 0, (1<<7)); + usb_irq_enable(); +} + +void +usb_set_address(uint_fast8_t addr) +{ + usb_irq_disable(); + sie_cmd_write(SIE_CMD_SET_ADDRESS, addr | (1<<7)); + usb_irq_enable(); + usb_send_ep0(NULL, 0); +} + +static void +realize_endpoint(uint32_t idx, uint32_t packet_size) +{ + LPC_USB->USBDevIntClr = EP_RLZED; + LPC_USB->USBReEp |= 1<USBEpInd = idx; + LPC_USB->USBMaxPSize = packet_size; + usb_wait(EP_RLZED); + LPC_USB->USBEpIntEn |= 1<WDMOD = 0x07; + NVIC_SystemReset(); +} + + +/**************************************************************** + * Setup and interrupts + ****************************************************************/ + +void +USB_IRQHandler(void) +{ + uint32_t udis = LPC_USB->USBDevIntSt; + if (udis & DEV_STAT) { + LPC_USB->USBDevIntClr = DEV_STAT; + // XXX - should handle reset and other states + } + if (udis & EP_SLOW) { + uint32_t ueis = LPC_USB->USBEpIntSt; + if (ueis & (1<USBDevIntClr = EP_SLOW; + } +} + +DECL_CONSTANT_STR("RESERVE_PINS_USB", "P0.30,P0.29,P2.9"); + +void +usbserial_init(void) +{ + usb_irq_disable(); + // enable power + enable_pclock(PCLK_USB); + // enable clock + LPC_USB->USBClkCtrl = 0x12; + while (LPC_USB->USBClkSt != 0x12) + ; + // configure USBD-, USBD+, and USB Connect pins + gpio_peripheral(GPIO(0, 30), 1, 0); + gpio_peripheral(GPIO(0, 29), 1, 0); + gpio_peripheral(GPIO(2, 9), 1, 0); + // enforce a minimum time bus is disconnected before connecting + udelay(5000); + // setup endpoints + realize_endpoint(EP0OUT, USB_CDC_EP0_SIZE); + realize_endpoint(EP0IN, USB_CDC_EP0_SIZE); + sie_cmd_write(SIE_CMD_SET_DEVICE_STATUS, 1); + // enable irqs + LPC_USB->USBDevIntEn = DEV_STAT | EP_SLOW; + armcm_enable_irq(USB_IRQHandler, USB_IRQn, 1); +} +DECL_INIT(usbserial_init); + +void +usbserial_shutdown(void) +{ + usb_irq_enable(); +} +DECL_SHUTDOWN(usbserial_shutdown);