From f1ecd66283ce0739a501c50efe0301a71aa79333 Mon Sep 17 00:00:00 2001 From: Jason Kotzin Date: Tue, 10 Jul 2018 15:40:36 -0700 Subject: [PATCH] =?UTF-8?q?Initial=20support=20for=20samd=20hardware=20and?= =?UTF-8?q?=20jeff=20=E2=80=98probe=E2=80=99?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- src/platforms/common/cdcacm.c | 2 +- src/platforms/jeff/Makefile.inc | 35 +++++++ src/platforms/jeff/platform.c | 172 ++++++++++++++++++++++++++++++++ src/platforms/jeff/platform.h | 161 ++++++++++++++++++++++++++++++ src/platforms/samd/gdb_if.c | 103 +++++++++++++++++++ src/platforms/samd/jtagtap.c | 43 ++++++++ src/platforms/samd/samd.ld | 28 ++++++ src/platforms/samd/traceswo.c | 57 +++++++++++ src/platforms/samd/usbuart.c | 58 +++++++++++ 9 files changed, 658 insertions(+), 1 deletion(-) create mode 100644 src/platforms/jeff/Makefile.inc create mode 100644 src/platforms/jeff/platform.c create mode 100644 src/platforms/jeff/platform.h create mode 100644 src/platforms/samd/gdb_if.c create mode 100644 src/platforms/samd/jtagtap.c create mode 100644 src/platforms/samd/samd.ld create mode 100644 src/platforms/samd/traceswo.c create mode 100644 src/platforms/samd/usbuart.c diff --git a/src/platforms/common/cdcacm.c b/src/platforms/common/cdcacm.c index a9e26724..0636a40b 100644 --- a/src/platforms/common/cdcacm.c +++ b/src/platforms/common/cdcacm.c @@ -502,7 +502,7 @@ static void cdcacm_set_config(usbd_device *dev, uint16_t wValue) configured = wValue; /* GDB interface */ -#if defined(STM32F4) || defined(LM4F) +#if defined(STM32F4) || defined(LM4F) || defined(SAMD) usbd_ep_setup(dev, 0x01, USB_ENDPOINT_ATTR_BULK, CDCACM_PACKET_SIZE, gdb_usb_out_cb); #else diff --git a/src/platforms/jeff/Makefile.inc b/src/platforms/jeff/Makefile.inc new file mode 100644 index 00000000..c0506f70 --- /dev/null +++ b/src/platforms/jeff/Makefile.inc @@ -0,0 +1,35 @@ +CROSS_COMPILE ?= arm-none-eabi- +CC = $(CROSS_COMPILE)gcc +OBJCOPY = $(CROSS_COMPILE)objcopy + + +ifeq ($(DEBUG_ME), 1) +CFLAGS += -DDEBUG_ME +endif + +CFLAGS += -mthumb -mcpu=cortex-m0plus \ + -DSAMD -DSAMD21E18 -DBLACKMAGIC -I../libopencm3/include \ + -Iplatforms/samd -msoft-float -ffunction-sections -fdata-sections -MD + +LINKER_SCRIPT="platforms/samd/samd.ld" +LDFLAGS = -mthumb -mcpu=cortex-m0plus -msoft-float -nostartfiles -lc $(CPU_FLAGS) -nodefaultlibs -T$(LINKER_SCRIPT) -Wl,--gc-sections \ + -L../libopencm3/lib -lopencm3_samd -lnosys -lm -lgcc + +ifeq ($(ENABLE_DEBUG), 1) +LDFLAGS += --specs=rdimon.specs +else +LDFLAGS += --specs=nosys.specs +endif + +VPATH += platforms/samd + +SRC += cdcacm.c \ + timing.c \ + traceswo.o \ + usbuart.c \ + +all: blackmagic.bin + +host_clean: + -$(Q)$(RM) -f blackmagic.bin blackmagic_dfu blackmagic_dfu.bin blackmagic_dfu.hex + diff --git a/src/platforms/jeff/platform.c b/src/platforms/jeff/platform.c new file mode 100644 index 00000000..986c22a4 --- /dev/null +++ b/src/platforms/jeff/platform.c @@ -0,0 +1,172 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2018 Flirc Inc. + * Written by Jason Kotzin + * + * This library is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this library. If not, see . + */ + +#include "general.h" +#include "gdb_if.h" +#include "cdcacm.h" +#include "usbuart.h" + +#include +#include +#include +#include + +#include +#include + +static struct gclk_hw clock = { + .gclk0 = SRC_DFLL48M, + .gclk1 = SRC_DFLL48M, + .gclk2 = SRC_DFLL48M, + .gclk3 = SRC_DFLL48M, + .gclk4 = SRC_DFLL48M, + .gclk5 = SRC_DFLL48M, + .gclk6 = SRC_DFLL48M, + .gclk7 = SRC_DFLL48M, +}; + +extern void trace_tick(void); + +uint8_t running_status; +static volatile uint32_t time_ms; + +void sys_tick_handler(void) +{ + if(running_status) + gpio_toggle(LED_PORT, LED_IDLE_RUN); + + time_ms += 10; +} + +uint32_t platform_time_ms(void) +{ + return time_ms; +} + +static void usb_setup(void) +{ + /* Enable USB */ + INSERTBF(PM_APBBMASK_USB, 1, PM->apbbmask); + + /* enable clocking to usb */ + set_periph_clk(GCLK0, GCLK_ID_USB); + periph_clk_en(GCLK_ID_USB, 1); + + gpio_config_special(PORTA, GPIO24, SOC_GPIO_PERIPH_G); + gpio_config_special(PORTA, GPIO25, SOC_GPIO_PERIPH_G); + +} + +static uint32_t timing_init(void) +{ + uint32_t cal = 0; + + systick_set_clocksource(STK_CSR_CLKSOURCE_AHB); + systick_set_reload(480000); /* Interrupt us at 10 Hz */ + systick_interrupt_enable(); + + systick_counter_enable(); + return cal; +} + +void platform_init(void) +{ + gclk_init(&clock); + + usb_setup(); + + gpio_config_output(LED_PORT, LED_IDLE_RUN, 0); + gpio_config_output(TMS_PORT, TMS_PIN, 0); + gpio_config_output(TCK_PORT, TCK_PIN, 0); + gpio_config_output(TDI_PORT, TDI_PIN, 0); + + /* enable both input and output with pullup disabled by default */ + PORT_DIRSET(SWDIO_PORT) = SWDIO_PIN; + PORT_PINCFG(SWDIO_PORT, SWDIO_PIN_NUM) |= GPIO_PINCFG_INEN | GPIO_PINCFG_PULLEN; + gpio_clear(SWDIO_PORT, SWDIO_PIN); + + /* configure swclk_pin as output */ + gpio_config_output(SWCLK_PORT, SWCLK_PIN, 0); + gpio_clear(SWCLK_PORT, SWCLK_PIN); + + gpio_config_input(TDO_PORT, TDO_PIN, 0); + gpio_config_output(SRST_PORT, SRST_PIN, GPIO_OUT_FLAG_DEFAULT_HIGH); + gpio_set(SRST_PORT, SRST_PIN); + + timing_init(); + + //nvic_enable_irq(NVIC_UART0_IRQ); + //usbuart_init(); + + cdcacm_init(); +} + +void platform_srst_set_val(bool assert) +{ + volatile int i; + if (assert) { + gpio_clear(SRST_PORT, SRST_PIN); + for(i = 0; i < 10000; i++) asm("nop"); + } else { + gpio_set(SRST_PORT, SRST_PIN); + } +} + +bool platform_srst_get_val(void) +{ + return gpio_get(SRST_PORT, SRST_PIN) == 0; +} + +void platform_delay(uint32_t ms) +{ + platform_timeout timeout; + platform_timeout_set(&timeout, ms); + while (!platform_timeout_is_expired(&timeout)); +} + +const char *platform_target_voltage(void) +{ + return "not supported"; +} + +char *serialno_read(char *s) +{ + int i; + volatile uint32_t unique_id = *(volatile uint32_t *)0x0080A00C + + *(volatile uint32_t *)0x0080A040 + + *(volatile uint32_t *)0x0080A044 + + *(volatile uint32_t *)0x0080A048; + + /* Fetch serial number from chip's unique ID */ + for(i = 0; i < 8; i++) { + s[7-i] = ((unique_id >> (4*i)) & 0xF) + '0'; + } + + for(i = 0; i < 8; i++) + if(s[i] > '9') + s[i] += 'A' - '9' - 1; + s[8] = 0; + + return s; +} + +void platform_request_boot(void) +{ +} diff --git a/src/platforms/jeff/platform.h b/src/platforms/jeff/platform.h new file mode 100644 index 00000000..8a8a7016 --- /dev/null +++ b/src/platforms/jeff/platform.h @@ -0,0 +1,161 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2018 Flirc Inc. + * Written by Jason Kotzin + * + * This library is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this library. If not, see . + */ + +#ifndef __PLATFORM_H +#define __PLATFORM_H + +#include +#include + +#include "timing.h" +#include "version.h" + +//#define PLATFORM_HAS_DEBUG +//#define USBUART_DEBUG + +#define BOARD_IDENT "Black Magic Probe (Launchpad ICDI), (Firmware " FIRMWARE_VERSION ")" +#define BOARD_IDENT_DFU "Black Magic (Upgrade) for Launchpad, (Firmware " FIRMWARE_VERSION ")" +#define DFU_IDENT "Black Magic Firmware Upgrade (Launchpad)" +#define DFU_IFACE_STRING "lolwut" + +extern uint8_t running_status; + +#ifdef DEBUG_ME + +#define LED_PORT PORTA +#define LED_IDLE_RUN GPIO11 +#define LED_ERROR GPIO10 + +#define TMS_PORT PORTA +#define TMS_PIN GPIO7 + +#define TCK_PORT PORTA +#define TCK_PIN GPIO8 + +#define TDI_PORT PORTA +#define TDI_PIN GPIO5 + +#define TDO_PORT PORTA +#define TDO_PIN GPIO4 + +#define SWO_PORT PORTA +#define SWO_PIN GPIO6 + +#define SWDIO_PORT PORTA +#define SWDIO_PIN TMS_PIN +#define SWDIO_PIN_NUM 7 + +#define SWCLK_PORT PORTA +#define SWCLK_PIN TCK_PIN + +#define SRST_PORT PORTA +#define SRST_PIN GPIO6 + +#else + +#define LED_PORT PORTA +#define LED_IDLE_RUN GPIO11 +#define LED_ERROR GPIO10 + +#define TMS_PORT PORTA +#define TMS_PIN GPIO31 + +#define TCK_PORT PORTA +#define TCK_PIN GPIO30 + +#define TDI_PORT PORTA +#define TDI_PIN GPIO5 + +#define TDO_PORT PORTA +#define TDO_PIN GPIO4 + +#define SWO_PORT PORTA +#define SWO_PIN GPIO6 + +#define SWDIO_PORT PORTA +#define SWDIO_PIN TMS_PIN +#define SWDIO_PIN_NUM 31 + +#define SWCLK_PORT PORTA +#define SWCLK_PIN TCK_PIN + +#define SRST_PORT PORTA +#define SRST_PIN GPIO26 +#endif + +#define TMS_SET_MODE() { \ + gpio_config_output(TMS_PORT, TMS_PIN, 0); \ +} + +#define SWDIO_MODE_FLOAT() do { \ + PORT_DIRCLR(SWDIO_PORT) = SWDIO_PIN; \ + gpio_set(SWDIO_PORT, SWDIO_PIN); \ +} while(0) +#define SWDIO_MODE_DRIVE() do { \ + PORT_DIRSET(SWDIO_PORT) = SWDIO_PIN; \ +} while(0) + +/* extern usbd_driver samd21_usb_driver; */ +#define USB_DRIVER samd21_usb_driver +#define USB_IRQ NVIC_USB_IRQ +#define USB_ISR usb_isr + +#define IRQ_PRI_USB (2 << 4) + +#define INLINE_GPIO + +#define gpio_set_val(port, pin, val) do { \ + if(val) \ + gpio_set((port), (pin)); \ + else \ + gpio_clear((port), (pin)); \ +} while(0) + +#ifdef INLINE_GPIO +static inline void _gpio_set(uint32_t gpioport, uint16_t gpios) +{ + PORT_OUTSET(gpioport) = gpios; +} +#define gpio_set _gpio_set + +static inline void _gpio_clear(uint32_t gpioport, uint16_t gpios) +{ + PORT_OUTCLR(gpioport) = gpios; +} +#define gpio_clear _gpio_clear + +static inline uint16_t _gpio_get(uint32_t gpioport, uint16_t gpios) +{ + return (uint32_t)PORT_IN(gpioport) & gpios; +} +#define gpio_get _gpio_get +#endif + +#define DEBUG(...) + +#define SET_RUN_STATE(state) {running_status = (state);} +#define SET_IDLE_STATE(state) {gpio_set_val(LED_PORT, LED_IDLE_RUN, state);} +#define SET_ERROR_STATE(state) {gpio_set_val(LED_PORT, LED_ERROR, state);} + +static inline int platform_hwversion(void) +{ + return 0; +} +#endif diff --git a/src/platforms/samd/gdb_if.c b/src/platforms/samd/gdb_if.c new file mode 100644 index 00000000..1f3c1f81 --- /dev/null +++ b/src/platforms/samd/gdb_if.c @@ -0,0 +1,103 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2011 Black Sphere Technologies Ltd. + * Written by Gareth McMullin + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +/* This file implements a transparent channel over which the GDB Remote + * Serial Debugging protocol is implemented. This implementation for STM32 + * uses the USB CDC-ACM device bulk endpoints to implement the channel. + */ + +#include "general.h" +#include "gdb_if.h" +#include "cdcacm.h" + +#include + +static volatile uint32_t head_out, tail_out; +static volatile uint32_t count_in; +static volatile uint8_t buffer_out[16*CDCACM_PACKET_SIZE]; +static volatile uint8_t buffer_in[CDCACM_PACKET_SIZE]; + +void gdb_if_putchar(unsigned char c, int flush) +{ + buffer_in[count_in++] = c; + if(flush || (count_in == CDCACM_PACKET_SIZE)) { + /* Refuse to send if USB isn't configured, and + * don't bother if nobody's listening */ + if((cdcacm_get_config() != 1) || !cdcacm_get_dtr()) { + count_in = 0; + return; + } + while(usbd_ep_write_packet(usbdev, CDCACM_GDB_ENDPOINT, + (uint8_t *)buffer_in, count_in) <= 0); + count_in = 0; + } +} + +void gdb_usb_out_cb(usbd_device *dev, uint8_t ep) +{ + (void)ep; + static uint8_t buf[CDCACM_PACKET_SIZE]; + + usbd_ep_nak_set(dev, CDCACM_GDB_ENDPOINT, 1); + uint32_t count = usbd_ep_read_packet(dev, CDCACM_GDB_ENDPOINT, + (uint8_t *)buf, CDCACM_PACKET_SIZE); + + + uint32_t idx; + for (idx=0; idx + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +/* Define memory regions. */ +MEMORY +{ + rom (rx) : ORIGIN = 0x00000000, LENGTH = 256K + ram (rwx) : ORIGIN = 0x20000000, LENGTH = 32K +} + +/* Include the common ld script from libopenstm32. */ +INCLUDE libopencm3_samd.ld diff --git a/src/platforms/samd/traceswo.c b/src/platforms/samd/traceswo.c new file mode 100644 index 00000000..2985f900 --- /dev/null +++ b/src/platforms/samd/traceswo.c @@ -0,0 +1,57 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2018 Flirc Inc. + * Written by Jason Kotzin + * + * This library is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this library. If not, see . + */ + +/* This file implements capture of the TRACESWO output. + * + * ARM DDI 0403D - ARMv7M Architecture Reference Manual + * ARM DDI 0337I - Cortex-M3 Technical Reference Manual + * ARM DDI 0314H - CoreSight Components Technical Reference Manual + */ + +#include "general.h" +#include "cdcacm.h" + +void traceswo_init(void) +{ +} + +void traceswo_baud(unsigned int baud) +{ + baud++; +} + +void trace_buf_push(void) +{ +} + +void trace_buf_drain(usbd_device *dev, uint8_t ep) +{ + ep ++; + if (dev == NULL) + return; +} + +void trace_tick(void) +{ +} + +void TRACEUART_ISR(void) +{ +} diff --git a/src/platforms/samd/usbuart.c b/src/platforms/samd/usbuart.c new file mode 100644 index 00000000..ceaef1b7 --- /dev/null +++ b/src/platforms/samd/usbuart.c @@ -0,0 +1,58 @@ +/* + * This file is part of the Black Magic Debug project. + * + * Copyright (C) 2018 Flirc Inc. + * Written by Jason Kotzin + * + * This library is free software: you can redistribute it and/or modify + * it under the terms of the GNU Lesser General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public License + * along with this library. If not, see . + */ + +#include "general.h" +#include "cdcacm.h" + +#include +#include +#include +#include + +void usbuart_init(void) +{ +} + +void usbuart_set_line_coding(struct usb_cdc_line_coding *coding) +{ + (void) coding; +} + +void usbuart_usb_out_cb(usbd_device *dev, uint8_t ep) +{ + (void) dev; + (void) ep; +} + + +void usbuart_usb_in_cb(usbd_device *dev, uint8_t ep) +{ + (void) dev; + (void) ep; +} + +/* + * Read a character from the UART RX and stuff it in a software FIFO. + * Allowed to read from FIFO out pointer, but not write to it. + * Allowed to write to FIFO in pointer. + */ +void USBUART_ISR(void) +{ +}