Add 96Boards Carbon as a probe host

The carbon contains two SoCs, an STM32 (host) and an nRF51 (BLE). The
STM32 implements the probe and allows the board to reprogram its own
radio firmware!
This commit is contained in:
Daniel Thompson 2017-04-22 22:03:35 +01:00 committed by Rachel Mant
parent 5e3cadec20
commit 738ac96e57
6 changed files with 466 additions and 0 deletions

View File

@ -0,0 +1,28 @@
CROSS_COMPILE ?= arm-none-eabi-
CC = $(CROSS_COMPILE)gcc
OBJCOPY = $(CROSS_COMPILE)objcopy
CFLAGS += -Istm32/include -mcpu=cortex-m4 -mthumb \
-mfloat-abi=hard -mfpu=fpv4-sp-d16 \
-DSTM32F4 -D_96B_CARBON -I../libopencm3/include \
-Iplatforms/stm32
LDFLAGS = -lopencm3_stm32f4 -Wl,--defsym,_stack=0x20006000 \
-Wl,-T,platforms/stm32/96b_carbon.ld -nostartfiles -lc -lnosys \
-Wl,-Map=mapfile -mthumb -mcpu=cortex-m4 -Wl,-gc-sections \
-mfloat-abi=hard -mfpu=fpv4-sp-d16 \
-L../libopencm3/lib
VPATH += platforms/stm32
SRC += cdcacm.c \
traceswo.c \
usbuart.c \
serialno.c \
timing.c \
timing_stm32.c \
all: blackmagic.bin
host_clean:
-$(Q)$(RM) blackmagic.bin

View File

@ -0,0 +1,71 @@
Connections
===========
The pinout for the programmer is concentrated within a single part of
the Low Speed connector. The target control pins at the even pins 2
through 16 with UART on LS-03 and LS-05.
The pinout for the programmer allows a Carbon to program another Carbon
(either the STM32 or the nRF51) with adjacent pins from LS-06 to LS-12.
The order matches that of the SWD pins for easy hook up.
JTAG/SWD
--------
* LS-02 (PB12): TDO/TRACESWO
* LS-04 (PB15): TDI
* LS-06 (PB14): TMS/SWDIO
* LS-08 (PB13): TCK/SWCLK
* LS-10 : GND
* LS-12 : Vcc
* LS-14 (PC3) : TRST (optional test reset)
* LS-16 (PC5) : SRST (system reset)
LEDs
----
* USR1 (green): Debug activity indicator
* USR2 (green): UART activity indicator
* BT (blue) : Error indicator
UART
----
* LS-03 (PA2): UART TX
* LS-05 (PA3): UART RX
How to Build
============
cd blackmagic
make clean
make PROBE_HOST=96b_carbon
Flashing using dfu-util
=======================
Connect to the USB OTG socket on the Carbon and force the device into
system bootloader mode by holding down the BOOT0 switch whilst pressing
and releasing the RST switch. To program the device try:
sudo dfu-util -d [0483:df11] -a 0 -D src/blackmagic.bin -s 0x08000000
Self-programming
================
A Carbon is capable of self-programming its own nRF51 by connecting two
jumper wires from LS-06 to BLE_SWD-4 (DIO) and LS-08 to BLE_SWD-3 (CLK).
+------------------------------------------------------------------+
| +-2--4--6--8-10-12-14-16-18-20-22-24-26-28-30-+ |
| | . . .-+.-+. . . . . . . . . . . | |
| | . . . |. |. . . . . . . . . . . | |
| +-1--3--5-|7-|9-11-13-15-17-19-21-23-25-27-29-+ |
| | | |
| +--+-----------------------------+ |
| | | |
| +--------------------------+ | |
| | | |
| . . . . . |
| . . . . . . . . . |
+------------------------------------------------------------------+

View File

@ -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 <gareth@blacksphere.co.nz>
*
* 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 <http://www.gnu.org/licenses/>.
*/
/* This file implements the platform specific functions for the STM32
* implementation.
*/
#include "general.h"
#include "cdcacm.h"
#include "usbuart.h"
#include "morse.h"
#include <libopencm3/stm32/f4/rcc.h>
#include <libopencm3/cm3/scb.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/stm32/exti.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/stm32/syscfg.h>
#include <libopencm3/usb/usbd.h>
jmp_buf fatal_error_jmpbuf;
void platform_init(void)
{
rcc_clock_setup_hse_3v3(&rcc_hse_16mhz_3v3[RCC_CLOCK_3V3_48MHZ]);
/* Enable peripherals */
rcc_periph_clock_enable(RCC_OTGFS);
rcc_periph_clock_enable(RCC_GPIOA);
rcc_periph_clock_enable(RCC_GPIOB);
rcc_periph_clock_enable(RCC_GPIOC);
rcc_periph_clock_enable(RCC_GPIOD);
rcc_periph_clock_enable(RCC_CRC);
/* Set up USB Pins and alternate function*/
gpio_mode_setup(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO11 | GPIO12);
gpio_set_af(GPIOA, GPIO_AF10, GPIO11 | GPIO12);
gpio_mode_setup(JTAG_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE,
TMS_PIN | TCK_PIN | TDI_PIN);
gpio_set_output_options(JTAG_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ,
TMS_PIN | TCK_PIN | TDI_PIN);
gpio_mode_setup(TDO_PORT, GPIO_MODE_INPUT, GPIO_PUPD_NONE,
TDO_PIN);
gpio_mode_setup(TRST_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, TRST_PIN);
gpio_mode_setup(SRST_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, SRST_PIN);
gpio_mode_setup(LED_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, LED_IDLE_RUN);
gpio_mode_setup(LED_PORT_UART, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, LED_UART);
gpio_mode_setup(LED_PORT_ERROR, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, LED_ERROR);
platform_timing_init();
usbuart_init();
cdcacm_init();
}
void platform_srst_set_val(bool assert)
{
if (assert)
gpio_clear(SRST_PORT, SRST_PIN);
else
gpio_set(SRST_PORT, SRST_PIN);
}
bool platform_srst_get_val(void)
{
return gpio_get(SRST_PORT, SRST_PIN);
}
const char *platform_target_voltage(void)
{
return "ABSENT!";
}
void platform_request_boot(void)
{
/* Disconnect USB cable */
usbd_disconnect(usbdev, 1);
nvic_disable_irq(USB_IRQ);
/* Jump to the built in bootloader by mapping System flash */
rcc_periph_clock_enable(RCC_SYSCFG);
SYSCFG_MEMRM &= ~3;
SYSCFG_MEMRM |= 1;
}

View File

@ -0,0 +1,161 @@
/*
* This file is part of the Black Magic Debug project.
*
* Copyright (C) 2011 Black Sphere Technologies Ltd.
* Written by Gareth McMullin <gareth@blacksphere.co.nz>
*
* 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 <http://www.gnu.org/licenses/>.
*/
/* This file implements the platform specific functions for the STM32
* implementation.
*/
#ifndef __PLATFORM_H
#define __PLATFORM_H
#include "gpio.h"
#include "timing.h"
#include "timing_stm32.h"
#include "version.h"
#include <setjmp.h>
#define PLATFORM_HAS_TRACESWO
#define BOARD_IDENT "Black Magic Probe (Carbon), (Firmware " FIRMWARE_VERSION ")"
#define BOARD_IDENT_DFU "Black Magic (Upgrade) for Carbon, (Firmware " FIRMWARE_VERSION ")"
#define DFU_IDENT "Black Magic Firmware Upgrade (Carbon)"
#define DFU_IFACE_STRING "@Internal Flash /0x08000000/1*016Ka,3*016Kg,1*064Kg,7*128Kg"
/* Important pin mappings for Carbon implementation:
*
* LED0 = PA15 (Green USR2 : Idle))
* LED1 = PD5 (Green USR1 : UART)
* LED2 = PB5 (Blue BT : Error)
*
* TDO = PB12 (LS-02)
* TDI = PB15 (LS-04)
* TMS/SWDIO = PB14 (LS-06) The pinout for the programmer allows a Carbon to
* TCK/SWCLK = PB13 (LS-08) program another Carbon (either the STM32 or the
* GND (LS-10) nRF51) with adjacent pins from LS-06 to LS-12.
* VCC (LS-12) The order matches the SWD pins for easy hook up.
* nTRST = PC3 (LS-14)
* nSRST = PC5 (LS-16)
*/
/* Hardware definitions... */
#define JTAG_PORT GPIOB
#define TDO_PORT JTAG_PORT
#define TDI_PORT JTAG_PORT
#define TMS_PORT JTAG_PORT
#define TCK_PORT JTAG_PORT
#define TDO_PIN GPIO12
#define TDI_PIN GPIO15
#define TMS_PIN GPIO14
#define TCK_PIN GPIO13
#define SWDIO_PORT JTAG_PORT
#define SWCLK_PORT JTAG_PORT
#define SWDIO_PIN TMS_PIN
#define SWCLK_PIN TCK_PIN
#define TRST_PORT GPIOC
#define TRST_PIN GPIO3
#define SRST_PORT GPIOC
#define SRST_PIN GPIO5
#define LED_PORT GPIOA
#define LED_IDLE_RUN GPIO15
#define LED_PORT_UART GPIOD
#define LED_UART GPIO2
#define LED_PORT_ERROR GPIOB
#define LED_ERROR GPIO5
#define TMS_SET_MODE() \
gpio_mode_setup(TMS_PORT, GPIO_MODE_OUTPUT, \
GPIO_PUPD_NONE, TMS_PIN);
#define SWDIO_MODE_FLOAT() \
gpio_mode_setup(SWDIO_PORT, GPIO_MODE_INPUT, \
GPIO_PUPD_NONE, SWDIO_PIN);
#define SWDIO_MODE_DRIVE() \
gpio_mode_setup(SWDIO_PORT, GPIO_MODE_OUTPUT, \
GPIO_PUPD_NONE, SWDIO_PIN);
#define USB_DRIVER otgfs_usb_driver
#define USB_IRQ NVIC_OTG_FS_IRQ
#define USB_ISR otg_fs_isr
/* Interrupt priorities. Low numbers are high priority.
* For now USART preempts USB which may spin while buffer is drained.
* TIM3 is used for traceswo capture and must be highest priority.
*/
#define IRQ_PRI_USB (2 << 4)
#define IRQ_PRI_USBUSART (1 << 4)
#define IRQ_PRI_USBUSART_TIM (3 << 4)
#define IRQ_PRI_TRACE (0 << 4)
#define USBUSART USART2
#define USBUSART_CR1 USART2_CR1
#define USBUSART_IRQ NVIC_USART2_IRQ
#define USBUSART_CLK RCC_USART2
#define USBUSART_TX_PORT GPIOA
#define USBUSART_TX_PIN GPIO2
#define USBUSART_RX_PORT GPIOA
#define USBUSART_RX_PIN GPIO3
#define USBUSART_ISR usart2_isr
#define USBUSART_TIM TIM4
#define USBUSART_TIM_CLK_EN() rcc_periph_clock_enable(RCC_TIM4)
#define USBUSART_TIM_IRQ NVIC_TIM4_IRQ
#define USBUSART_TIM_ISR tim4_isr
#define UART_PIN_SETUP() do { \
gpio_mode_setup(USBUSART_TX_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, \
USBUSART_TX_PIN); \
gpio_mode_setup(USBUSART_RX_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, \
USBUSART_RX_PIN); \
gpio_set_af(USBUSART_TX_PORT, GPIO_AF7, USBUSART_TX_PIN); \
gpio_set_af(USBUSART_RX_PORT, GPIO_AF7, USBUSART_RX_PIN); \
} while(0)
#define TRACE_TIM TIM3
#define TRACE_TIM_CLK_EN() rcc_periph_clock_enable(RCC_TIM3)
#define TRACE_IRQ NVIC_TIM3_IRQ
#define TRACE_ISR tim3_isr
#define DEBUG(...)
#define gpio_set_val(port, pin, val) do { \
if(val) \
gpio_set((port), (pin)); \
else \
gpio_clear((port), (pin)); \
} while(0)
#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_ERROR, LED_ERROR, state);}
static inline int platform_hwversion(void)
{
return 0;
}
/* Use newlib provided integer only stdio functions */
#define sscanf siscanf
#define sprintf siprintf
#define vasprintf vasiprintf
#define snprintf sniprintf
#endif

View File

@ -0,0 +1,74 @@
/*
* This file is part of the Black Magic Debug project.
*
* Copyright (C) 2013 Gareth McMullin <gareth@blacksphere.co.nz>
*
* 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 <http://www.gnu.org/licenses/>.
*/
#include "general.h"
#include "usbdfu.h"
#include <libopencm3/cm3/systick.h>
#include <libopencm3/stm32/rcc.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/cm3/scb.h>
void dfu_detach(void)
{
/* USB device must detach, we just reset... */
scb_reset_system();
}
int main(void)
{
/* Check the force bootloader pin*/
rcc_periph_enable_clock(RCC_GPIOA);
if(!gpio_get(GPIOA, GPIO0))
dfu_jump_app_if_valid();
dfu_protect_enable();
/* Set up clock*/
rcc_clock_setup_hse_3v3(&hse_8mhz_3v3[CLOCK_3V3_168MHZ]);
systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8);
systick_set_reload(2100000);
systick_interrupt_enable();
systick_counter_enable();
/* Handle LEDs */
rcc_periph_enable_clock(RCC_GPIOD);
gpio_clear(GPIOD, GPIO12 | GPIO13 | GPIO14 |GPIO15);
gpio_mode_setup(GPIOD, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE,
GPIO12 | GPIO13 | GPIO14 |GPIO15);
/* Set up USB*/
rcc_periph_enable_clock(RCC_OTGFS);
/* Set up USB Pins and alternate function*/
gpio_mode_setup(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE,
GPIO10 | GPIO11 | GPIO12);
gpio_set_af(GPIOA, GPIO_AF10, GPIO10 | GPIO11 | GPIO12);
dfu_init(&stm32f107_usb_driver);
dfu_main();
}
void sys_tick_handler(void)
{
gpio_toggle(GPIOD, GPIO12); /* Green LED on/off */
}

View File

@ -0,0 +1,29 @@
/*
* This file is part of the libopenstm32 project.
*
* Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
*
* 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 <http://www.gnu.org/licenses/>.
*/
/* Define memory regions. */
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K
}
/* Include the common ld script from libopenstm32. */
INCLUDE libopencm3_stm32f4.ld