Merge pull request #12 from UweBonnes/master
Make adaption to different STM32 boards easier
This commit is contained in:
commit
acda4bd46c
|
@ -1,3 +1,9 @@
|
|||
blackmagic
|
||||
blackmagic.bin
|
||||
blackmagic_dfu
|
||||
blackmagic_dfu.bin
|
||||
blackmagic_dfu.hex
|
||||
mapfile
|
||||
*.o
|
||||
*.d
|
||||
.*.swp
|
||||
|
|
15
HACKING
15
HACKING
|
@ -9,6 +9,11 @@ resides in the 'src' directory.
|
|||
|
||||
Compiling for the native hardware
|
||||
---------------------------------
|
||||
Run
|
||||
git submodule init
|
||||
git submodule update
|
||||
after cloning blackmagic to fill the libopencm3 directory.
|
||||
|
||||
To build the firmware for the standard hardware platform run 'make' in the
|
||||
src directory. You will require a GCC cross compiler for ARM Cortex-M3
|
||||
targets. You will also need to have the libopenstm32 library installed.
|
||||
|
@ -39,6 +44,16 @@ over USB:
|
|||
The device should reset and re-enumerate as a CDC-ACM device implementing
|
||||
the GDB protocol.
|
||||
|
||||
Errors when compiling libopencm3
|
||||
-------------------------------
|
||||
If while compiling libopencm3 you get an error like
|
||||
arm-none-eabi/bin/ld: error: cdcacm.elf uses VFP register arguments, \
|
||||
arm-none-eabi/lib/thumb/v7m/libc.a(lib_a-memcpy-stub.o) does not
|
||||
your toolchain and libopencm3 disagree on the calling convention for floation
|
||||
point functions on the F4. Change in
|
||||
lib/stm32/f4/Makefile and examples/stm32/f4/Makefile.include all apperance of
|
||||
-mfloat-abi=hard to -mfloat-abi=soft
|
||||
This doesn't matter for blackmagic, as it doesn't use floating point.
|
||||
|
||||
Compiling as a Linux application using FT2232 hardware
|
||||
------------------------------------------------------
|
||||
|
|
5
README
5
README
|
@ -38,6 +38,11 @@ instead of JTAG to connect to the target.
|
|||
Once attached, all the standard GDB commands may be used to start and control
|
||||
the execution of the embedded application.
|
||||
|
||||
The peripheral registers are not included in the memory map provided to GDB.
|
||||
I suggest you add the command "set mem inaccessible-by-default off' to
|
||||
your '.gdbinit'. That will allow you to access addresses outside of
|
||||
the memory map. It will treat anything outside of the memory map as
|
||||
RAM.
|
||||
|
||||
Project layout
|
||||
==============
|
||||
|
|
|
@ -21,6 +21,7 @@ from time import sleep
|
|||
import struct
|
||||
from sys import stdout, argv
|
||||
|
||||
import argparse
|
||||
import usb
|
||||
import dfu
|
||||
|
||||
|
@ -60,11 +61,15 @@ def stm32_manifest(dev):
|
|||
|
||||
if __name__ == "__main__":
|
||||
print
|
||||
print "USB Device Firmware Upgrade - Host Utility -- version 1.1"
|
||||
print "USB Device Firmware Upgrade - Host Utility -- version 1.2"
|
||||
print "Copyright (C) 2011 Black Sphere Technologies"
|
||||
print "License GPLv3+: GNU GPL version 3 or later <http://gnu.org/licenses/gpl.html>"
|
||||
print
|
||||
|
||||
parser = argparse.ArgumentParser()
|
||||
parser.add_argument("progfile", help="Binary file to program")
|
||||
parser.add_argument("-s", "--serial_target", help="Match Serial Number")
|
||||
args = parser.parse_args()
|
||||
devs = dfu.finddevs()
|
||||
if not devs:
|
||||
print "No devices found!"
|
||||
|
@ -73,13 +78,22 @@ if __name__ == "__main__":
|
|||
for dev in devs:
|
||||
dfudev = dfu.dfu_device(*dev)
|
||||
man = dfudev.handle.getString(dfudev.dev.iManufacturer, 30)
|
||||
product = dfudev.handle.getString(dfudev.dev.iProduct, 30)
|
||||
if man == "Black Sphere Technologies": break
|
||||
if man == "STMicroelectronics": break
|
||||
product = dfudev.handle.getString(dfudev.dev.iProduct, 64)
|
||||
serial_no = dfudev.handle.getString(dfudev.dev.iSerialNumber, 30)
|
||||
if args.serial_target:
|
||||
if man == "Black Sphere Technologies" and serial_no == args.serial_target: break
|
||||
if man == "STMicroelectronics" and serial_no == args.serial_target: break
|
||||
else:
|
||||
if man == "Black Sphere Technologies": break
|
||||
if man == "STMicroelectronics": break
|
||||
|
||||
print "Device %s: ID %04x:%04x %s - %s" % (dfudev.dev.filename,
|
||||
dfudev.dev.idVendor, dfudev.dev.idProduct, man, product)
|
||||
print "Device %s: ID %04x:%04x %s - %s\n\tSerial %s" % (
|
||||
dfudev.dev.filename, dfudev.dev.idVendor,
|
||||
dfudev.dev.idProduct, man, product, serial_no)
|
||||
|
||||
if args.serial_target and serial_no != args.serial_target:
|
||||
print "Serial number doesn't match!\n"
|
||||
exit(-2)
|
||||
try:
|
||||
state = dfudev.get_state()
|
||||
except:
|
||||
|
@ -92,13 +106,20 @@ if __name__ == "__main__":
|
|||
|
||||
dfudev.make_idle()
|
||||
|
||||
bin = open(argv[1], "rb").read()
|
||||
bin = open(args.progfile, "rb").read()
|
||||
|
||||
addr = 0x8002000
|
||||
if product.find("F4") :
|
||||
addr = 0x8004000
|
||||
else:
|
||||
addr = 0x8002000
|
||||
while bin:
|
||||
print ("Programming memory at 0x%08X\r" % addr),
|
||||
stdout.flush()
|
||||
stm32_erase(dfudev, addr)
|
||||
try:
|
||||
stm32_erase(dfudev, addr)
|
||||
except:
|
||||
print "\nErase Timed out\n"
|
||||
break
|
||||
stm32_write(dfudev, bin[:1024])
|
||||
|
||||
bin = bin[1024:]
|
||||
|
|
|
@ -47,6 +47,7 @@ blackmagic: $(OBJ)
|
|||
|
||||
clean: host_clean
|
||||
$(RM) *.o *.d *~ blackmagic $(HOSTFILES)
|
||||
$(RM) platforms/*/*.o platforms/*/*.d mapfile
|
||||
|
||||
-include *.d
|
||||
|
||||
|
|
28
src/crc32.c
28
src/crc32.c
|
@ -21,6 +21,7 @@
|
|||
#include "platform.h"
|
||||
#include "target.h"
|
||||
|
||||
#if !defined(STM32F1) && !defined(STM32F4)
|
||||
static const uint32_t crc32_table[] = {
|
||||
0x00000000, 0x04C11DB7, 0x09823B6E, 0x0D4326D9,
|
||||
0x130476DC, 0x17C56B6B, 0x1A864DB2, 0x1E475005,
|
||||
|
@ -107,4 +108,31 @@ uint32_t generic_crc32(struct target_s *target, uint32_t base, int len)
|
|||
}
|
||||
return crc;
|
||||
}
|
||||
#else
|
||||
#include <libopencm3/stm32/crc.h>
|
||||
uint32_t generic_crc32(struct target_s *target, uint32_t base, int len)
|
||||
{
|
||||
uint32_t data;
|
||||
uint8_t byte;
|
||||
|
||||
CRC_CR |= CRC_CR_RESET;
|
||||
|
||||
while (len >3) {
|
||||
if (target_mem_read_words(target, &data, base, 1) != 0)
|
||||
return -1;
|
||||
|
||||
CRC_DR = data;
|
||||
base+=4;
|
||||
len -= 4;
|
||||
}
|
||||
while (len--) {
|
||||
if (target_mem_read_bytes(target, &byte, base, 1) != 0)
|
||||
return -1;
|
||||
|
||||
CRC_DR = byte;
|
||||
base++;
|
||||
}
|
||||
return CRC_DR;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -21,6 +21,11 @@
|
|||
#ifndef __GDB_IF_H
|
||||
#define __GDB_IF_H
|
||||
|
||||
#if !defined(LIBFTDI)
|
||||
#include <libopencm3/usb/usbd.h>
|
||||
void gdb_usb_out_cb(usbd_device *dev, uint8_t ep);
|
||||
#endif
|
||||
|
||||
int gdb_if_init(void);
|
||||
unsigned char gdb_if_getchar(void);
|
||||
unsigned char gdb_if_getchar_to(int timeout);
|
||||
|
|
|
@ -26,4 +26,3 @@ void traceswo_init(void);
|
|||
void trace_buf_drain(usbd_device *dev, uint8_t ep);
|
||||
|
||||
#endif
|
||||
|
|
@ -31,4 +31,3 @@ void usbuart_usb_out_cb(usbd_device *dev, uint8_t ep);
|
|||
void usbuart_usb_in_cb(usbd_device *dev, uint8_t ep);
|
||||
|
||||
#endif
|
||||
|
|
@ -58,6 +58,8 @@ static struct jtag_dev_descr_s {
|
|||
.descr = "ST Microelectronics: STM32, Low density."},
|
||||
{.idcode = 0x06414041, .idmask = 0x0FFFFFFF,
|
||||
.descr = "ST Microelectronics: STM32, High density."},
|
||||
{.idcode = 0x06416041, .idmask = 0x0FFFFFFF,
|
||||
.descr = "ST Microelectronics: STM32L."},
|
||||
{.idcode = 0x06418041, .idmask = 0x0FFFFFFF,
|
||||
.descr = "ST Microelectronics: STM32, Connectivity Line."},
|
||||
{.idcode = 0x06420041, .idmask = 0x0FFFFFFF,
|
||||
|
|
|
@ -34,10 +34,15 @@
|
|||
#include "target.h"
|
||||
|
||||
int
|
||||
main(void)
|
||||
main(int argc, char **argv)
|
||||
{
|
||||
#if defined(LIBFTDI)
|
||||
assert(platform_init(argc, argv) == 0);
|
||||
#else
|
||||
(void) argc;
|
||||
(void) argv;
|
||||
assert(platform_init() == 0);
|
||||
|
||||
#endif
|
||||
PLATFORM_SET_FATAL_ERROR_RECOVERY();
|
||||
|
||||
gdb_main();
|
||||
|
|
|
@ -0,0 +1,36 @@
|
|||
CROSS_COMPILE ?= arm-none-eabi-
|
||||
CC = $(CROSS_COMPILE)gcc
|
||||
OBJCOPY = $(CROSS_COMPILE)objcopy
|
||||
|
||||
CFLAGS += -Istm32/include -mcpu=cortex-m3 -mthumb \
|
||||
-DSTM32F4 -DF4DISCOVERY -I../libopencm3/include
|
||||
|
||||
LDFLAGS_BOOT = -lopencm3_stm32f4 -Wl,--defsym,_stack=0x20020000 \
|
||||
-Wl,-T,platforms/stm32/f4discovery.ld -nostartfiles -lc -lnosys \
|
||||
-Wl,-Map=mapfile -mthumb -mcpu=cortex-m3 -Wl,-gc-sections \
|
||||
-L../libopencm3/lib
|
||||
LDFLAGS = $(LDFLAGS_BOOT) -Wl,-Ttext=0x8010000
|
||||
|
||||
VPATH += platforms/stm32
|
||||
|
||||
SRC += cdcacm.c \
|
||||
platform.c \
|
||||
traceswo.c \
|
||||
usbuart.c \
|
||||
|
||||
all: blackmagic.bin blackmagic_dfu.bin blackmagic_dfu.hex
|
||||
|
||||
blackmagic.bin: blackmagic
|
||||
$(OBJCOPY) -O binary $^ $@
|
||||
|
||||
blackmagic_dfu: usbdfu.o
|
||||
$(CC) $^ -o $@ $(LDFLAGS_BOOT)
|
||||
|
||||
blackmagic_dfu.bin: blackmagic_dfu
|
||||
$(OBJCOPY) -O binary $^ $@
|
||||
|
||||
blackmagic_dfu.hex: blackmagic_dfu
|
||||
$(OBJCOPY) -O ihex $^ $@
|
||||
|
||||
host_clean:
|
||||
-rm blackmagic.bin blackmagic_dfu blackmagic_dfu.bin blackmagic_dfu.hex
|
|
@ -0,0 +1,17 @@
|
|||
Application start address:
|
||||
=========================
|
||||
|
||||
Use 0x8010000
|
||||
- lower 3 16 k pages may be used for parameter storage
|
||||
- Erasing a single 64 k Page is faster then erasing 2 16 k Pages
|
||||
eventual the 64 k page
|
||||
|
||||
|
||||
Internal boot loader:
|
||||
====================
|
||||
|
||||
When we request invokation of a bootloader from inside the application,
|
||||
we boot the device internal bootloader with the blue botton pressed.
|
||||
|
||||
That way, we can easy exchange the custom bootloader via the device
|
||||
internale bootloader
|
|
@ -0,0 +1,208 @@
|
|||
/*
|
||||
* 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 <libopencm3/stm32/f4/rcc.h>
|
||||
#include <libopencm3/cm3/systick.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>
|
||||
|
||||
#include "platform.h"
|
||||
#include "jtag_scan.h"
|
||||
#include <usbuart.h>
|
||||
|
||||
#include <ctype.h>
|
||||
|
||||
uint8_t running_status;
|
||||
volatile uint32_t timeout_counter;
|
||||
|
||||
jmp_buf fatal_error_jmpbuf;
|
||||
|
||||
static void morse_update(void);
|
||||
|
||||
int platform_init(void)
|
||||
{
|
||||
rcc_clock_setup_hse_3v3(&hse_8mhz_3v3[CLOCK_3V3_168MHZ]);
|
||||
|
||||
/* Enable peripherals */
|
||||
rcc_peripheral_enable_clock(&RCC_AHB2ENR, RCC_AHB2ENR_OTGFSEN);
|
||||
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPAEN);
|
||||
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPBEN);
|
||||
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPDEN);
|
||||
|
||||
|
||||
/* Set up USB Pins and alternate function*/
|
||||
gpio_mode_setup(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE,
|
||||
GPIO9 | GPIO11 | GPIO12);
|
||||
gpio_set_af(GPIOA, GPIO_AF10, GPIO9 | GPIO11 | GPIO12);
|
||||
|
||||
GPIOA_OSPEEDR &=~0xfc;
|
||||
GPIOA_OSPEEDR |= 0xa8;
|
||||
gpio_mode_setup(JTAG_PORT, GPIO_MODE_OUTPUT,
|
||||
GPIO_PUPD_NONE,
|
||||
TMS_PIN | TCK_PIN | TDI_PIN);
|
||||
|
||||
gpio_mode_setup(TDO_PORT, GPIO_MODE_INPUT,
|
||||
GPIO_PUPD_NONE,
|
||||
TDO_PIN);
|
||||
|
||||
gpio_mode_setup(LED_PORT, GPIO_MODE_OUTPUT,
|
||||
GPIO_PUPD_NONE,
|
||||
LED_UART | LED_IDLE_RUN | LED_ERROR | LED_SPARE1);
|
||||
|
||||
/* Setup heartbeat timer */
|
||||
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
|
||||
systick_set_reload(168000000/(10*8)); /* Interrupt us at 10 Hz */
|
||||
SCB_SHPR(11) &= ~((15 << 4) & 0xff);
|
||||
SCB_SHPR(11) |= ((14 << 4) & 0xff);
|
||||
systick_interrupt_enable();
|
||||
systick_counter_enable();
|
||||
|
||||
usbuart_init();
|
||||
|
||||
SCB_VTOR = 0x10000; // Relocate interrupt vector table here
|
||||
|
||||
cdcacm_init();
|
||||
|
||||
jtag_scan(NULL);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void platform_delay(uint32_t delay)
|
||||
{
|
||||
timeout_counter = delay;
|
||||
while(timeout_counter);
|
||||
}
|
||||
|
||||
void sys_tick_handler(void)
|
||||
{
|
||||
if(running_status)
|
||||
gpio_toggle(LED_PORT, LED_IDLE_RUN);
|
||||
|
||||
if(timeout_counter)
|
||||
timeout_counter--;
|
||||
|
||||
morse_update();
|
||||
}
|
||||
|
||||
|
||||
/* Morse code patterns and lengths */
|
||||
static const struct {
|
||||
uint16_t code;
|
||||
uint8_t bits;
|
||||
} morse_letter[] = {
|
||||
{ 0b00011101, 8}, // 'A' .-
|
||||
{ 0b000101010111, 12}, // 'B' -...
|
||||
{ 0b00010111010111, 14}, // 'C' -.-.
|
||||
{ 0b0001010111, 10}, // 'D' -..
|
||||
{ 0b0001, 4}, // 'E' .
|
||||
{ 0b000101110101, 12}, // 'F' ..-.
|
||||
{ 0b000101110111, 12}, // 'G' --.
|
||||
{ 0b0001010101, 10}, // 'H' ....
|
||||
{ 0b000101, 6}, // 'I' ..
|
||||
{0b0001110111011101, 16}, // 'J' .---
|
||||
{ 0b000111010111, 12}, // 'K' -.-
|
||||
{ 0b000101011101, 12}, // 'L' .-..
|
||||
{ 0b0001110111, 10}, // 'M' --
|
||||
{ 0b00010111, 8}, // 'N' -.
|
||||
{ 0b00011101110111, 14}, // 'O' ---
|
||||
{ 0b00010111011101, 14}, // 'P' .--.
|
||||
{0b0001110101110111, 16}, // 'Q' --.-
|
||||
{ 0b0001011101, 10}, // 'R' .-.
|
||||
{ 0b00010101, 8}, // 'S' ...
|
||||
{ 0b000111, 6}, // 'T' -
|
||||
{ 0b0001110101, 10}, // 'U' ..-
|
||||
{ 0b000111010101, 12}, // 'V' ...-
|
||||
{ 0b000111011101, 12}, // 'W' .--
|
||||
{ 0b00011101010111, 14}, // 'X' -..-
|
||||
{0b0001110111010111, 16}, // 'Y' -.--
|
||||
{ 0b00010101110111, 14}, // 'Z' --..
|
||||
};
|
||||
|
||||
|
||||
const char *morse_msg;
|
||||
static const char * volatile morse_ptr;
|
||||
static char morse_repeat;
|
||||
|
||||
void morse(const char *msg, char repeat)
|
||||
{
|
||||
morse_msg = morse_ptr = msg;
|
||||
morse_repeat = repeat;
|
||||
SET_ERROR_STATE(0);
|
||||
}
|
||||
|
||||
static void morse_update(void)
|
||||
{
|
||||
static uint16_t code;
|
||||
static uint8_t bits;
|
||||
|
||||
if(!morse_ptr) return;
|
||||
|
||||
if(!bits) {
|
||||
char c = *morse_ptr++;
|
||||
if(!c) {
|
||||
if(morse_repeat) {
|
||||
morse_ptr = morse_msg;
|
||||
c = *morse_ptr++;
|
||||
} else {
|
||||
morse_ptr = 0;
|
||||
return;
|
||||
}
|
||||
}
|
||||
if((c >= 'A') && (c <= 'Z')) {
|
||||
c -= 'A';
|
||||
code = morse_letter[c].code;
|
||||
bits = morse_letter[c].bits;
|
||||
} else {
|
||||
code = 0; bits = 4;
|
||||
}
|
||||
}
|
||||
SET_ERROR_STATE(code & 1);
|
||||
code >>= 1; bits--;
|
||||
}
|
||||
|
||||
const char *platform_target_voltage(void)
|
||||
{
|
||||
return "ABSENT!";
|
||||
}
|
||||
|
||||
void assert_boot_pin(void)
|
||||
{
|
||||
if (gpio_get(GPIOA, GPIO0)) {
|
||||
/* Jump to the built in bootloader by mapping System flash */
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_SYSCFGEN);
|
||||
SYSCFG_MEMRM &= ~3;
|
||||
SYSCFG_MEMRM |= 1;
|
||||
}
|
||||
else {
|
||||
/* Flag Bootloader Request by mimicing a pushed USER button*/
|
||||
gpio_mode_setup(GPIOA, GPIO_MODE_OUTPUT,
|
||||
GPIO_PUPD_NONE, GPIO0);
|
||||
gpio_set(GPIOA, GPIO0);
|
||||
}
|
||||
}
|
|
@ -0,0 +1,213 @@
|
|||
/*
|
||||
* 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 <libopencm3/stm32/f4/gpio.h>
|
||||
#include <libopencm3/usb/usbd.h>
|
||||
|
||||
#include <setjmp.h>
|
||||
#include <alloca.h>
|
||||
|
||||
#include "gdb_packet.h"
|
||||
|
||||
#define INLINE_GPIO
|
||||
#define CDCACM_PACKET_SIZE 64
|
||||
#define PLATFORM_HAS_TRACESWO
|
||||
#define BOARD_IDENT "Black Magic Probe (F4Discovery), (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")"
|
||||
#define DFU_IDENT "Black Magic Firmware Upgrade (F4Discovery"
|
||||
|
||||
extern usbd_device *usbdev;
|
||||
#define CDCACM_GDB_ENDPOINT 1
|
||||
#define CDCACM_UART_ENDPOINT 3
|
||||
|
||||
/* Important pin mappings for STM32 implementation:
|
||||
*
|
||||
* LED0 = PD12 (Green LED : Running)
|
||||
* LED1 = PD13 (Orange LED : Idle)
|
||||
* LED2 = PD12 (Red LED : Error)
|
||||
*
|
||||
* TPWR = XXX (input) -- analogue on mini design ADC1, ch8
|
||||
* nTRST = PD0
|
||||
* SRST_OUT = PD1
|
||||
* TDI = PA1
|
||||
* TMS = PA3 (input for SWDP)
|
||||
* TCK = PA8
|
||||
* TDO = PB4 (input)
|
||||
* nSRST = PD2 (input)
|
||||
*
|
||||
* USB cable pull-up: PA8
|
||||
* USB VBUS detect: PB13 -- New on mini design.
|
||||
* Enable pull up for compatibility.
|
||||
* Force DFU mode button: PB12
|
||||
*/
|
||||
|
||||
/* Hardware definitions... */
|
||||
#define JTAG_PORT GPIOA
|
||||
#define TDI_PORT JTAG_PORT
|
||||
#define TMS_PORT JTAG_PORT
|
||||
#define TCK_PORT JTAG_PORT
|
||||
#define TDO_PORT GPIOB
|
||||
#define TDI_PIN GPIO1
|
||||
#define TMS_PIN GPIO3
|
||||
#define TCK_PIN GPIO2
|
||||
#define TDO_PIN GPIO4
|
||||
|
||||
#define SWDIO_PORT JTAG_PORT
|
||||
#define SWCLK_PORT JTAG_PORT
|
||||
#define SWDIO_PIN TMS_PIN
|
||||
#define SWCLK_PIN TCK_PIN
|
||||
|
||||
#define TRST_PORT GPIOD
|
||||
#define TRST_PIN GPIO0
|
||||
#define SRST_PORT GPIOD
|
||||
#define SRST_PIN GPIO1
|
||||
|
||||
#define LED_PORT GPIOD
|
||||
#define LED_PORT_UART GPIOD
|
||||
#define LED_UART GPIO12
|
||||
#define LED_IDLE_RUN GPIO13
|
||||
#define LED_ERROR GPIO14
|
||||
#define LED_SPARE1 GPIO15
|
||||
|
||||
#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 stm32f107_usb_driver
|
||||
#define USB_IRQ NVIC_OTG_FS_IRQ
|
||||
#define USB_ISR otg_fs_isr
|
||||
/* Interrupt priorities. Low numbers are high priority.
|
||||
* For now USART1 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_TRACE (0 << 4)
|
||||
|
||||
#define USBUSART USART3
|
||||
#define USBUSART_CR1 USART3_CR1
|
||||
#define USBUSART_IRQ NVIC_USART3_IRQ
|
||||
#define USBUSART_APB_ENR RCC_APB1ENR
|
||||
#define USBUSART_CLK_ENABLE RCC_APB1ENR_USART3EN
|
||||
#define USBUSART_TX_PORT GPIOD
|
||||
#define USBUSART_TX_PIN GPIO8
|
||||
#define USBUSART_RX_PORT GPIOD
|
||||
#define USBUSART_RX_PIN GPIO9
|
||||
#define USBUSART_ISR usart3_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_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_TIM3EN)
|
||||
#define TRACE_IRQ NVIC_TIM3_IRQ
|
||||
#define TRACE_ISR tim3_isr
|
||||
|
||||
#define DEBUG(...)
|
||||
|
||||
extern uint8_t running_status;
|
||||
extern volatile uint32_t timeout_counter;
|
||||
|
||||
extern jmp_buf fatal_error_jmpbuf;
|
||||
|
||||
extern const char *morse_msg;
|
||||
|
||||
#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, LED_ERROR, state);}
|
||||
|
||||
#define PLATFORM_SET_FATAL_ERROR_RECOVERY() {setjmp(fatal_error_jmpbuf);}
|
||||
#define PLATFORM_FATAL_ERROR(error) { \
|
||||
if(running_status) gdb_putpacketz("X1D"); \
|
||||
else gdb_putpacketz("EFF"); \
|
||||
running_status = 0; \
|
||||
target_list_free(); \
|
||||
morse("TARGET LOST.", 1); \
|
||||
longjmp(fatal_error_jmpbuf, (error)); \
|
||||
}
|
||||
|
||||
int platform_init(void);
|
||||
void morse(const char *msg, char repeat);
|
||||
const char *platform_target_voltage(void);
|
||||
int platform_hwversion(void);
|
||||
void platform_delay(uint32_t delay);
|
||||
|
||||
/* <cdcacm.c> */
|
||||
void cdcacm_init(void);
|
||||
/* Returns current usb configuration, or 0 if not configured. */
|
||||
int cdcacm_get_config(void);
|
||||
int cdcacm_get_dtr(void);
|
||||
|
||||
/* <platform.h> */
|
||||
void uart_usb_buf_drain(uint8_t ep);
|
||||
|
||||
/* Use newlib provided integer only stdio functions */
|
||||
#define sscanf siscanf
|
||||
#define sprintf siprintf
|
||||
#define vasprintf vasiprintf
|
||||
|
||||
#ifdef INLINE_GPIO
|
||||
static inline void _gpio_set(u32 gpioport, u16 gpios)
|
||||
{
|
||||
GPIO_BSRR(gpioport) = gpios;
|
||||
}
|
||||
#define gpio_set _gpio_set
|
||||
|
||||
static inline void _gpio_clear(u32 gpioport, u16 gpios)
|
||||
{
|
||||
GPIO_BSRR(gpioport) = gpios<<16;
|
||||
}
|
||||
#define gpio_clear _gpio_clear
|
||||
|
||||
static inline u16 _gpio_get(u32 gpioport, u16 gpios)
|
||||
{
|
||||
return (u16)GPIO_IDR(gpioport) & gpios;
|
||||
}
|
||||
#define gpio_get _gpio_get
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#define disconnect_usb() do {usbd_disconnect(usbdev,1); nvic_disable_irq(USB_IRQ);} while(0)
|
||||
void assert_boot_pin(void);
|
||||
#define setup_vbus_irq()
|
|
@ -1 +1,2 @@
|
|||
CFLAGS += -DLIBFTDI
|
||||
LDFLAGS += -lftdi -lusb
|
||||
|
|
|
@ -55,14 +55,6 @@ int jtagtap_init(void)
|
|||
|
||||
assert(ftdic != NULL);
|
||||
|
||||
if((err = ftdi_set_bitmode(ftdic, 0xAB, BITMODE_MPSSE)) != 0) {
|
||||
fprintf(stderr, "ftdi_set_bitmode: %d: %s\n",
|
||||
err, ftdi_get_error_string(ftdic));
|
||||
abort();
|
||||
}
|
||||
|
||||
assert(ftdi_write_data(ftdic, "\x86\x00\x00\x80\xA8\xAB", 6) == 6);
|
||||
|
||||
/* Go to JTAG mode for SWJ-DP */
|
||||
for(int i = 0; i <= 50; i++) jtagtap_next(1, 0); /* Reset SW-DP */
|
||||
jtagtap_tms_seq(0xE73C, 16); /* SWD to JTAG sequence */
|
||||
|
|
|
@ -32,9 +32,125 @@ struct ftdi_context *ftdic;
|
|||
static uint8_t outbuf[BUF_SIZE];
|
||||
static uint16_t bufptr = 0;
|
||||
|
||||
int platform_init(void)
|
||||
static struct cable_desc_s {
|
||||
int vendor;
|
||||
int product;
|
||||
int interface;
|
||||
uint8_t dbus_data;
|
||||
uint8_t dbus_ddr;
|
||||
uint8_t cbus_data;
|
||||
uint8_t cbus_ddr;
|
||||
char *description;
|
||||
char * name;
|
||||
} cable_desc[] = {
|
||||
{
|
||||
.vendor = 0x0403,
|
||||
.product = 0x6010,
|
||||
.interface = INTERFACE_A,
|
||||
.dbus_data = 0x08,
|
||||
.dbus_ddr = 0x1B,
|
||||
.description = "FTDIJTAG",
|
||||
.name = "ftdijtag"
|
||||
},
|
||||
{
|
||||
.vendor = 0x15b1,
|
||||
.product = 0x0003,
|
||||
.interface = INTERFACE_A,
|
||||
.dbus_data = 0x08,
|
||||
.dbus_ddr = 0x1B,
|
||||
.name = "olimex"
|
||||
},
|
||||
{
|
||||
.vendor = 0x0403,
|
||||
.product = 0xbdc8,
|
||||
.interface = INTERFACE_A,
|
||||
.dbus_data = 0x08,
|
||||
.dbus_ddr = 0x1B,
|
||||
.name = "turtelizer"
|
||||
},
|
||||
{
|
||||
.vendor = 0x0403,
|
||||
.product = 0xbdc8,
|
||||
.interface = INTERFACE_A,
|
||||
.dbus_data = 0x08,
|
||||
.dbus_ddr = 0x1B,
|
||||
.name = "jtaghs1"
|
||||
},
|
||||
{
|
||||
.vendor = 0x0403,
|
||||
.product = 0xbdc8,
|
||||
.interface = INTERFACE_A,
|
||||
.dbus_data = 0xA8,
|
||||
.dbus_ddr = 0xAB,
|
||||
.name = "ftdi"
|
||||
},
|
||||
{
|
||||
.vendor = 0x0403,
|
||||
.product = 0x6014,
|
||||
.interface = INTERFACE_A,
|
||||
.dbus_data = 0x08,
|
||||
.dbus_ddr = 0x0B,
|
||||
.name = "ft232h"
|
||||
},
|
||||
{
|
||||
.vendor = 0x0403,
|
||||
.product = 0x6011,
|
||||
.interface = INTERFACE_A,
|
||||
.dbus_data = 0x08,
|
||||
.dbus_ddr = 0x0B,
|
||||
.name = "ft4232h"
|
||||
},
|
||||
{
|
||||
.vendor = 0x15ba,
|
||||
.product = 0x002b,
|
||||
.interface = INTERFACE_A,
|
||||
.dbus_data = 0x08,
|
||||
.dbus_ddr = 0x1B,
|
||||
.cbus_data = 0x00,
|
||||
.cbus_ddr = 0x08,
|
||||
.name = "arm-usb-ocd-h"
|
||||
},
|
||||
};
|
||||
|
||||
int platform_init(int argc, char **argv)
|
||||
{
|
||||
int err;
|
||||
int c;
|
||||
int index = 0;
|
||||
char *serial = NULL;
|
||||
char * cablename = "ftdi";
|
||||
uint8_t ftdi_init[9] = {TCK_DIVISOR, 0x01, 0x00, SET_BITS_LOW, 0,0,
|
||||
SET_BITS_HIGH, 0,0};
|
||||
|
||||
while((c = getopt(argc, argv, "c:s:")) != -1) {
|
||||
switch(c) {
|
||||
case 'c':
|
||||
cablename = optarg;
|
||||
break;
|
||||
case 's':
|
||||
serial = optarg;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
for(index = 0; index < sizeof(cable_desc)/sizeof(cable_desc[0]);
|
||||
index++)
|
||||
if (strcmp(cable_desc[index].name, cablename) == 0)
|
||||
break;
|
||||
|
||||
if (index == sizeof(cable_desc)/sizeof(cable_desc[0])){
|
||||
fprintf(stderr, "No cable matching %s found\n",cablename);
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (cable_desc[index].dbus_data)
|
||||
ftdi_init[4]= cable_desc[index].dbus_data;
|
||||
if (cable_desc[index].dbus_ddr)
|
||||
ftdi_init[5]= cable_desc[index].dbus_ddr;
|
||||
if (cable_desc[index].cbus_data)
|
||||
ftdi_init[7]= cable_desc[index].cbus_data;
|
||||
if(cable_desc[index].cbus_ddr)
|
||||
ftdi_init[8]= cable_desc[index].cbus_ddr;
|
||||
|
||||
if(ftdic) {
|
||||
ftdi_usb_close(ftdic);
|
||||
|
@ -46,12 +162,14 @@ int platform_init(void)
|
|||
ftdi_get_error_string(ftdic));
|
||||
abort();
|
||||
}
|
||||
if((err = ftdi_set_interface(ftdic, INTERFACE_A)) != 0) {
|
||||
if((err = ftdi_set_interface(ftdic, cable_desc[index].interface)) != 0) {
|
||||
fprintf(stderr, "ftdi_set_interface: %d: %s\n",
|
||||
err, ftdi_get_error_string(ftdic));
|
||||
abort();
|
||||
}
|
||||
if((err = ftdi_usb_open(ftdic, FT2232_VID, FT2232_PID)) != 0) {
|
||||
if((err = ftdi_usb_open_desc(
|
||||
ftdic, cable_desc[index].vendor, cable_desc[index].product,
|
||||
cable_desc[index].description, serial)) != 0) {
|
||||
fprintf(stderr, "unable to open ftdi device: %d (%s)\n",
|
||||
err, ftdi_get_error_string(ftdic));
|
||||
abort();
|
||||
|
@ -78,6 +196,14 @@ int platform_init(void)
|
|||
abort();
|
||||
}
|
||||
|
||||
if((err = ftdi_set_bitmode(ftdic, 0xAB, BITMODE_MPSSE)) != 0) {
|
||||
fprintf(stderr, "ftdi_set_bitmode: %d: %s\n",
|
||||
err, ftdi_get_error_string(ftdic));
|
||||
abort();
|
||||
}
|
||||
|
||||
assert(ftdi_write_data(ftdic, ftdi_init, 9) == 9);
|
||||
|
||||
assert(gdb_if_init() == 0);
|
||||
|
||||
jtag_scan(NULL);
|
||||
|
|
|
@ -40,12 +40,12 @@
|
|||
#define PLATFORM_FATAL_ERROR(error) abort()
|
||||
#define PLATFORM_SET_FATAL_ERROR_RECOVERY()
|
||||
|
||||
#define morse(x, y) do {} while(0)
|
||||
#define morse(x, y) fprintf(stderr,"%s\n", x)
|
||||
#define morse_msg 0
|
||||
|
||||
extern struct ftdi_context *ftdic;
|
||||
|
||||
int platform_init(void);
|
||||
int platform_init(int argc, char **argv);
|
||||
const char *platform_target_voltage(void);
|
||||
void platform_delay(uint32_t delay);
|
||||
|
||||
|
|
|
@ -3,7 +3,8 @@ CC = $(CROSS_COMPILE)gcc
|
|||
OBJCOPY = $(CROSS_COMPILE)objcopy
|
||||
|
||||
CFLAGS += -Istm32/include -mcpu=cortex-m3 -mthumb \
|
||||
-DSTM32F1 -I../libopencm3/include
|
||||
-DSTM32F1 -DBLACKMAGIC -I../libopencm3/include
|
||||
|
||||
LDFLAGS_BOOT = -lopencm3_stm32f1 -Wl,--defsym,_stack=0x20005000 \
|
||||
-Wl,-T,platforms/stm32/blackmagic.ld -nostartfiles -lc -lnosys \
|
||||
-Wl,-Map=mapfile -mthumb -mcpu=cortex-m3 -Wl,-gc-sections \
|
||||
|
|
|
@ -26,13 +26,14 @@
|
|||
#include <libopencm3/cm3/systick.h>
|
||||
#include <libopencm3/cm3/scb.h>
|
||||
#include <libopencm3/cm3/nvic.h>
|
||||
#include <libopencm3/stm32/exti.h>
|
||||
#include <libopencm3/stm32/usart.h>
|
||||
#include <libopencm3/usb/usbd.h>
|
||||
#include <libopencm3/stm32/f1/adc.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "jtag_scan.h"
|
||||
#include "usbuart.h"
|
||||
#include <usbuart.h>
|
||||
|
||||
#include <ctype.h>
|
||||
|
||||
|
@ -262,3 +263,44 @@ const char *platform_target_voltage(void)
|
|||
|
||||
return ret;
|
||||
}
|
||||
|
||||
void assert_boot_pin(void)
|
||||
{
|
||||
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, GPIO12);
|
||||
gpio_clear(GPIOB, GPIO12);
|
||||
}
|
||||
|
||||
void exti15_10_isr(void)
|
||||
{
|
||||
if (gpio_get(USB_VBUS_PORT, USB_VBUS_PIN)) {
|
||||
/* Drive pull-up high if VBUS connected */
|
||||
gpio_set_mode(USB_PU_PORT, GPIO_MODE_OUTPUT_10_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, USB_PU_PIN);
|
||||
} else {
|
||||
/* Allow pull-up to float if VBUS disconnected */
|
||||
gpio_set_mode(USB_PU_PORT, GPIO_MODE_INPUT,
|
||||
GPIO_CNF_INPUT_FLOAT, USB_PU_PIN);
|
||||
}
|
||||
|
||||
exti_reset_request(USB_VBUS_PIN);
|
||||
}
|
||||
|
||||
void setup_vbus_irq(void)
|
||||
{
|
||||
nvic_set_priority(USB_VBUS_IRQ, IRQ_PRI_USB_VBUS);
|
||||
nvic_enable_irq(USB_VBUS_IRQ);
|
||||
|
||||
gpio_set(USB_VBUS_PORT, USB_VBUS_PIN);
|
||||
gpio_set(USB_PU_PORT, USB_PU_PIN);
|
||||
|
||||
gpio_set_mode(USB_VBUS_PORT, GPIO_MODE_INPUT,
|
||||
GPIO_CNF_INPUT_PULL_UPDOWN, USB_VBUS_PIN);
|
||||
|
||||
/* Configure EXTI for USB VBUS monitor */
|
||||
exti_select_source(USB_VBUS_PIN, USB_VBUS_PORT);
|
||||
exti_set_trigger(USB_VBUS_PIN, EXTI_TRIGGER_BOTH);
|
||||
exti_enable_request(USB_VBUS_PIN);
|
||||
|
||||
exti15_10_isr();
|
||||
}
|
||||
|
|
|
@ -35,6 +35,8 @@
|
|||
#define INLINE_GPIO
|
||||
#define CDCACM_PACKET_SIZE 64
|
||||
#define PLATFORM_HAS_TRACESWO
|
||||
#define BOARD_IDENT "Black Magic Probe, (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")"
|
||||
#define DFU_IDENT "Black Magic Firmware Upgrade"
|
||||
|
||||
extern usbd_device *usbdev;
|
||||
#define CDCACM_GDB_ENDPOINT 1
|
||||
|
@ -90,18 +92,50 @@ extern usbd_device *usbdev;
|
|||
#define USB_VBUS_IRQ NVIC_EXTI15_10_IRQ
|
||||
|
||||
#define LED_PORT GPIOB
|
||||
#define LED_PORT_UART GPIOB
|
||||
#define LED_UART GPIO2
|
||||
#define LED_IDLE_RUN GPIO10
|
||||
#define LED_ERROR GPIO11
|
||||
|
||||
#define TMS_SET_MODE() \
|
||||
gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_50_MHZ, \
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, TMS_PIN);
|
||||
#define SWDIO_MODE_FLOAT() \
|
||||
gpio_set_mode(SWDIO_PORT, GPIO_MODE_INPUT, \
|
||||
GPIO_CNF_INPUT_FLOAT, SWDIO_PIN);
|
||||
#define SWDIO_MODE_DRIVE() \
|
||||
gpio_set_mode(SWDIO_PORT, GPIO_MODE_OUTPUT_50_MHZ, \
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, SWDIO_PIN);
|
||||
|
||||
#define UART_PIN_SETUP() \
|
||||
gpio_set_mode(USBUSART_PORT, GPIO_MODE_OUTPUT_2_MHZ, \
|
||||
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, USBUSART_TX_PIN);
|
||||
|
||||
#define USB_DRIVER stm32f103_usb_driver
|
||||
#define USB_IRQ NVIC_USB_LP_CAN_RX0_IRQ
|
||||
#define USB_ISR usb_lp_can_rx0_isr
|
||||
/* Interrupt priorities. Low numbers are high priority.
|
||||
* For now USART1 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_USART1 (1 << 4)
|
||||
#define IRQ_PRI_USBUSART (1 << 4)
|
||||
#define IRQ_PRI_USB_VBUS (14 << 4)
|
||||
#define IRQ_PRI_TIM3 (0 << 4)
|
||||
#define IRQ_PRI_TRACE (0 << 4)
|
||||
|
||||
#define USBUSART USART1
|
||||
#define USBUSART_CR1 USART1_CR1
|
||||
#define USBUSART_IRQ NVIC_USART1_IRQ
|
||||
#define USBUSART_APB_ENR RCC_APB2ENR
|
||||
#define USBUSART_CLK_ENABLE RCC_APB2ENR_USART1EN
|
||||
#define USBUSART_PORT GPIOA
|
||||
#define USBUSART_TX_PIN GPIO9
|
||||
#define USBUSART_ISR usart1_isr
|
||||
|
||||
#define TRACE_TIM TIM3
|
||||
#define TRACE_TIM_CLK_EN() rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_TIM3EN)
|
||||
#define TRACE_IRQ NVIC_TIM3_IRQ
|
||||
#define TRACE_ISR tim3_isr
|
||||
|
||||
#define DEBUG(...)
|
||||
|
||||
|
@ -175,3 +209,6 @@ static inline u16 _gpio_get(u32 gpioport, u16 gpios)
|
|||
|
||||
#endif
|
||||
|
||||
#define disconnect_usb() gpio_set_mode(USB_PU_PORT, GPIO_MODE_INPUT, 0, USB_PU_PIN);
|
||||
void assert_boot_pin(void);
|
||||
void setup_vbus_irq(void);
|
||||
|
|
|
@ -1,333 +0,0 @@
|
|||
/*
|
||||
* This file is part of the libopencm3 project.
|
||||
*
|
||||
* Copyright (C) 2010 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 <string.h>
|
||||
#include <libopencm3/cm3/systick.h>
|
||||
#include <libopencm3/stm32/f1/rcc.h>
|
||||
#include <libopencm3/stm32/f1/gpio.h>
|
||||
#include <libopencm3/stm32/f1/flash.h>
|
||||
#include <libopencm3/cm3/scb.h>
|
||||
#include <libopencm3/usb/usbd.h>
|
||||
#include <libopencm3/usb/dfu.h>
|
||||
|
||||
#define APP_ADDRESS 0x08002000
|
||||
|
||||
/* Commands sent with wBlockNum == 0 as per ST implementation. */
|
||||
#define CMD_SETADDR 0x21
|
||||
#define CMD_ERASE 0x41
|
||||
|
||||
#define FLASH_OBP_RDP 0x1FFFF800
|
||||
#define FLASH_OBP_WRP10 0x1FFFF808
|
||||
|
||||
#define FLASH_OBP_RDP_KEY 0x5aa5
|
||||
|
||||
usbd_device *usbdev;
|
||||
/* We need a special large control buffer for this device: */
|
||||
u8 usbd_control_buffer[1024];
|
||||
|
||||
static enum dfu_state usbdfu_state = STATE_DFU_IDLE;
|
||||
|
||||
static char *get_dev_unique_id(char *serial_no);
|
||||
|
||||
static struct {
|
||||
u8 buf[sizeof(usbd_control_buffer)];
|
||||
u16 len;
|
||||
u32 addr;
|
||||
u16 blocknum;
|
||||
} prog;
|
||||
|
||||
const struct usb_device_descriptor dev = {
|
||||
.bLength = USB_DT_DEVICE_SIZE,
|
||||
.bDescriptorType = USB_DT_DEVICE,
|
||||
.bcdUSB = 0x0200,
|
||||
.bDeviceClass = 0,
|
||||
.bDeviceSubClass = 0,
|
||||
.bDeviceProtocol = 0,
|
||||
.bMaxPacketSize0 = 64,
|
||||
.idVendor = 0x1D50,
|
||||
.idProduct = 0x6017,
|
||||
.bcdDevice = 0x0100,
|
||||
.iManufacturer = 1,
|
||||
.iProduct = 2,
|
||||
.iSerialNumber = 3,
|
||||
.bNumConfigurations = 1,
|
||||
};
|
||||
|
||||
const struct usb_dfu_descriptor dfu_function = {
|
||||
.bLength = sizeof(struct usb_dfu_descriptor),
|
||||
.bDescriptorType = DFU_FUNCTIONAL,
|
||||
.bmAttributes = USB_DFU_CAN_DOWNLOAD | USB_DFU_WILL_DETACH,
|
||||
.wDetachTimeout = 255,
|
||||
.wTransferSize = 1024,
|
||||
.bcdDFUVersion = 0x011A,
|
||||
};
|
||||
|
||||
const struct usb_interface_descriptor iface = {
|
||||
.bLength = USB_DT_INTERFACE_SIZE,
|
||||
.bDescriptorType = USB_DT_INTERFACE,
|
||||
.bInterfaceNumber = 0,
|
||||
.bAlternateSetting = 0,
|
||||
.bNumEndpoints = 0,
|
||||
.bInterfaceClass = 0xFE, /* Device Firmware Upgrade */
|
||||
.bInterfaceSubClass = 1,
|
||||
.bInterfaceProtocol = 2,
|
||||
|
||||
/* The ST Microelectronics DfuSe application needs this string.
|
||||
* The format isn't documented... */
|
||||
.iInterface = 4,
|
||||
|
||||
.extra = &dfu_function,
|
||||
.extralen = sizeof(dfu_function),
|
||||
};
|
||||
|
||||
const struct usb_interface ifaces[] = {{
|
||||
.num_altsetting = 1,
|
||||
.altsetting = &iface,
|
||||
}};
|
||||
|
||||
const struct usb_config_descriptor config = {
|
||||
.bLength = USB_DT_CONFIGURATION_SIZE,
|
||||
.bDescriptorType = USB_DT_CONFIGURATION,
|
||||
.wTotalLength = 0,
|
||||
.bNumInterfaces = 1,
|
||||
.bConfigurationValue = 1,
|
||||
.iConfiguration = 0,
|
||||
.bmAttributes = 0xC0,
|
||||
.bMaxPower = 0x32,
|
||||
|
||||
.interface = ifaces,
|
||||
};
|
||||
|
||||
static char serial_no[9];
|
||||
|
||||
static const char *usb_strings[] = {
|
||||
"Black Sphere Technologies",
|
||||
"Black Magic Probe (Upgrade)",
|
||||
serial_no,
|
||||
/* This string is used by ST Microelectronics' DfuSe utility */
|
||||
"@Internal Flash /0x08000000/8*001Ka,120*001Kg"
|
||||
};
|
||||
|
||||
static u8 usbdfu_getstatus(u32 *bwPollTimeout)
|
||||
{
|
||||
switch(usbdfu_state) {
|
||||
case STATE_DFU_DNLOAD_SYNC:
|
||||
usbdfu_state = STATE_DFU_DNBUSY;
|
||||
*bwPollTimeout = 100;
|
||||
return DFU_STATUS_OK;
|
||||
|
||||
case STATE_DFU_MANIFEST_SYNC:
|
||||
/* Device will reset when read is complete */
|
||||
usbdfu_state = STATE_DFU_MANIFEST;
|
||||
return DFU_STATUS_OK;
|
||||
|
||||
default:
|
||||
return DFU_STATUS_OK;
|
||||
}
|
||||
}
|
||||
|
||||
static void
|
||||
usbdfu_getstatus_complete(usbd_device *dev, struct usb_setup_data *req)
|
||||
{
|
||||
int i;
|
||||
(void)req;
|
||||
|
||||
switch(usbdfu_state) {
|
||||
case STATE_DFU_DNBUSY:
|
||||
|
||||
flash_unlock();
|
||||
if(prog.blocknum == 0) {
|
||||
if ((*(u32*)(prog.buf+1) < 0x8002000) ||
|
||||
(*(u32*)(prog.buf+1) >= 0x8020000)) {
|
||||
usbd_ep_stall_set(dev, 0, 1);
|
||||
return;
|
||||
}
|
||||
switch(prog.buf[0]) {
|
||||
case CMD_ERASE:
|
||||
flash_erase_page(*(u32*)(prog.buf+1));
|
||||
case CMD_SETADDR:
|
||||
prog.addr = *(u32*)(prog.buf+1);
|
||||
}
|
||||
} else {
|
||||
u32 baseaddr = prog.addr +
|
||||
((prog.blocknum - 2) *
|
||||
dfu_function.wTransferSize);
|
||||
for(i = 0; i < prog.len; i += 2)
|
||||
flash_program_half_word(baseaddr + i,
|
||||
*(u16*)(prog.buf+i));
|
||||
}
|
||||
flash_lock();
|
||||
|
||||
/* We jump straight to dfuDNLOAD-IDLE,
|
||||
* skipping dfuDNLOAD-SYNC
|
||||
*/
|
||||
usbdfu_state = STATE_DFU_DNLOAD_IDLE;
|
||||
return;
|
||||
|
||||
case STATE_DFU_MANIFEST:
|
||||
/* USB device must detach, we just reset... */
|
||||
scb_reset_system();
|
||||
return; /* Will never return */
|
||||
default:
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
static int usbdfu_control_request(usbd_device *dev,
|
||||
struct usb_setup_data *req, u8 **buf, u16 *len,
|
||||
void (**complete)(usbd_device *dev, struct usb_setup_data *req))
|
||||
{
|
||||
(void)dev;
|
||||
|
||||
if((req->bmRequestType & 0x7F) != 0x21)
|
||||
return 0; /* Only accept class request */
|
||||
|
||||
switch(req->bRequest) {
|
||||
case DFU_DNLOAD:
|
||||
if((len == NULL) || (*len == 0)) {
|
||||
usbdfu_state = STATE_DFU_MANIFEST_SYNC;
|
||||
return 1;
|
||||
} else {
|
||||
/* Copy download data for use on GET_STATUS */
|
||||
prog.blocknum = req->wValue;
|
||||
prog.len = *len;
|
||||
memcpy(prog.buf, *buf, *len);
|
||||
usbdfu_state = STATE_DFU_DNLOAD_SYNC;
|
||||
return 1;
|
||||
}
|
||||
case DFU_CLRSTATUS:
|
||||
/* Clear error and return to dfuIDLE */
|
||||
if(usbdfu_state == STATE_DFU_ERROR)
|
||||
usbdfu_state = STATE_DFU_IDLE;
|
||||
return 1;
|
||||
case DFU_ABORT:
|
||||
/* Abort returns to dfuIDLE state */
|
||||
usbdfu_state = STATE_DFU_IDLE;
|
||||
return 1;
|
||||
case DFU_UPLOAD:
|
||||
/* Upload not supported for now */
|
||||
return 0;
|
||||
case DFU_GETSTATUS: {
|
||||
u32 bwPollTimeout = 0; /* 24-bit integer in DFU class spec */
|
||||
|
||||
(*buf)[0] = usbdfu_getstatus(&bwPollTimeout);
|
||||
(*buf)[1] = bwPollTimeout & 0xFF;
|
||||
(*buf)[2] = (bwPollTimeout >> 8) & 0xFF;
|
||||
(*buf)[3] = (bwPollTimeout >> 16) & 0xFF;
|
||||
(*buf)[4] = usbdfu_state;
|
||||
(*buf)[5] = 0; /* iString not used here */
|
||||
*len = 6;
|
||||
|
||||
*complete = usbdfu_getstatus_complete;
|
||||
|
||||
return 1;
|
||||
}
|
||||
case DFU_GETSTATE:
|
||||
/* Return state with no state transision */
|
||||
*buf[0] = usbdfu_state;
|
||||
*len = 1;
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int main(void)
|
||||
{
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
|
||||
if(gpio_get(GPIOB, GPIO12)) {
|
||||
/* Boot the application if it's valid */
|
||||
if((*(volatile u32*)APP_ADDRESS & 0x2FFE0000) == 0x20000000) {
|
||||
/* Set vector table base address */
|
||||
SCB_VTOR = APP_ADDRESS & 0xFFFF;
|
||||
/* Initialise master stack pointer */
|
||||
asm volatile ("msr msp, %0"::"g"
|
||||
(*(volatile u32*)APP_ADDRESS));
|
||||
/* Jump to application */
|
||||
(*(void(**)())(APP_ADDRESS + 4))();
|
||||
}
|
||||
}
|
||||
|
||||
if ((FLASH_WRPR & 0x03) != 0x00) {
|
||||
flash_unlock();
|
||||
FLASH_CR = 0;
|
||||
flash_erase_option_bytes();
|
||||
flash_program_option_bytes(FLASH_OBP_RDP, FLASH_OBP_RDP_KEY);
|
||||
flash_program_option_bytes(FLASH_OBP_WRP10, 0x03FC);
|
||||
}
|
||||
|
||||
rcc_clock_setup_in_hse_8mhz_out_72mhz();
|
||||
|
||||
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
|
||||
|
||||
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, 0, GPIO8);
|
||||
|
||||
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, GPIO11);
|
||||
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
|
||||
systick_set_reload(900000);
|
||||
systick_interrupt_enable();
|
||||
systick_counter_enable();
|
||||
gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
|
||||
GPIO_CNF_INPUT_FLOAT, GPIO2 | GPIO10);
|
||||
|
||||
get_dev_unique_id(serial_no);
|
||||
|
||||
usbdev = usbd_init(&stm32f103_usb_driver,
|
||||
&dev, &config, usb_strings, 4);
|
||||
usbd_set_control_buffer_size(usbdev, sizeof(usbd_control_buffer));
|
||||
usbd_register_control_callback(usbdev,
|
||||
USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
|
||||
USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
|
||||
usbdfu_control_request);
|
||||
|
||||
gpio_set(GPIOA, GPIO8);
|
||||
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
|
||||
|
||||
while (1)
|
||||
usbd_poll(usbdev);
|
||||
}
|
||||
|
||||
static char *get_dev_unique_id(char *s)
|
||||
{
|
||||
volatile uint32_t *unique_id_p = (volatile uint32_t *)0x1FFFF7E8;
|
||||
uint32_t unique_id = *unique_id_p +
|
||||
*(unique_id_p + 1) +
|
||||
*(unique_id_p + 2);
|
||||
int i;
|
||||
|
||||
/* 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 sys_tick_handler()
|
||||
{
|
||||
gpio_toggle(GPIOB, GPIO11); /* LED2 on/off */
|
||||
}
|
||||
|
|
@ -3,22 +3,33 @@ CC = $(CROSS_COMPILE)gcc
|
|||
OBJCOPY = $(CROSS_COMPILE)objcopy
|
||||
|
||||
CFLAGS += -mcpu=cortex-m3 -mthumb \
|
||||
-DSTM32F1 -I../libopencm3/include
|
||||
LDFLAGS = -lopencm3_stm32f1 -Wl,--defsym,_stack=0x20005000 \
|
||||
-Wl,-T,platforms/stm32/blackmagic.ld -nostartfiles -lc -lnosys \
|
||||
-DSTM32F1 -DDISCOVERY_STLINK -I../libopencm3/include
|
||||
LDFLAGS_BOOT = -lopencm3_stm32f1 -Wl,--defsym,_stack=0x20005000 \
|
||||
-Wl,-T,platforms/stm32/stlink.ld -nostartfiles -lc -lnosys \
|
||||
-Wl,-Map=mapfile -mthumb -mcpu=cortex-m3 -Wl,-gc-sections \
|
||||
-L../libopencm3/lib
|
||||
LDFLAGS = $(LDFLAGS_BOOT) -Wl,-Ttext=0x8002000
|
||||
|
||||
VPATH += platforms/stm32
|
||||
|
||||
SRC += cdcacm.c \
|
||||
platform.c \
|
||||
usbuart.c \
|
||||
|
||||
all: blackmagic.bin
|
||||
all: blackmagic.bin blackmagic_dfu.bin blackmagic_dfu.hex
|
||||
|
||||
blackmagic.bin: blackmagic
|
||||
$(OBJCOPY) -O binary $^ $@
|
||||
|
||||
host_clean:
|
||||
-rm blackmagic.bin
|
||||
blackmagic_dfu: usbdfu.o
|
||||
$(CC) $^ -o $@ $(LDFLAGS_BOOT)
|
||||
|
||||
blackmagic_dfu.bin: blackmagic_dfu
|
||||
$(OBJCOPY) -O binary $^ $@
|
||||
|
||||
blackmagic_dfu.hex: blackmagic_dfu
|
||||
$(OBJCOPY) -O ihex $^ $@
|
||||
|
||||
host_clean:
|
||||
-rm blackmagic.bin blackmagic_dfu blackmagic_dfu.bin blackmagic_dfu.hex
|
||||
|
||||
|
|
|
@ -0,0 +1,11 @@
|
|||
Find a description how to modify a Discovery Board to use it's Stlink as
|
||||
black magic debug at
|
||||
http://embdev.net/articles/STM_Discovery_as_Black_Magic_Probe
|
||||
|
||||
Differences between V1/V2
|
||||
|
||||
V1 V2
|
||||
ID Pins PC13/14 unconnected PC 13 pulled low
|
||||
LED STLINK PA8, active High PA9, Dual Led
|
||||
MCO Out NA PA8
|
||||
RESET(Target) T_JRST(PB1) NRST (PB0)
|
|
@ -1,309 +0,0 @@
|
|||
/*
|
||||
* 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 a the USB Communications Device Class - Abstract
|
||||
* Control Model (CDC-ACM) as defined in CDC PSTN subclass 1.2.
|
||||
* A Device Firmware Upgrade (DFU 1.1) class interface is provided for
|
||||
* field firmware upgrade.
|
||||
*
|
||||
* The device's unique id is used as the USB serial number string.
|
||||
*/
|
||||
|
||||
#include <libopencm3/stm32/f1/rcc.h>
|
||||
#include <libopencm3/stm32/f1/nvic.h>
|
||||
#include <libopencm3/stm32/exti.h>
|
||||
#include <libopencm3/stm32/f1/gpio.h>
|
||||
#include <libopencm3/usb/usbd.h>
|
||||
#include <libopencm3/usb/cdc.h>
|
||||
#include <libopencm3/cm3/scb.h>
|
||||
#include <libopencm3/usb/dfu.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
usbd_device *usbdev;
|
||||
|
||||
static char *get_dev_unique_id(char *serial_no);
|
||||
|
||||
static int configured;
|
||||
static int cdcacm_gdb_dtr = 1;
|
||||
|
||||
static const struct usb_device_descriptor dev = {
|
||||
.bLength = USB_DT_DEVICE_SIZE,
|
||||
.bDescriptorType = USB_DT_DEVICE,
|
||||
.bcdUSB = 0x0200,
|
||||
.bDeviceClass = 0xEF, /* Miscellaneous Device */
|
||||
.bDeviceSubClass = 2, /* Common Class */
|
||||
.bDeviceProtocol = 1, /* Interface Association */
|
||||
.bMaxPacketSize0 = 64,
|
||||
.idVendor = 0x1D50,
|
||||
.idProduct = 0x6018,
|
||||
.bcdDevice = 0x0100,
|
||||
.iManufacturer = 1,
|
||||
.iProduct = 2,
|
||||
.iSerialNumber = 3,
|
||||
.bNumConfigurations = 1,
|
||||
};
|
||||
|
||||
/* This notification endpoint isn't implemented. According to CDC spec its
|
||||
* optional, but its absence causes a NULL pointer dereference in Linux cdc_acm
|
||||
* driver. */
|
||||
static const struct usb_endpoint_descriptor gdb_comm_endp[] = {{
|
||||
.bLength = USB_DT_ENDPOINT_SIZE,
|
||||
.bDescriptorType = USB_DT_ENDPOINT,
|
||||
.bEndpointAddress = 0x82,
|
||||
.bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT,
|
||||
.wMaxPacketSize = 16,
|
||||
.bInterval = 255,
|
||||
}};
|
||||
|
||||
static const struct usb_endpoint_descriptor gdb_data_endp[] = {{
|
||||
.bLength = USB_DT_ENDPOINT_SIZE,
|
||||
.bDescriptorType = USB_DT_ENDPOINT,
|
||||
.bEndpointAddress = 0x01,
|
||||
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
|
||||
.wMaxPacketSize = CDCACM_PACKET_SIZE,
|
||||
.bInterval = 1,
|
||||
}, {
|
||||
.bLength = USB_DT_ENDPOINT_SIZE,
|
||||
.bDescriptorType = USB_DT_ENDPOINT,
|
||||
.bEndpointAddress = 0x81,
|
||||
.bmAttributes = USB_ENDPOINT_ATTR_BULK,
|
||||
.wMaxPacketSize = CDCACM_PACKET_SIZE,
|
||||
.bInterval = 1,
|
||||
}};
|
||||
|
||||
static const struct {
|
||||
struct usb_cdc_header_descriptor header;
|
||||
struct usb_cdc_call_management_descriptor call_mgmt;
|
||||
struct usb_cdc_acm_descriptor acm;
|
||||
struct usb_cdc_union_descriptor cdc_union;
|
||||
} __attribute__((packed)) gdb_cdcacm_functional_descriptors = {
|
||||
.header = {
|
||||
.bFunctionLength = sizeof(struct usb_cdc_header_descriptor),
|
||||
.bDescriptorType = CS_INTERFACE,
|
||||
.bDescriptorSubtype = USB_CDC_TYPE_HEADER,
|
||||
.bcdCDC = 0x0110,
|
||||
},
|
||||
.call_mgmt = {
|
||||
.bFunctionLength =
|
||||
sizeof(struct usb_cdc_call_management_descriptor),
|
||||
.bDescriptorType = CS_INTERFACE,
|
||||
.bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT,
|
||||
.bmCapabilities = 0,
|
||||
.bDataInterface = 1,
|
||||
},
|
||||
.acm = {
|
||||
.bFunctionLength = sizeof(struct usb_cdc_acm_descriptor),
|
||||
.bDescriptorType = CS_INTERFACE,
|
||||
.bDescriptorSubtype = USB_CDC_TYPE_ACM,
|
||||
.bmCapabilities = 2, /* SET_LINE_CODING supported */
|
||||
},
|
||||
.cdc_union = {
|
||||
.bFunctionLength = sizeof(struct usb_cdc_union_descriptor),
|
||||
.bDescriptorType = CS_INTERFACE,
|
||||
.bDescriptorSubtype = USB_CDC_TYPE_UNION,
|
||||
.bControlInterface = 0,
|
||||
.bSubordinateInterface0 = 1,
|
||||
}
|
||||
};
|
||||
|
||||
static const struct usb_interface_descriptor gdb_comm_iface[] = {{
|
||||
.bLength = USB_DT_INTERFACE_SIZE,
|
||||
.bDescriptorType = USB_DT_INTERFACE,
|
||||
.bInterfaceNumber = 0,
|
||||
.bAlternateSetting = 0,
|
||||
.bNumEndpoints = 1,
|
||||
.bInterfaceClass = USB_CLASS_CDC,
|
||||
.bInterfaceSubClass = USB_CDC_SUBCLASS_ACM,
|
||||
.bInterfaceProtocol = USB_CDC_PROTOCOL_AT,
|
||||
.iInterface = 4,
|
||||
|
||||
.endpoint = gdb_comm_endp,
|
||||
|
||||
.extra = &gdb_cdcacm_functional_descriptors,
|
||||
.extralen = sizeof(gdb_cdcacm_functional_descriptors)
|
||||
}};
|
||||
|
||||
static const struct usb_interface_descriptor gdb_data_iface[] = {{
|
||||
.bLength = USB_DT_INTERFACE_SIZE,
|
||||
.bDescriptorType = USB_DT_INTERFACE,
|
||||
.bInterfaceNumber = 1,
|
||||
.bAlternateSetting = 0,
|
||||
.bNumEndpoints = 2,
|
||||
.bInterfaceClass = USB_CLASS_DATA,
|
||||
.bInterfaceSubClass = 0,
|
||||
.bInterfaceProtocol = 0,
|
||||
.iInterface = 0,
|
||||
|
||||
.endpoint = gdb_data_endp,
|
||||
}};
|
||||
|
||||
static const struct usb_iface_assoc_descriptor gdb_assoc = {
|
||||
.bLength = USB_DT_INTERFACE_ASSOCIATION_SIZE,
|
||||
.bDescriptorType = USB_DT_INTERFACE_ASSOCIATION,
|
||||
.bFirstInterface = 0,
|
||||
.bInterfaceCount = 2,
|
||||
.bFunctionClass = USB_CLASS_CDC,
|
||||
.bFunctionSubClass = USB_CDC_SUBCLASS_ACM,
|
||||
.bFunctionProtocol = USB_CDC_PROTOCOL_AT,
|
||||
.iFunction = 0,
|
||||
};
|
||||
|
||||
static const struct usb_interface ifaces[] = {{
|
||||
.num_altsetting = 1,
|
||||
.iface_assoc = &gdb_assoc,
|
||||
.altsetting = gdb_comm_iface,
|
||||
}, {
|
||||
.num_altsetting = 1,
|
||||
.altsetting = gdb_data_iface,
|
||||
}};
|
||||
|
||||
static const struct usb_config_descriptor config = {
|
||||
.bLength = USB_DT_CONFIGURATION_SIZE,
|
||||
.bDescriptorType = USB_DT_CONFIGURATION,
|
||||
.wTotalLength = 0,
|
||||
.bNumInterfaces = 2,
|
||||
.bConfigurationValue = 1,
|
||||
.iConfiguration = 0,
|
||||
.bmAttributes = 0x80,
|
||||
.bMaxPower = 0x32,
|
||||
|
||||
.interface = ifaces,
|
||||
};
|
||||
|
||||
char serial_no[9];
|
||||
|
||||
static const char *usb_strings[] = {
|
||||
"Black Sphere Technologies",
|
||||
"Black Magic Probe",
|
||||
serial_no,
|
||||
"Black Magic GDB Server",
|
||||
};
|
||||
|
||||
static int cdcacm_control_request(usbd_device *dev,
|
||||
struct usb_setup_data *req, uint8_t **buf, uint16_t *len,
|
||||
void (**complete)(usbd_device *dev, struct usb_setup_data *req))
|
||||
{
|
||||
(void)dev;
|
||||
(void)complete;
|
||||
(void)buf;
|
||||
(void)len;
|
||||
|
||||
switch(req->bRequest) {
|
||||
case USB_CDC_REQ_SET_CONTROL_LINE_STATE:
|
||||
/* Ignore if not for GDB interface */
|
||||
if(req->wIndex != 0)
|
||||
return 1;
|
||||
|
||||
cdcacm_gdb_dtr = req->wValue & 1;
|
||||
|
||||
return 1;
|
||||
case USB_CDC_REQ_SET_LINE_CODING:
|
||||
if(*len < sizeof(struct usb_cdc_line_coding))
|
||||
return 0;
|
||||
|
||||
switch(req->wIndex) {
|
||||
case 0:
|
||||
return 1; /* Ignore on GDB Port */
|
||||
default:
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int cdcacm_get_config(void)
|
||||
{
|
||||
return configured;
|
||||
}
|
||||
|
||||
int cdcacm_get_dtr(void)
|
||||
{
|
||||
return cdcacm_gdb_dtr;
|
||||
}
|
||||
|
||||
static void cdcacm_set_config(usbd_device *dev, u16 wValue)
|
||||
{
|
||||
configured = wValue;
|
||||
|
||||
/* GDB interface */
|
||||
usbd_ep_setup(dev, 0x01, USB_ENDPOINT_ATTR_BULK, CDCACM_PACKET_SIZE, NULL);
|
||||
usbd_ep_setup(dev, 0x81, USB_ENDPOINT_ATTR_BULK, CDCACM_PACKET_SIZE, NULL);
|
||||
usbd_ep_setup(dev, 0x82, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL);
|
||||
|
||||
usbd_register_control_callback(dev,
|
||||
USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
|
||||
USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
|
||||
cdcacm_control_request);
|
||||
|
||||
/* Notify the host that DCD is asserted.
|
||||
* Allows the use of /dev/tty* devices on *BSD/MacOS
|
||||
*/
|
||||
char buf[10];
|
||||
struct usb_cdc_notification *notif = (void*)buf;
|
||||
/* We echo signals back to host as notification */
|
||||
notif->bmRequestType = 0xA1;
|
||||
notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE;
|
||||
notif->wValue = 0;
|
||||
notif->wIndex = 0;
|
||||
notif->wLength = 2;
|
||||
buf[8] = 3; /* DCD | DSR */
|
||||
buf[9] = 0;
|
||||
usbd_ep_write_packet(dev, 0x82, buf, 10);
|
||||
}
|
||||
|
||||
void cdcacm_init(void)
|
||||
{
|
||||
void exti15_10_isr(void);
|
||||
|
||||
get_dev_unique_id(serial_no);
|
||||
|
||||
usbdev = usbd_init(&stm32f103_usb_driver, &dev, &config, usb_strings, 4);
|
||||
usbd_register_set_config_callback(usbdev, cdcacm_set_config);
|
||||
|
||||
nvic_enable_irq(NVIC_USB_LP_CAN_RX0_IRQ);
|
||||
}
|
||||
|
||||
void usb_lp_can_rx0_isr(void)
|
||||
{
|
||||
usbd_poll(usbdev);
|
||||
}
|
||||
|
||||
static char *get_dev_unique_id(char *s)
|
||||
{
|
||||
volatile uint32_t *unique_id_p = (volatile uint32_t *)0x1FFFF7E8;
|
||||
uint32_t unique_id = *unique_id_p +
|
||||
*(unique_id_p + 1) +
|
||||
*(unique_id_p + 2);
|
||||
int i;
|
||||
|
||||
/* 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;
|
||||
}
|
||||
|
|
@ -25,13 +25,14 @@
|
|||
#include <libopencm3/stm32/f1/rcc.h>
|
||||
#include <libopencm3/cm3/systick.h>
|
||||
#include <libopencm3/cm3/scb.h>
|
||||
#include <libopencm3/stm32/f1/nvic.h>
|
||||
#include <libopencm3/cm3/nvic.h>
|
||||
#include <libopencm3/stm32/usart.h>
|
||||
#include <libopencm3/usb/usbd.h>
|
||||
#include <libopencm3/stm32/f1/adc.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "jtag_scan.h"
|
||||
#include <usbuart.h>
|
||||
|
||||
#include <ctype.h>
|
||||
|
||||
|
@ -40,6 +41,34 @@ volatile uint32_t timeout_counter;
|
|||
|
||||
jmp_buf fatal_error_jmpbuf;
|
||||
|
||||
uint16_t led_idle_run;
|
||||
/* Pins PC[14:13] are used to detect hardware revision. Read
|
||||
* 11 for STLink V1 e.g. on VL Discovery, tag as hwversion 0
|
||||
* 10 for STLink V2 e.g. on F4 Discovery, tag as hwversion 1
|
||||
*/
|
||||
int platform_hwversion(void)
|
||||
{
|
||||
static int hwversion = -1;
|
||||
int i;
|
||||
if (hwversion == -1) {
|
||||
gpio_set_mode(GPIOC, GPIO_MODE_INPUT,
|
||||
GPIO_CNF_INPUT_PULL_UPDOWN,
|
||||
GPIO14 | GPIO13);
|
||||
gpio_set(GPIOC, GPIO14 | GPIO13);
|
||||
for (i = 0; i<10; i++)
|
||||
hwversion = ~(gpio_get(GPIOC, GPIO14 | GPIO13) >> 13) & 3;
|
||||
switch (hwversion)
|
||||
{
|
||||
case 0:
|
||||
led_idle_run = GPIO8;
|
||||
break;
|
||||
default:
|
||||
led_idle_run = GPIO9;
|
||||
}
|
||||
}
|
||||
return hwversion;
|
||||
}
|
||||
|
||||
int platform_init(void)
|
||||
{
|
||||
rcc_clock_setup_in_hse_8mhz_out_72mhz();
|
||||
|
@ -48,7 +77,19 @@ int platform_init(void)
|
|||
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
|
||||
|
||||
/* On Rev 1 unconditionally activate MCO on PORTA8 with HSE
|
||||
* platform_hwversion() also needed to initialize led_idle_run!
|
||||
*/
|
||||
if (platform_hwversion() == 1)
|
||||
{
|
||||
RCC_CFGR &= ~( 0xf<< 24);
|
||||
RCC_CFGR |= (RCC_CFGR_MCO_HSECLK << 24);
|
||||
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
|
||||
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO8);
|
||||
}
|
||||
/* Setup GPIO ports */
|
||||
gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_50_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, TMS_PIN);
|
||||
|
@ -58,14 +99,20 @@ int platform_init(void)
|
|||
GPIO_CNF_OUTPUT_PUSHPULL, TDI_PIN);
|
||||
|
||||
gpio_set_mode(LED_PORT, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, LED_IDLE_RUN);
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, led_idle_run);
|
||||
|
||||
/* Setup heartbeat timer */
|
||||
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
|
||||
systick_set_reload(900000); /* Interrupt us at 10 Hz */
|
||||
SCB_SHPR(11) &= ~((15 << 4) & 0xff);
|
||||
SCB_SHPR(11) |= ((14 << 4) & 0xff);
|
||||
systick_interrupt_enable();
|
||||
systick_counter_enable();
|
||||
|
||||
usbuart_init();
|
||||
|
||||
SCB_VTOR = 0x2000; // Relocate interrupt vector table here
|
||||
|
||||
cdcacm_init();
|
||||
|
||||
jtag_scan(NULL);
|
||||
|
@ -82,7 +129,7 @@ void platform_delay(uint32_t delay)
|
|||
void sys_tick_handler(void)
|
||||
{
|
||||
if(running_status)
|
||||
gpio_toggle(LED_PORT, LED_IDLE_RUN);
|
||||
gpio_toggle(LED_PORT, led_idle_run);
|
||||
|
||||
if(timeout_counter)
|
||||
timeout_counter--;
|
||||
|
@ -100,3 +147,29 @@ const char *platform_target_voltage(void)
|
|||
{
|
||||
return "unknown";
|
||||
}
|
||||
|
||||
void disconnect_usb(void)
|
||||
{
|
||||
/* Disconnect USB cable by resetting USB Device and pulling USB_DP low*/
|
||||
rcc_peripheral_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN);
|
||||
rcc_peripheral_clear_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
|
||||
gpio_clear(GPIOA, GPIO12);
|
||||
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_OPENDRAIN, GPIO12);
|
||||
}
|
||||
|
||||
void assert_boot_pin(void)
|
||||
{
|
||||
uint32_t crl = GPIOA_CRL;
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
|
||||
/* Enable Pull on GPIOA1. We don't rely on the external pin
|
||||
* really pulled, but only on the value of the CNF register
|
||||
* changed from the reset value
|
||||
*/
|
||||
crl &= 0xffffff0f;
|
||||
crl |= 0x80;
|
||||
GPIOA_CRL = crl;
|
||||
}
|
||||
void setup_vbus_irq(void){};
|
||||
|
|
|
@ -33,10 +33,13 @@
|
|||
#include "gdb_packet.h"
|
||||
|
||||
#define INLINE_GPIO
|
||||
#define CDCACM_PACKET_SIZE 64
|
||||
#define BOARD_IDENT "Black Magic Probe (STLINK), (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")"
|
||||
#define DFU_IDENT "Black Magic Firmware Upgrade (STLINK)"
|
||||
|
||||
extern usbd_device *usbdev;
|
||||
#define CDCACM_PACKET_SIZE 64
|
||||
#define CDCACM_GDB_ENDPOINT 1
|
||||
#define CDCACM_UART_ENDPOINT 3
|
||||
|
||||
/* Important pin mappings for STM32 implementation:
|
||||
*
|
||||
|
@ -75,10 +78,44 @@ extern usbd_device *usbdev;
|
|||
#define SWCLK_PIN TCK_PIN
|
||||
|
||||
#define LED_PORT GPIOA
|
||||
/* The value line discovery board stlink has it's led on PA8
|
||||
* All other stlinks have the led connected to PA9 instead and MCO to PA8
|
||||
/* Use PC14 for a "dummy" uart led. So we can observere at least with scope*/
|
||||
#define LED_PORT_UART GPIOC
|
||||
#define LED_UART GPIO14
|
||||
|
||||
#define TMS_SET_MODE() \
|
||||
gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_50_MHZ, \
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, TMS_PIN);
|
||||
#define SWDIO_MODE_FLOAT() \
|
||||
gpio_set_mode(SWDIO_PORT, GPIO_MODE_INPUT, \
|
||||
GPIO_CNF_INPUT_FLOAT, SWDIO_PIN);
|
||||
#define SWDIO_MODE_DRIVE() \
|
||||
gpio_set_mode(SWDIO_PORT, GPIO_MODE_OUTPUT_50_MHZ, \
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, SWDIO_PIN);
|
||||
|
||||
#define UART_PIN_SETUP() \
|
||||
gpio_set_mode(USBUSART_PORT, GPIO_MODE_OUTPUT_2_MHZ, \
|
||||
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, USBUSART_TX_PIN);
|
||||
|
||||
#define USB_DRIVER stm32f103_usb_driver
|
||||
#define USB_IRQ NVIC_USB_LP_CAN_RX0_IRQ
|
||||
#define USB_ISR usb_lp_can_rx0_isr
|
||||
/* Interrupt priorities. Low numbers are high priority.
|
||||
* For now USART2 preempts USB which may spin while buffer is drained.
|
||||
* TIM3 is used for traceswo capture and must be highest priority.
|
||||
*/
|
||||
#define LED_IDLE_RUN GPIO9
|
||||
#define IRQ_PRI_USB (2 << 4)
|
||||
#define IRQ_PRI_USBUSART (1 << 4)
|
||||
#define IRQ_PRI_USB_VBUS (14 << 4)
|
||||
#define IRQ_PRI_TIM3 (0 << 4)
|
||||
|
||||
#define USBUSART USART2
|
||||
#define USBUSART_CR1 USART2_CR1
|
||||
#define USBUSART_IRQ NVIC_USART2_IRQ
|
||||
#define USBUSART_APB_ENR RCC_APB1ENR
|
||||
#define USBUSART_CLK_ENABLE RCC_APB1ENR_USART2EN
|
||||
#define USBUSART_PORT GPIOA
|
||||
#define USBUSART_TX_PIN GPIO2
|
||||
#define USBUSART_ISR usart2_isr
|
||||
|
||||
#define DEBUG(...)
|
||||
|
||||
|
@ -96,8 +133,9 @@ extern const char *morse_msg;
|
|||
gpio_clear((port), (pin)); \
|
||||
} while(0)
|
||||
|
||||
extern uint16_t led_idle_run;
|
||||
#define SET_RUN_STATE(state) {running_status = (state);}
|
||||
#define SET_IDLE_STATE(state) {gpio_set_val(LED_PORT, LED_IDLE_RUN, state);}
|
||||
#define SET_IDLE_STATE(state) {gpio_set_val(LED_PORT, led_idle_run, state);}
|
||||
|
||||
#define PLATFORM_SET_FATAL_ERROR_RECOVERY() {setjmp(fatal_error_jmpbuf);}
|
||||
#define PLATFORM_FATAL_ERROR(error) { \
|
||||
|
@ -119,6 +157,9 @@ void cdcacm_init(void);
|
|||
int cdcacm_get_config(void);
|
||||
int cdcacm_get_dtr(void);
|
||||
|
||||
/* <platform.h> */
|
||||
void uart_usb_buf_drain(uint8_t ep);
|
||||
|
||||
/* Use newlib provided integer only stdio functions */
|
||||
#define sscanf siscanf
|
||||
#define sprintf siprintf
|
||||
|
@ -146,3 +187,5 @@ static inline u16 _gpio_get(u32 gpioport, u16 gpios)
|
|||
|
||||
#endif
|
||||
|
||||
void disconnect_usb(void);
|
||||
void assert_boot_pin(void);
|
||||
|
|
|
@ -26,10 +26,7 @@
|
|||
* The device's unique id is used as the USB serial number string.
|
||||
*/
|
||||
|
||||
#include <libopencm3/stm32/f1/rcc.h>
|
||||
#include <libopencm3/cm3/nvic.h>
|
||||
#include <libopencm3/stm32/exti.h>
|
||||
#include <libopencm3/stm32/f1/gpio.h>
|
||||
#include <libopencm3/usb/usbd.h>
|
||||
#include <libopencm3/usb/cdc.h>
|
||||
#include <libopencm3/cm3/scb.h>
|
||||
|
@ -37,8 +34,11 @@
|
|||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "traceswo.h"
|
||||
#include "usbuart.h"
|
||||
#include "gdb_if.h"
|
||||
#if defined(PLATFORM_HAS_TRACESWO)
|
||||
#include <traceswo.h>
|
||||
#endif
|
||||
#include <usbuart.h>
|
||||
|
||||
#define DFU_IF_NO 4
|
||||
|
||||
|
@ -310,6 +310,7 @@ static const struct usb_iface_assoc_descriptor dfu_assoc = {
|
|||
.iFunction = 6,
|
||||
};
|
||||
|
||||
#if defined(PLATFORM_HAS_TRACESWO)
|
||||
static const struct usb_endpoint_descriptor trace_endp[] = {{
|
||||
.bLength = USB_DT_ENDPOINT_SIZE,
|
||||
.bDescriptorType = USB_DT_ENDPOINT,
|
||||
|
@ -343,6 +344,7 @@ static const struct usb_iface_assoc_descriptor trace_assoc = {
|
|||
.bFunctionProtocol = 0xFF,
|
||||
.iFunction = 7,
|
||||
};
|
||||
#endif
|
||||
|
||||
static const struct usb_interface ifaces[] = {{
|
||||
.num_altsetting = 1,
|
||||
|
@ -362,17 +364,23 @@ static const struct usb_interface ifaces[] = {{
|
|||
.num_altsetting = 1,
|
||||
.iface_assoc = &dfu_assoc,
|
||||
.altsetting = &dfu_iface,
|
||||
#if defined(PLATFORM_HAS_TRACESWO)
|
||||
}, {
|
||||
.num_altsetting = 1,
|
||||
.iface_assoc = &trace_assoc,
|
||||
.altsetting = &trace_iface,
|
||||
#endif
|
||||
}};
|
||||
|
||||
static const struct usb_config_descriptor config = {
|
||||
.bLength = USB_DT_CONFIGURATION_SIZE,
|
||||
.bDescriptorType = USB_DT_CONFIGURATION,
|
||||
.wTotalLength = 0,
|
||||
#if defined(PLATFORM_HAS_TRACESWO)
|
||||
.bNumInterfaces = 6,
|
||||
#else
|
||||
.bNumInterfaces = 5,
|
||||
#endif
|
||||
.bConfigurationValue = 1,
|
||||
.iConfiguration = 0,
|
||||
.bmAttributes = 0x80,
|
||||
|
@ -385,12 +393,14 @@ char serial_no[9];
|
|||
|
||||
static const char *usb_strings[] = {
|
||||
"Black Sphere Technologies",
|
||||
"Black Magic Probe",
|
||||
BOARD_IDENT,
|
||||
serial_no,
|
||||
"Black Magic GDB Server",
|
||||
"Black Magic UART Port",
|
||||
"Black Magic Firmware Upgrade",
|
||||
DFU_IDENT,
|
||||
#if defined(PLATFORM_HAS_TRACESWO)
|
||||
"Black Magic Trace Capture",
|
||||
#endif
|
||||
};
|
||||
|
||||
static void dfu_detach_complete(usbd_device *dev, struct usb_setup_data *req)
|
||||
|
@ -399,12 +409,10 @@ static void dfu_detach_complete(usbd_device *dev, struct usb_setup_data *req)
|
|||
(void)req;
|
||||
|
||||
/* Disconnect USB cable */
|
||||
gpio_set_mode(USB_PU_PORT, GPIO_MODE_INPUT, 0, USB_PU_PIN);
|
||||
disconnect_usb();
|
||||
|
||||
/* Assert boot-request pin */
|
||||
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, GPIO12);
|
||||
gpio_clear(GPIOB, GPIO12);
|
||||
assert_boot_pin();
|
||||
|
||||
/* Reset core to enter bootloader */
|
||||
scb_reset_core();
|
||||
|
@ -478,7 +486,7 @@ static void cdcacm_set_config(usbd_device *dev, u16 wValue)
|
|||
|
||||
/* GDB interface */
|
||||
usbd_ep_setup(dev, 0x01, USB_ENDPOINT_ATTR_BULK,
|
||||
CDCACM_PACKET_SIZE, NULL);
|
||||
CDCACM_PACKET_SIZE, gdb_usb_out_cb);
|
||||
usbd_ep_setup(dev, 0x81, USB_ENDPOINT_ATTR_BULK,
|
||||
CDCACM_PACKET_SIZE, NULL);
|
||||
usbd_ep_setup(dev, 0x82, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL);
|
||||
|
@ -490,9 +498,11 @@ static void cdcacm_set_config(usbd_device *dev, u16 wValue)
|
|||
CDCACM_PACKET_SIZE, usbuart_usb_in_cb);
|
||||
usbd_ep_setup(dev, 0x84, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL);
|
||||
|
||||
#if defined(PLATFORM_HAS_TRACESWO)
|
||||
/* Trace interface */
|
||||
usbd_ep_setup(dev, 0x85, USB_ENDPOINT_ATTR_BULK,
|
||||
64, trace_buf_drain);
|
||||
#endif
|
||||
|
||||
usbd_register_control_callback(dev,
|
||||
USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
|
||||
|
@ -526,53 +536,27 @@ void cdcacm_init(void)
|
|||
|
||||
get_dev_unique_id(serial_no);
|
||||
|
||||
usbdev = usbd_init(&stm32f103_usb_driver,
|
||||
&dev, &config, usb_strings, 7);
|
||||
usbdev = usbd_init(&USB_DRIVER, &dev, &config, usb_strings, sizeof(usb_strings)/sizeof(char *));
|
||||
usbd_set_control_buffer_size(usbdev, sizeof(usbd_control_buffer));
|
||||
usbd_register_set_config_callback(usbdev, cdcacm_set_config);
|
||||
|
||||
nvic_set_priority(NVIC_USB_LP_CAN_RX0_IRQ, IRQ_PRI_USB);
|
||||
nvic_enable_irq(NVIC_USB_LP_CAN_RX0_IRQ);
|
||||
nvic_set_priority(USB_VBUS_IRQ, IRQ_PRI_USB_VBUS);
|
||||
nvic_enable_irq(USB_VBUS_IRQ);
|
||||
|
||||
gpio_set(USB_VBUS_PORT, USB_VBUS_PIN);
|
||||
gpio_set(USB_PU_PORT, USB_PU_PIN);
|
||||
|
||||
gpio_set_mode(USB_VBUS_PORT, GPIO_MODE_INPUT,
|
||||
GPIO_CNF_INPUT_PULL_UPDOWN, USB_VBUS_PIN);
|
||||
|
||||
/* Configure EXTI for USB VBUS monitor */
|
||||
exti_select_source(USB_VBUS_PIN, USB_VBUS_PORT);
|
||||
exti_set_trigger(USB_VBUS_PIN, EXTI_TRIGGER_BOTH);
|
||||
exti_enable_request(USB_VBUS_PIN);
|
||||
|
||||
exti15_10_isr();
|
||||
nvic_set_priority(USB_IRQ, IRQ_PRI_USB);
|
||||
nvic_enable_irq(USB_IRQ);
|
||||
setup_vbus_irq();
|
||||
}
|
||||
|
||||
void usb_lp_can_rx0_isr(void)
|
||||
void USB_ISR(void)
|
||||
{
|
||||
usbd_poll(usbdev);
|
||||
}
|
||||
|
||||
void exti15_10_isr(void)
|
||||
{
|
||||
if (gpio_get(USB_VBUS_PORT, USB_VBUS_PIN)) {
|
||||
/* Drive pull-up high if VBUS connected */
|
||||
gpio_set_mode(USB_PU_PORT, GPIO_MODE_OUTPUT_10_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, USB_PU_PIN);
|
||||
} else {
|
||||
/* Allow pull-up to float if VBUS disconnected */
|
||||
gpio_set_mode(USB_PU_PORT, GPIO_MODE_INPUT,
|
||||
GPIO_CNF_INPUT_FLOAT, USB_PU_PIN);
|
||||
}
|
||||
|
||||
exti_reset_request(USB_VBUS_PIN);
|
||||
}
|
||||
|
||||
static char *get_dev_unique_id(char *s)
|
||||
{
|
||||
#if defined(STM32F4)
|
||||
volatile uint32_t *unique_id_p = (volatile uint32_t *)0x1FFF7A10;
|
||||
#else
|
||||
volatile uint32_t *unique_id_p = (volatile uint32_t *)0x1FFFF7E8;
|
||||
#endif
|
||||
uint32_t unique_id = *unique_id_p +
|
||||
*(unique_id_p + 1) +
|
||||
*(unique_id_p + 2);
|
||||
|
@ -589,4 +573,3 @@ static char *get_dev_unique_id(char *s)
|
|||
|
||||
return s;
|
||||
}
|
||||
|
|
@ -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 = 1024K
|
||||
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
}
|
||||
|
||||
/* Include the common ld script from libopenstm32. */
|
||||
INCLUDE libopencm3_stm32f4.ld
|
||||
|
|
@ -28,9 +28,11 @@
|
|||
#include "gdb_if.h"
|
||||
|
||||
static uint32_t count_out;
|
||||
static uint32_t count_new;
|
||||
static uint32_t count_in;
|
||||
static uint32_t out_ptr;
|
||||
static uint8_t buffer_out[CDCACM_PACKET_SIZE];
|
||||
static uint8_t double_buffer_out[CDCACM_PACKET_SIZE];
|
||||
static uint8_t buffer_in[CDCACM_PACKET_SIZE];
|
||||
|
||||
void gdb_if_putchar(unsigned char c, int flush)
|
||||
|
@ -49,17 +51,28 @@ void gdb_if_putchar(unsigned char c, int flush)
|
|||
}
|
||||
}
|
||||
|
||||
void gdb_usb_out_cb(usbd_device *dev, uint8_t ep)
|
||||
{
|
||||
(void)ep;
|
||||
count_new = usbd_ep_read_packet(dev, CDCACM_GDB_ENDPOINT,
|
||||
double_buffer_out, CDCACM_PACKET_SIZE);
|
||||
}
|
||||
|
||||
unsigned char gdb_if_getchar(void)
|
||||
{
|
||||
|
||||
while(!(out_ptr < count_out)) {
|
||||
/* Detach if port closed */
|
||||
if(!cdcacm_get_dtr())
|
||||
return 0x04;
|
||||
|
||||
while(cdcacm_get_config() != 1);
|
||||
count_out = usbd_ep_read_packet(usbdev, CDCACM_GDB_ENDPOINT,
|
||||
buffer_out, CDCACM_PACKET_SIZE);
|
||||
out_ptr = 0;
|
||||
if (count_new) {
|
||||
memcpy(buffer_out, double_buffer_out,count_new);
|
||||
count_out = count_new;
|
||||
count_new = 0;
|
||||
out_ptr = 0;
|
||||
}
|
||||
}
|
||||
|
||||
return buffer_out[out_ptr++];
|
||||
|
@ -74,9 +87,13 @@ unsigned char gdb_if_getchar_to(int timeout)
|
|||
if(!cdcacm_get_dtr())
|
||||
return 0x04;
|
||||
|
||||
count_out = usbd_ep_read_packet(usbdev, CDCACM_GDB_ENDPOINT,
|
||||
buffer_out, CDCACM_PACKET_SIZE);
|
||||
out_ptr = 0;
|
||||
while(cdcacm_get_config() != 1);
|
||||
if (count_new) {
|
||||
memcpy(buffer_out, double_buffer_out,count_new);
|
||||
count_out = count_new;
|
||||
count_new = 0;
|
||||
out_ptr = 0;
|
||||
}
|
||||
} while(timeout_counter && !(out_ptr < count_out));
|
||||
|
||||
if(out_ptr < count_out)
|
||||
|
|
|
@ -25,11 +25,11 @@
|
|||
#include "general.h"
|
||||
|
||||
#include "jtagtap.h"
|
||||
#include "platform.h"
|
||||
|
||||
int jtagtap_init(void)
|
||||
{
|
||||
gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_50_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, TMS_PIN);
|
||||
TMS_SET_MODE();
|
||||
|
||||
/* Go to JTAG mode for SWJ-DP */
|
||||
for(int i = 0; i <= 50; i++) jtagtap_next(1, 0); /* Reset SW-DP */
|
||||
|
|
|
@ -0,0 +1,28 @@
|
|||
/*
|
||||
* 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 = 64K
|
||||
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
|
||||
}
|
||||
|
||||
/* Include the common ld script from libopenstm32. */
|
||||
INCLUDE libopencm3_stm32f1.ld
|
|
@ -0,0 +1,28 @@
|
|||
/*
|
||||
* 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 = 256K
|
||||
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
}
|
||||
|
||||
/* Include the common ld script from libopenstm32. */
|
||||
INCLUDE libopencm3_stm32f1.ld
|
|
@ -39,13 +39,11 @@ static void swdptap_turnaround(uint8_t dir)
|
|||
olddir = dir;
|
||||
|
||||
if(dir)
|
||||
gpio_set_mode(SWDIO_PORT, GPIO_MODE_INPUT,
|
||||
GPIO_CNF_INPUT_FLOAT, SWDIO_PIN);
|
||||
SWDIO_MODE_FLOAT();
|
||||
gpio_set(SWCLK_PORT, SWCLK_PIN);
|
||||
gpio_clear(SWCLK_PORT, SWCLK_PIN);
|
||||
if(!dir)
|
||||
gpio_set_mode(SWDIO_PORT, GPIO_MODE_OUTPUT_50_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, SWDIO_PIN);
|
||||
SWDIO_MODE_DRIVE();
|
||||
}
|
||||
|
||||
static uint8_t swdptap_bit_in(void)
|
||||
|
|
|
@ -40,12 +40,13 @@
|
|||
#include <libopencm3/usb/usbd.h>
|
||||
|
||||
#include <string.h>
|
||||
#include "platform.h"
|
||||
|
||||
void traceswo_init(void)
|
||||
{
|
||||
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_TIM3EN);
|
||||
TRACE_TIM_CLK_EN();
|
||||
|
||||
timer_reset(TIM3);
|
||||
timer_reset(TRACE_TIM);
|
||||
|
||||
/* Refer to ST doc RM0008 - STM32F10xx Reference Manual.
|
||||
* Section 14.3.4 - 14.3.6 (General Purpose Timer - Input Capture)
|
||||
|
@ -54,29 +55,29 @@ void traceswo_init(void)
|
|||
*/
|
||||
|
||||
/* Use TI1 as capture input for CH1 and CH2 */
|
||||
timer_ic_set_input(TIM3, TIM_IC1, TIM_IC_IN_TI1);
|
||||
timer_ic_set_input(TIM3, TIM_IC2, TIM_IC_IN_TI1);
|
||||
timer_ic_set_input(TRACE_TIM, TIM_IC1, TIM_IC_IN_TI1);
|
||||
timer_ic_set_input(TRACE_TIM, TIM_IC2, TIM_IC_IN_TI1);
|
||||
|
||||
/* Capture CH1 on rising edge, CH2 on falling edge */
|
||||
timer_ic_set_polarity(TIM3, TIM_IC1, TIM_IC_RISING);
|
||||
timer_ic_set_polarity(TIM3, TIM_IC2, TIM_IC_FALLING);
|
||||
timer_ic_set_polarity(TRACE_TIM, TIM_IC1, TIM_IC_RISING);
|
||||
timer_ic_set_polarity(TRACE_TIM, TIM_IC2, TIM_IC_FALLING);
|
||||
|
||||
/* Trigger on Filtered Timer Input 1 (TI1FP1) */
|
||||
timer_slave_set_trigger(TIM3, TIM_SMCR_TS_IT1FP1);
|
||||
timer_slave_set_trigger(TRACE_TIM, TIM_SMCR_TS_IT1FP1);
|
||||
|
||||
/* Slave reset mode: reset counter on trigger */
|
||||
timer_slave_set_mode(TIM3, TIM_SMCR_SMS_RM);
|
||||
timer_slave_set_mode(TRACE_TIM, TIM_SMCR_SMS_RM);
|
||||
|
||||
/* Enable capture interrupt */
|
||||
nvic_set_priority(NVIC_TIM3_IRQ, IRQ_PRI_TIM3);
|
||||
nvic_enable_irq(NVIC_TIM3_IRQ);
|
||||
timer_enable_irq(TIM3, TIM_DIER_CC1IE);
|
||||
nvic_set_priority(TRACE_IRQ, IRQ_PRI_TRACE);
|
||||
nvic_enable_irq(TRACE_IRQ);
|
||||
timer_enable_irq(TRACE_TIM, TIM_DIER_CC1IE);
|
||||
|
||||
/* Enable the capture channels */
|
||||
timer_ic_enable(TIM3, TIM_IC1);
|
||||
timer_ic_enable(TIM3, TIM_IC2);
|
||||
timer_ic_enable(TRACE_TIM, TIM_IC1);
|
||||
timer_ic_enable(TRACE_TIM, TIM_IC2);
|
||||
|
||||
timer_enable_counter(TIM3);
|
||||
timer_enable_counter(TRACE_TIM);
|
||||
}
|
||||
|
||||
static uint8_t trace_usb_buf[64];
|
||||
|
@ -107,9 +108,9 @@ void trace_buf_drain(usbd_device *dev, uint8_t ep)
|
|||
|
||||
#define ALLOWED_DUTY_ERROR 5
|
||||
|
||||
void tim3_isr(void)
|
||||
void trace_isr(void)
|
||||
{
|
||||
uint16_t sr = TIM_SR(TIM3);
|
||||
uint16_t sr = TIM_SR(TRACE_TIM);
|
||||
uint16_t duty, cycle;
|
||||
static uint16_t bt;
|
||||
static uint8_t lastbit;
|
||||
|
@ -120,13 +121,13 @@ void tim3_isr(void)
|
|||
|
||||
/* Reset decoder state if capture overflowed */
|
||||
if (sr & (TIM_SR_CC1OF | TIM_SR_UIF)) {
|
||||
timer_clear_flag(TIM3, TIM_SR_CC1OF | TIM_SR_UIF);
|
||||
timer_clear_flag(TRACE_TIM, TIM_SR_CC1OF | TIM_SR_UIF);
|
||||
if (!(sr & (TIM_SR_CC2IF | TIM_SR_CC1IF)))
|
||||
goto flush_and_reset;
|
||||
}
|
||||
|
||||
cycle = TIM_CCR1(TIM3);
|
||||
duty = TIM_CCR2(TIM3);
|
||||
cycle = TIM_CCR1(TRACE_TIM);
|
||||
duty = TIM_CCR2(TRACE_TIM);
|
||||
|
||||
/* Reset decoder state if crazy shit happened */
|
||||
if ((bt && (((duty / bt) > 2) || ((duty / bt) == 0))) || (duty == 0))
|
||||
|
@ -147,9 +148,9 @@ void tim3_isr(void)
|
|||
bt = duty;
|
||||
lastbit = 1;
|
||||
halfbit = 0;
|
||||
timer_set_period(TIM3, duty * 6);
|
||||
timer_clear_flag(TIM3, TIM_SR_UIF);
|
||||
timer_enable_irq(TIM3, TIM_DIER_UIE);
|
||||
timer_set_period(TRACE_TIM, duty * 6);
|
||||
timer_clear_flag(TRACE_TIM, TIM_SR_UIF);
|
||||
timer_enable_irq(TRACE_TIM, TIM_DIER_UIE);
|
||||
} else {
|
||||
/* If high time is extended we need to flip the bit */
|
||||
if ((duty / bt) > 1) {
|
||||
|
@ -179,12 +180,10 @@ void tim3_isr(void)
|
|||
return;
|
||||
|
||||
flush_and_reset:
|
||||
timer_set_period(TIM3, -1);
|
||||
timer_disable_irq(TIM3, TIM_DIER_UIE);
|
||||
timer_set_period(TRACE_TIM, -1);
|
||||
timer_disable_irq(TRACE_TIM, TIM_DIER_UIE);
|
||||
trace_buf_push(decbuf, decbuf_pos >> 3);
|
||||
bt = 0;
|
||||
decbuf_pos = 0;
|
||||
memset(decbuf, 0, sizeof(decbuf));
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,626 @@
|
|||
/*
|
||||
* This file is part of the libopencm3 project.
|
||||
*
|
||||
* Copyright (C) 2010 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 <string.h>
|
||||
#include <libopencm3/cm3/systick.h>
|
||||
#include <libopencm3/stm32/rcc.h>
|
||||
#include <libopencm3/stm32/gpio.h>
|
||||
#if defined(STM32F1)
|
||||
#include <libopencm3/stm32/f1/flash.h>
|
||||
#elif defined(STM32F2)
|
||||
#include <libopencm3/stm32/f2/flash.h>
|
||||
#elif defined(STM32F4)
|
||||
#include <libopencm3/stm32/f4/flash.h>
|
||||
#else
|
||||
#warning "Unhandled STM32 family"
|
||||
#endif
|
||||
#include <libopencm3/cm3/scb.h>
|
||||
#include <libopencm3/usb/usbd.h>
|
||||
#include <libopencm3/usb/dfu.h>
|
||||
|
||||
/* Commands sent with wBlockNum == 0 as per ST implementation. */
|
||||
#define CMD_SETADDR 0x21
|
||||
#define CMD_ERASE 0x41
|
||||
|
||||
#define FLASH_OBP_RDP 0x1FFFF800
|
||||
#define FLASH_OBP_WRP10 0x1FFFF808
|
||||
|
||||
#define FLASH_OBP_RDP_KEY 0x5aa5
|
||||
|
||||
usbd_device *usbdev;
|
||||
/* We need a special large control buffer for this device: */
|
||||
u8 usbd_control_buffer[1024];
|
||||
|
||||
#if defined (STM32_CAN)
|
||||
#define FLASHBLOCKSIZE 2048
|
||||
#else
|
||||
#define FLASHBLOCKSIZE 1024
|
||||
#endif
|
||||
|
||||
#if defined(DISCOVERY_STLINK)
|
||||
uint8_t rev;
|
||||
uint16_t led_idle_run;
|
||||
u32 led2_state = 0;
|
||||
int stlink_test_nrst(void) {
|
||||
/* Test if JRST/NRST is pulled down*/
|
||||
int i;
|
||||
uint16_t nrst;
|
||||
uint16_t pin;
|
||||
|
||||
/* First, get Board revision by pulling PC13/14 up. Read
|
||||
* 11 for ST-Link V1, e.g. on VL Discovery, tag as rev 0
|
||||
* 10 for ST-Link V2, e.g. on F4 Discovery, tag as rev 1
|
||||
*/
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
|
||||
gpio_set_mode(GPIOC, GPIO_MODE_INPUT,
|
||||
GPIO_CNF_INPUT_PULL_UPDOWN, GPIO14|GPIO13);
|
||||
gpio_set(GPIOC, GPIO14|GPIO13);
|
||||
for (i=0; i< 100; i++)
|
||||
rev = (~(gpio_get(GPIOC, GPIO14|GPIO13))>>13) & 3;
|
||||
|
||||
switch (rev)
|
||||
{
|
||||
case 0:
|
||||
pin = GPIO1;
|
||||
led_idle_run= GPIO8;
|
||||
break;
|
||||
default:
|
||||
pin = GPIO0;
|
||||
led_idle_run = GPIO9;
|
||||
}
|
||||
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, led_idle_run);
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
|
||||
gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
|
||||
GPIO_CNF_INPUT_PULL_UPDOWN, pin);
|
||||
gpio_set(GPIOB, pin);
|
||||
for (i=0; i< 100; i++)
|
||||
nrst = gpio_get(GPIOB, pin);
|
||||
return (nrst)?1:0;
|
||||
}
|
||||
#endif
|
||||
|
||||
static u32 max_address;
|
||||
#if defined (STM32F4)
|
||||
#define APP_ADDRESS 0x08010000
|
||||
static u32 sector_addr[] = {0x8000000, 0x8004000, 0x8008000, 0x800c000,
|
||||
0x8010000, 0x8020000, 0x8040000, 0x8060000,
|
||||
0x8080000, 0x80a0000, 0x80c0000, 0x80e0000,
|
||||
0x8100000, 0};
|
||||
u16 sector_erase_time[12]= {500, 500, 500, 500,
|
||||
1100,
|
||||
2600, 2600, 2600, 2600, 2600, 2600, 2600};
|
||||
u8 sector_num = 0xff;
|
||||
/* Find the sector number for a given address*/
|
||||
void get_sector_num(u32 addr)
|
||||
{
|
||||
int i = 0;
|
||||
while(sector_addr[i+1]) {
|
||||
if (addr < sector_addr[i+1])
|
||||
break;
|
||||
i++;
|
||||
}
|
||||
if (!sector_addr[i])
|
||||
return;
|
||||
sector_num = i;
|
||||
}
|
||||
|
||||
void check_and_do_sector_erase(u32 addr)
|
||||
{
|
||||
if(addr == sector_addr[sector_num]) {
|
||||
flash_erase_sector((sector_num & 0x1f)<<3, FLASH_PROGRAM_X32);
|
||||
}
|
||||
}
|
||||
#else
|
||||
#define APP_ADDRESS 0x08002000
|
||||
static uint32_t last_erased_page=0xffffffff;
|
||||
void check_and_do_sector_erase(u32 sector)
|
||||
{
|
||||
sector &= (~(FLASHBLOCKSIZE-1));
|
||||
if (sector != last_erased_page) {
|
||||
flash_erase_page(sector);
|
||||
last_erased_page = sector;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
static enum dfu_state usbdfu_state = STATE_DFU_IDLE;
|
||||
|
||||
static char *get_dev_unique_id(char *serial_no);
|
||||
|
||||
static struct {
|
||||
u8 buf[sizeof(usbd_control_buffer)];
|
||||
u16 len;
|
||||
u32 addr;
|
||||
u16 blocknum;
|
||||
} prog;
|
||||
|
||||
const struct usb_device_descriptor dev = {
|
||||
.bLength = USB_DT_DEVICE_SIZE,
|
||||
.bDescriptorType = USB_DT_DEVICE,
|
||||
.bcdUSB = 0x0200,
|
||||
.bDeviceClass = 0,
|
||||
.bDeviceSubClass = 0,
|
||||
.bDeviceProtocol = 0,
|
||||
.bMaxPacketSize0 = 64,
|
||||
.idVendor = 0x1D50,
|
||||
.idProduct = 0x6017,
|
||||
.bcdDevice = 0x0100,
|
||||
.iManufacturer = 1,
|
||||
.iProduct = 2,
|
||||
.iSerialNumber = 3,
|
||||
.bNumConfigurations = 1,
|
||||
};
|
||||
|
||||
const struct usb_dfu_descriptor dfu_function = {
|
||||
.bLength = sizeof(struct usb_dfu_descriptor),
|
||||
.bDescriptorType = DFU_FUNCTIONAL,
|
||||
.bmAttributes = USB_DFU_CAN_DOWNLOAD | USB_DFU_WILL_DETACH,
|
||||
.wDetachTimeout = 255,
|
||||
.wTransferSize = 1024,
|
||||
.bcdDFUVersion = 0x011A,
|
||||
};
|
||||
|
||||
const struct usb_interface_descriptor iface = {
|
||||
.bLength = USB_DT_INTERFACE_SIZE,
|
||||
.bDescriptorType = USB_DT_INTERFACE,
|
||||
.bInterfaceNumber = 0,
|
||||
.bAlternateSetting = 0,
|
||||
.bNumEndpoints = 0,
|
||||
.bInterfaceClass = 0xFE, /* Device Firmware Upgrade */
|
||||
.bInterfaceSubClass = 1,
|
||||
.bInterfaceProtocol = 2,
|
||||
|
||||
/* The ST Microelectronics DfuSe application needs this string.
|
||||
* The format isn't documented... */
|
||||
.iInterface = 4,
|
||||
|
||||
.extra = &dfu_function,
|
||||
.extralen = sizeof(dfu_function),
|
||||
};
|
||||
|
||||
const struct usb_interface ifaces[] = {{
|
||||
.num_altsetting = 1,
|
||||
.altsetting = &iface,
|
||||
}};
|
||||
|
||||
const struct usb_config_descriptor config = {
|
||||
.bLength = USB_DT_CONFIGURATION_SIZE,
|
||||
.bDescriptorType = USB_DT_CONFIGURATION,
|
||||
.wTotalLength = 0,
|
||||
.bNumInterfaces = 1,
|
||||
.bConfigurationValue = 1,
|
||||
.iConfiguration = 0,
|
||||
.bmAttributes = 0xC0,
|
||||
.bMaxPower = 0x32,
|
||||
|
||||
.interface = ifaces,
|
||||
};
|
||||
|
||||
static char serial_no[9];
|
||||
|
||||
static const char *usb_strings[] = {
|
||||
"Black Sphere Technologies",
|
||||
#if defined(BLACKMAGIC)
|
||||
"Black Magic Probe (Upgrade), (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")",
|
||||
#elif defined(DISCOVERY_STLINK)
|
||||
"Black Magic (Upgrade) for STLink/Discovery, (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")",
|
||||
#elif defined(STM32_CAN)
|
||||
"Black Magic (Upgrade) for STM32_CAN, (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")",
|
||||
#elif defined(F4DISCOVERY)
|
||||
"Black Magic (Upgrade) for F4Discovery, (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")",
|
||||
#elif defined(USPS_F407)
|
||||
"Black Magic (Upgrade) for USPS_F407, (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")",
|
||||
#else
|
||||
#warning "Unhandled board"
|
||||
#endif
|
||||
serial_no,
|
||||
/* This string is used by ST Microelectronics' DfuSe utility */
|
||||
#if defined(BLACKMAGIC)
|
||||
"@Internal Flash /0x08000000/8*001Ka,120*001Kg"
|
||||
#elif defined(DISCOVERY_STLINK)
|
||||
"@Internal Flash /0x08000000/8*001Ka,56*001Kg"
|
||||
#elif defined(STM32_CAN)
|
||||
"@Internal Flash /0x08000000/4*002Ka,124*002Kg"
|
||||
#elif defined(F4DISCOVERY) || defined(USPS_F407)
|
||||
"@Internal Flash /0x08000000/1*016Ka,3*016Kg,1*064Kg,7*128Kg"
|
||||
#else
|
||||
#warning "Unhandled board"
|
||||
#endif
|
||||
};
|
||||
|
||||
static u8 usbdfu_getstatus(u32 *bwPollTimeout)
|
||||
{
|
||||
switch(usbdfu_state) {
|
||||
case STATE_DFU_DNLOAD_SYNC:
|
||||
usbdfu_state = STATE_DFU_DNBUSY;
|
||||
#if defined(STM32F4)
|
||||
/* Programming 256 word with 100 us(max) per word*/
|
||||
*bwPollTimeout = 26;
|
||||
/* Erase for big pages on STM2/4 needs "long" time
|
||||
Try not to hit USB timeouts*/
|
||||
if ((prog.blocknum == 0) && (prog.buf[0] == CMD_ERASE)) {
|
||||
u32 addr = *(u32 *)(prog.buf + 1);
|
||||
get_sector_num(addr);
|
||||
if(addr == sector_addr[sector_num])
|
||||
*bwPollTimeout = sector_erase_time[sector_num];
|
||||
}
|
||||
#else
|
||||
*bwPollTimeout = 100;
|
||||
#endif
|
||||
return DFU_STATUS_OK;
|
||||
|
||||
case STATE_DFU_MANIFEST_SYNC:
|
||||
/* Device will reset when read is complete */
|
||||
usbdfu_state = STATE_DFU_MANIFEST;
|
||||
return DFU_STATUS_OK;
|
||||
|
||||
default:
|
||||
return DFU_STATUS_OK;
|
||||
}
|
||||
}
|
||||
|
||||
static void
|
||||
usbdfu_getstatus_complete(usbd_device *dev, struct usb_setup_data *req)
|
||||
{
|
||||
int i;
|
||||
(void)req;
|
||||
|
||||
switch(usbdfu_state) {
|
||||
case STATE_DFU_DNBUSY:
|
||||
|
||||
flash_unlock();
|
||||
if(prog.blocknum == 0) {
|
||||
u32 addr = *(u32 *)(prog.buf + 1);
|
||||
if (addr < APP_ADDRESS ||
|
||||
(addr >= max_address)) {
|
||||
flash_lock();
|
||||
usbd_ep_stall_set(dev, 0, 1);
|
||||
return;
|
||||
}
|
||||
switch(prog.buf[0]) {
|
||||
case CMD_ERASE:
|
||||
check_and_do_sector_erase(addr);
|
||||
case CMD_SETADDR:
|
||||
prog.addr = addr;
|
||||
}
|
||||
} else {
|
||||
u32 baseaddr = prog.addr +
|
||||
((prog.blocknum - 2) *
|
||||
dfu_function.wTransferSize);
|
||||
#if defined (STM32F4)
|
||||
for(i = 0; i < prog.len; i += 4)
|
||||
flash_program_word(baseaddr + i,
|
||||
*(u32*)(prog.buf+i),
|
||||
FLASH_PROGRAM_X32);
|
||||
#else
|
||||
for(i = 0; i < prog.len; i += 2)
|
||||
flash_program_half_word(baseaddr + i,
|
||||
*(u16*)(prog.buf+i));
|
||||
#endif
|
||||
}
|
||||
flash_lock();
|
||||
|
||||
/* We jump straight to dfuDNLOAD-IDLE,
|
||||
* skipping dfuDNLOAD-SYNC
|
||||
*/
|
||||
usbdfu_state = STATE_DFU_DNLOAD_IDLE;
|
||||
return;
|
||||
|
||||
case STATE_DFU_MANIFEST:
|
||||
#if defined (DISCOVERY_STLINK)
|
||||
/* Disconnect USB cable by resetting USB Device
|
||||
and pulling USB_DP low*/
|
||||
rcc_peripheral_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN);
|
||||
rcc_peripheral_clear_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
|
||||
gpio_clear(GPIOA, GPIO12);
|
||||
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_OPENDRAIN, GPIO12);
|
||||
#else
|
||||
/* USB device must detach, we just reset... */
|
||||
#endif
|
||||
scb_reset_system();
|
||||
return; /* Will never return */
|
||||
default:
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
static int usbdfu_control_request(usbd_device *dev,
|
||||
struct usb_setup_data *req, u8 **buf, u16 *len,
|
||||
void (**complete)(usbd_device *dev, struct usb_setup_data *req))
|
||||
{
|
||||
(void)dev;
|
||||
|
||||
if((req->bmRequestType & 0x7F) != 0x21)
|
||||
return 0; /* Only accept class request */
|
||||
|
||||
switch(req->bRequest) {
|
||||
case DFU_DNLOAD:
|
||||
if((len == NULL) || (*len == 0)) {
|
||||
usbdfu_state = STATE_DFU_MANIFEST_SYNC;
|
||||
return 1;
|
||||
} else {
|
||||
/* Copy download data for use on GET_STATUS */
|
||||
prog.blocknum = req->wValue;
|
||||
prog.len = *len;
|
||||
memcpy(prog.buf, *buf, *len);
|
||||
usbdfu_state = STATE_DFU_DNLOAD_SYNC;
|
||||
return 1;
|
||||
}
|
||||
case DFU_CLRSTATUS:
|
||||
/* Clear error and return to dfuIDLE */
|
||||
if(usbdfu_state == STATE_DFU_ERROR)
|
||||
usbdfu_state = STATE_DFU_IDLE;
|
||||
return 1;
|
||||
case DFU_ABORT:
|
||||
/* Abort returns to dfuIDLE state */
|
||||
usbdfu_state = STATE_DFU_IDLE;
|
||||
return 1;
|
||||
case DFU_UPLOAD:
|
||||
/* Upload not supported for now */
|
||||
return 0;
|
||||
case DFU_GETSTATUS: {
|
||||
u32 bwPollTimeout = 0; /* 24-bit integer in DFU class spec */
|
||||
|
||||
(*buf)[0] = usbdfu_getstatus(&bwPollTimeout);
|
||||
(*buf)[1] = bwPollTimeout & 0xFF;
|
||||
(*buf)[2] = (bwPollTimeout >> 8) & 0xFF;
|
||||
(*buf)[3] = (bwPollTimeout >> 16) & 0xFF;
|
||||
(*buf)[4] = usbdfu_state;
|
||||
(*buf)[5] = 0; /* iString not used here */
|
||||
*len = 6;
|
||||
|
||||
*complete = usbdfu_getstatus_complete;
|
||||
|
||||
return 1;
|
||||
}
|
||||
case DFU_GETSTATE:
|
||||
/* Return state with no state transision */
|
||||
*buf[0] = usbdfu_state;
|
||||
*len = 1;
|
||||
return 1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int main(void)
|
||||
{
|
||||
/* Check the force bootloader pin*/
|
||||
#if defined (DISCOVERY_STLINK)
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
|
||||
/* Check value of GPIOA1 configuration. This pin is unconnected on
|
||||
* STLink V1 and V2. If we have a value other than the reset value (0x4),
|
||||
* we have a warm start and request Bootloader entry
|
||||
*/
|
||||
if(((GPIOA_CRL & 0x40) == 0x40) && stlink_test_nrst()) {
|
||||
#elif defined (STM32_CAN)
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
|
||||
if(!gpio_get(GPIOA, GPIO0)) {
|
||||
#elif defined (F4DISCOVERY)
|
||||
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPAEN);
|
||||
if(!gpio_get(GPIOA, GPIO0)) {
|
||||
#elif defined (USPS_F407)
|
||||
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPBEN);
|
||||
/* Pull up an look if external pulled low or if we restart with PB1 low*/
|
||||
GPIOB_PUPDR |= 4;
|
||||
{
|
||||
int i;
|
||||
for(i=0; i<100000; i++) __asm__("NOP");
|
||||
}
|
||||
if(gpio_get(GPIOB, GPIO1)) {
|
||||
#else
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
|
||||
if(gpio_get(GPIOB, GPIO12)) {
|
||||
#endif
|
||||
/* Boot the application if it's valid */
|
||||
#if defined (STM32F4)
|
||||
/* Vector table may be anywhere in 128 kByte RAM
|
||||
CCM not handled*/
|
||||
if((*(volatile u32*)APP_ADDRESS & 0x2FFC0000) == 0x20000000) {
|
||||
#else
|
||||
if((*(volatile u32*)APP_ADDRESS & 0x2FFE0000) == 0x20000000) {
|
||||
#endif
|
||||
/* Set vector table base address */
|
||||
SCB_VTOR = APP_ADDRESS & 0x1FFFFF; /* Max 2 MByte Flash*/
|
||||
/* Initialise master stack pointer */
|
||||
asm volatile ("msr msp, %0"::"g"
|
||||
(*(volatile u32*)APP_ADDRESS));
|
||||
/* Jump to application */
|
||||
(*(void(**)())(APP_ADDRESS + 4))();
|
||||
}
|
||||
}
|
||||
|
||||
#if defined (STM32F4)
|
||||
if ((FLASH_OPTCR & 0x10000) != 0) {
|
||||
flash_program_option_bytes(FLASH_OPTCR & ~0x10000);
|
||||
flash_lock_option_bytes();
|
||||
}
|
||||
#else
|
||||
if ((FLASH_WRPR & 0x03) != 0x00) {
|
||||
flash_unlock();
|
||||
FLASH_CR = 0;
|
||||
flash_erase_option_bytes();
|
||||
flash_program_option_bytes(FLASH_OBP_RDP, FLASH_OBP_RDP_KEY);
|
||||
/* CL Device: Protect 2 bits with (2 * 2k pages each)*/
|
||||
/* MD Device: Protect 2 bits with (4 * 1k pages each)*/
|
||||
flash_program_option_bytes(FLASH_OBP_WRP10, 0x03FC);
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Set up clock*/
|
||||
#if defined (F4DISCOVERY) || defined(USPS_F407)
|
||||
rcc_clock_setup_hse_3v3(&hse_8mhz_3v3[CLOCK_3V3_168MHZ]);
|
||||
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
|
||||
systick_set_reload(2100000);
|
||||
#else
|
||||
rcc_clock_setup_in_hse_8mhz_out_72mhz();
|
||||
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
|
||||
systick_set_reload(900000);
|
||||
#endif
|
||||
|
||||
/* Handle USB disconnect/connect */
|
||||
#if defined(DISCOVERY_STLINK)
|
||||
/* Just in case: Disconnect USB cable by resetting USB Device
|
||||
* and pulling USB_DP low
|
||||
* Device will reconnect automatically as Pull-Up is hard wired*/
|
||||
rcc_peripheral_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN);
|
||||
rcc_peripheral_clear_reset(&RCC_APB1RSTR, RCC_APB1ENR_USBEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
|
||||
gpio_clear(GPIOA, GPIO12);
|
||||
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_OPENDRAIN, GPIO12);
|
||||
#elif defined(F4DISCOVERY)
|
||||
#elif defined(USPS_F407)
|
||||
#elif defined(STM32_CAN)
|
||||
#else
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_USBEN);
|
||||
gpio_set_mode(GPIOA, GPIO_MODE_INPUT, 0, GPIO8);
|
||||
|
||||
#endif
|
||||
systick_interrupt_enable();
|
||||
systick_counter_enable();
|
||||
get_dev_unique_id(serial_no);
|
||||
|
||||
/* Handle LEDs */
|
||||
#if defined(F4DISCOVERY)
|
||||
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPDEN);
|
||||
gpio_clear(GPIOD, GPIO12 | GPIO13 | GPIO14 |GPIO15);
|
||||
gpio_mode_setup(GPIOD, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE,
|
||||
GPIO12 | GPIO13 | GPIO14 |GPIO15);
|
||||
#elif defined(USPS_F407)
|
||||
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPBEN);
|
||||
gpio_clear(GPIOB, GPIO2);
|
||||
gpio_mode_setup(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE,
|
||||
GPIO2);
|
||||
#elif defined (STM32_CAN)
|
||||
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, GPIO0);
|
||||
#else
|
||||
gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, GPIO11);
|
||||
gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
|
||||
GPIO_CNF_INPUT_FLOAT, GPIO2 | GPIO10);
|
||||
|
||||
#endif
|
||||
|
||||
/* Set up USB*/
|
||||
#if defined(STM32_CAN)
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
|
||||
rcc_peripheral_enable_clock(&RCC_AHBENR, RCC_AHBENR_OTGFSEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
|
||||
usbdev = usbd_init(&stm32f107_usb_driver,
|
||||
&dev, &config, usb_strings, 4);
|
||||
#elif defined(STM32F2)||defined(STM32F4)
|
||||
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPAEN);
|
||||
rcc_peripheral_enable_clock(&RCC_AHB2ENR, RCC_AHB2ENR_OTGFSEN);
|
||||
|
||||
/* Set up USB Pins and alternate function*/
|
||||
gpio_mode_setup(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE,
|
||||
GPIO9 | GPIO10 | GPIO11 | GPIO12);
|
||||
gpio_set_af(GPIOA, GPIO_AF10, GPIO9 | GPIO10| GPIO11 | GPIO12);
|
||||
usbdev = usbd_init(&stm32f107_usb_driver,
|
||||
&dev, &config, usb_strings, 4);
|
||||
#else
|
||||
usbdev = usbd_init(&stm32f103_usb_driver,
|
||||
&dev, &config, usb_strings, 4);
|
||||
#endif
|
||||
usbd_set_control_buffer_size(usbdev, sizeof(usbd_control_buffer));
|
||||
usbd_register_control_callback(usbdev,
|
||||
USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
|
||||
USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
|
||||
usbdfu_control_request);
|
||||
|
||||
#if defined(BLACKMAGIG)
|
||||
gpio_set(GPIOA, GPIO8);
|
||||
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, GPIO8);
|
||||
#endif
|
||||
|
||||
while (1)
|
||||
usbd_poll(usbdev);
|
||||
}
|
||||
|
||||
static char *get_dev_unique_id(char *s)
|
||||
{
|
||||
#if defined(STM32F4) || defined(STM32F2)
|
||||
#define UNIQUE_SERIAL_R 0x1FFF7A10
|
||||
#define FLASH_SIZE_R 0x1fff7A22
|
||||
#elif defined(STM32F3)
|
||||
#define UNIQUE_SERIAL_R 0x1FFFF7AC
|
||||
#define FLASH_SIZE_R 0x1fff77cc
|
||||
#elif defined(STM32L1)
|
||||
#define UNIQUE_SERIAL_R 0x1ff80050
|
||||
#define FLASH_SIZE_R 0x1FF8004C
|
||||
#else
|
||||
#define UNIQUE_SERIAL_R 0x1FFFF7E8;
|
||||
#define FLASH_SIZE_R 0x1ffff7e0
|
||||
#endif
|
||||
volatile uint32_t *unique_id_p = (volatile uint32_t *)UNIQUE_SERIAL_R;
|
||||
uint32_t unique_id = *unique_id_p +
|
||||
*(unique_id_p + 1) +
|
||||
*(unique_id_p + 2);
|
||||
int i;
|
||||
|
||||
/* Calculated the upper flash limit from the exported data
|
||||
in theparameter block*/
|
||||
max_address = (*(u32 *) FLASH_SIZE_R) <<10;
|
||||
/* 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 sys_tick_handler()
|
||||
{
|
||||
#if defined(DISCOVERY_STLINK)
|
||||
if (rev == 0)
|
||||
gpio_toggle(GPIOA, led_idle_run);
|
||||
else
|
||||
{
|
||||
if (led2_state & 1)
|
||||
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, led_idle_run);
|
||||
else
|
||||
gpio_set_mode(GPIOA, GPIO_MODE_INPUT,
|
||||
GPIO_CNF_INPUT_ANALOG, led_idle_run);
|
||||
led2_state++;
|
||||
}
|
||||
#elif defined (F4DISCOVERY)
|
||||
gpio_toggle(GPIOD, GPIO12); /* Green LED on/off */
|
||||
#elif defined (USPS_F407)
|
||||
gpio_toggle(GPIOB, GPIO2); /* Green LED on/off */
|
||||
#elif defined(STM32_CAN)
|
||||
gpio_toggle(GPIOB, GPIO0); /* LED2 on/off */
|
||||
#else
|
||||
gpio_toggle(GPIOB, GPIO11); /* LED2 on/off */
|
||||
#endif
|
||||
}
|
||||
|
|
@ -18,70 +18,70 @@
|
|||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <libopencm3/stm32/f1/rcc.h>
|
||||
#include <libopencm3/stm32/f1/gpio.h>
|
||||
#include <libopencm3/stm32/rcc.h>
|
||||
#include <libopencm3/stm32/gpio.h>
|
||||
#include <libopencm3/stm32/usart.h>
|
||||
#include <libopencm3/cm3/nvic.h>
|
||||
#include <libopencm3/cm3/scs.h>
|
||||
#include <libopencm3/usb/usbd.h>
|
||||
#include <libopencm3/usb/cdc.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include <platform.h>
|
||||
|
||||
void usbuart_init(void)
|
||||
{
|
||||
#if defined(BLACKMAGIC)
|
||||
/* On mini hardware, UART and SWD share connector pins.
|
||||
* Don't enable UART if we're being debugged. */
|
||||
if ((platform_hwversion() == 1) && (SCS_DEMCR & SCS_DEMCR_TRCENA))
|
||||
return;
|
||||
#endif
|
||||
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_USART1EN);
|
||||
rcc_peripheral_enable_clock(&USBUSART_APB_ENR, USBUSART_CLK_ENABLE);
|
||||
|
||||
/* UART1 TX to 'alternate function output push-pull' */
|
||||
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO9);
|
||||
UART_PIN_SETUP();
|
||||
|
||||
/* Setup UART parameters. */
|
||||
usart_set_baudrate(USART1, 38400);
|
||||
usart_set_databits(USART1, 8);
|
||||
usart_set_stopbits(USART1, USART_STOPBITS_1);
|
||||
usart_set_mode(USART1, USART_MODE_TX_RX);
|
||||
usart_set_parity(USART1, USART_PARITY_NONE);
|
||||
usart_set_flow_control(USART1, USART_FLOWCONTROL_NONE);
|
||||
usart_set_baudrate(USBUSART, 38400);
|
||||
usart_set_databits(USBUSART, 8);
|
||||
usart_set_stopbits(USBUSART, USART_STOPBITS_1);
|
||||
usart_set_mode(USBUSART, USART_MODE_TX_RX);
|
||||
usart_set_parity(USBUSART, USART_PARITY_NONE);
|
||||
usart_set_flow_control(USBUSART, USART_FLOWCONTROL_NONE);
|
||||
|
||||
/* Finally enable the USART. */
|
||||
usart_enable(USART1);
|
||||
usart_enable(USBUSART);
|
||||
|
||||
/* Enable interrupts */
|
||||
USART1_CR1 |= USART_CR1_RXNEIE;
|
||||
nvic_set_priority(NVIC_USART1_IRQ, IRQ_PRI_USART1);
|
||||
nvic_enable_irq(NVIC_USART1_IRQ);
|
||||
USBUSART_CR1 |= USART_CR1_RXNEIE;
|
||||
nvic_set_priority(USBUSART_IRQ, IRQ_PRI_USBUSART);
|
||||
nvic_enable_irq(USBUSART_IRQ);
|
||||
}
|
||||
|
||||
void usbuart_set_line_coding(struct usb_cdc_line_coding *coding)
|
||||
{
|
||||
usart_set_baudrate(USART1, coding->dwDTERate);
|
||||
usart_set_databits(USART1, coding->bDataBits);
|
||||
usart_set_baudrate(USBUSART, coding->dwDTERate);
|
||||
usart_set_databits(USBUSART, coding->bDataBits);
|
||||
switch(coding->bCharFormat) {
|
||||
case 0:
|
||||
usart_set_stopbits(USART1, USART_STOPBITS_1);
|
||||
usart_set_stopbits(USBUSART, USART_STOPBITS_1);
|
||||
break;
|
||||
case 1:
|
||||
usart_set_stopbits(USART1, USART_STOPBITS_1_5);
|
||||
usart_set_stopbits(USBUSART, USART_STOPBITS_1_5);
|
||||
break;
|
||||
case 2:
|
||||
usart_set_stopbits(USART1, USART_STOPBITS_2);
|
||||
usart_set_stopbits(USBUSART, USART_STOPBITS_2);
|
||||
break;
|
||||
}
|
||||
switch(coding->bParityType) {
|
||||
case 0:
|
||||
usart_set_parity(USART1, USART_PARITY_NONE);
|
||||
usart_set_parity(USBUSART, USART_PARITY_NONE);
|
||||
break;
|
||||
case 1:
|
||||
usart_set_parity(USART1, USART_PARITY_ODD);
|
||||
usart_set_parity(USBUSART, USART_PARITY_ODD);
|
||||
break;
|
||||
case 2:
|
||||
usart_set_parity(USART1, USART_PARITY_EVEN);
|
||||
usart_set_parity(USBUSART, USART_PARITY_EVEN);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -94,16 +94,18 @@ void usbuart_usb_out_cb(usbd_device *dev, uint8_t ep)
|
|||
int len = usbd_ep_read_packet(dev, CDCACM_UART_ENDPOINT,
|
||||
buf, CDCACM_PACKET_SIZE);
|
||||
|
||||
#if defined(BLACKMAGIC)
|
||||
/* Don't bother if uart is disabled.
|
||||
* This will be the case on mini while we're being debugged.
|
||||
*/
|
||||
if(!(RCC_APB2ENR & RCC_APB2ENR_USART1EN))
|
||||
return;
|
||||
#endif
|
||||
|
||||
gpio_set(LED_PORT, LED_UART);
|
||||
gpio_set(LED_PORT_UART, LED_UART);
|
||||
for(int i = 0; i < len; i++)
|
||||
usart_send_blocking(USART1, buf[i]);
|
||||
gpio_clear(LED_PORT, LED_UART);
|
||||
usart_send_blocking(USBUSART, buf[i]);
|
||||
gpio_clear(LED_PORT_UART, LED_UART);
|
||||
}
|
||||
|
||||
static uint8_t uart_usb_buf[CDCACM_PACKET_SIZE];
|
||||
|
@ -112,7 +114,7 @@ static uint8_t uart_usb_buf_size;
|
|||
void usbuart_usb_in_cb(usbd_device *dev, uint8_t ep)
|
||||
{
|
||||
if (!uart_usb_buf_size) {
|
||||
gpio_clear(LED_PORT, LED_UART);
|
||||
gpio_clear(LED_PORT_UART, LED_UART);
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -120,11 +122,17 @@ void usbuart_usb_in_cb(usbd_device *dev, uint8_t ep)
|
|||
uart_usb_buf_size = 0;
|
||||
}
|
||||
|
||||
void usart1_isr(void)
|
||||
void USBUSART_ISR(void)
|
||||
{
|
||||
char c = usart_recv(USART1);
|
||||
char c = usart_recv(USBUSART);
|
||||
|
||||
gpio_set(LED_PORT, LED_UART);
|
||||
/* Don't try to write until we are configured.
|
||||
* Otherwise enumeration hanged in some cases.
|
||||
*/
|
||||
if (cdcacm_get_config() != 1)
|
||||
return;
|
||||
|
||||
gpio_set(LED_PORT_UART, LED_UART);
|
||||
|
||||
/* Try to send now */
|
||||
if (usbd_ep_write_packet(usbdev, CDCACM_UART_ENDPOINT, &c, 1) == 1)
|
||||
|
@ -138,4 +146,3 @@ void usart1_isr(void)
|
|||
|
||||
uart_usb_buf[uart_usb_buf_size++] = c;
|
||||
}
|
||||
|
|
@ -0,0 +1,35 @@
|
|||
CROSS_COMPILE ?= arm-none-eabi-
|
||||
CC = $(CROSS_COMPILE)gcc
|
||||
OBJCOPY = $(CROSS_COMPILE)objcopy
|
||||
|
||||
CFLAGS += -Istm32/include -mcpu=cortex-m3 -mthumb \
|
||||
-DSTM32F1 -DSTM32_CAN -I../libopencm3/include
|
||||
|
||||
LDFLAGS_BOOT = -lopencm3_stm32f1 -Wl,--defsym,_stack=0x20010000 \
|
||||
-Wl,-T,platforms/stm32/stm32_can.ld -nostartfiles -lc -lnosys \
|
||||
-Wl,-Map=mapfile -mthumb -mcpu=cortex-m3 -Wl,-gc-sections \
|
||||
-L../libopencm3/lib
|
||||
LDFLAGS = $(LDFLAGS_BOOT) -Wl,-Ttext=0x8002000
|
||||
|
||||
VPATH += platforms/stm32
|
||||
|
||||
SRC += cdcacm.c \
|
||||
platform.c \
|
||||
usbuart.c \
|
||||
|
||||
all: blackmagic.bin blackmagic_dfu.bin blackmagic_dfu.hex
|
||||
|
||||
blackmagic.bin: blackmagic
|
||||
$(OBJCOPY) -O binary $^ $@
|
||||
|
||||
blackmagic_dfu: usbdfu.o
|
||||
$(CC) $^ -o $@ $(LDFLAGS_BOOT)
|
||||
|
||||
blackmagic_dfu.bin: blackmagic_dfu
|
||||
$(OBJCOPY) -O binary $^ $@
|
||||
|
||||
blackmagic_dfu.hex: blackmagic_dfu
|
||||
$(OBJCOPY) -O ihex $^ $@
|
||||
|
||||
host_clean:
|
||||
-rm blackmagic.bin blackmagic_dfu blackmagic_dfu.bin blackmagic_dfu.hex
|
|
@ -0,0 +1,197 @@
|
|||
/*
|
||||
* 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 <libopencm3/stm32/f1/rcc.h>
|
||||
#include <libopencm3/cm3/systick.h>
|
||||
#include <libopencm3/cm3/scb.h>
|
||||
#include <libopencm3/cm3/nvic.h>
|
||||
#include <libopencm3/stm32/exti.h>
|
||||
#include <libopencm3/stm32/usart.h>
|
||||
#include <libopencm3/usb/usbd.h>
|
||||
#include <libopencm3/stm32/f1/adc.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "jtag_scan.h"
|
||||
#include <usbuart.h>
|
||||
|
||||
#include <ctype.h>
|
||||
|
||||
uint8_t running_status;
|
||||
volatile uint32_t timeout_counter;
|
||||
|
||||
jmp_buf fatal_error_jmpbuf;
|
||||
|
||||
static void morse_update(void);
|
||||
|
||||
int platform_init(void)
|
||||
{
|
||||
|
||||
/* Enable peripherals */
|
||||
rcc_peripheral_enable_clock(&RCC_AHBENR, RCC_AHBENR_OTGFSEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
|
||||
rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
|
||||
|
||||
rcc_clock_setup_in_hse_8mhz_out_72mhz();
|
||||
/* Setup GPIO ports */
|
||||
gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_50_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL,
|
||||
TMS_PIN);
|
||||
|
||||
gpio_set_mode(TCK_PORT, GPIO_MODE_OUTPUT_50_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL,
|
||||
TCK_PIN | TDI_PIN);
|
||||
|
||||
gpio_set_mode(TCK_PORT, GPIO_MODE_INPUT,
|
||||
GPIO_CNF_INPUT_FLOAT,
|
||||
TDO_PIN);
|
||||
|
||||
gpio_set_mode(LED_PORT, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL,
|
||||
LED_UART | LED_IDLE_RUN | LED_ERROR);
|
||||
|
||||
/* Setup heartbeat timer */
|
||||
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
|
||||
systick_set_reload(900000); /* Interrupt us at 10 Hz */
|
||||
SCB_SHPR(11) &= ~((15 << 4) & 0xff);
|
||||
SCB_SHPR(11) |= ((14 << 4) & 0xff);
|
||||
systick_interrupt_enable();
|
||||
systick_counter_enable();
|
||||
|
||||
usbuart_init();
|
||||
|
||||
SCB_VTOR = 0x2000; // Relocate interrupt vector table here
|
||||
|
||||
cdcacm_init();
|
||||
|
||||
jtag_scan(NULL);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void platform_delay(uint32_t delay)
|
||||
{
|
||||
timeout_counter = delay;
|
||||
while(timeout_counter);
|
||||
}
|
||||
|
||||
void sys_tick_handler(void)
|
||||
{
|
||||
if(running_status)
|
||||
gpio_toggle(LED_PORT, LED_IDLE_RUN);
|
||||
|
||||
if(timeout_counter)
|
||||
timeout_counter--;
|
||||
|
||||
morse_update();
|
||||
}
|
||||
|
||||
|
||||
/* Morse code patterns and lengths */
|
||||
static const struct {
|
||||
uint16_t code;
|
||||
uint8_t bits;
|
||||
} morse_letter[] = {
|
||||
{ 0b00011101, 8}, // 'A' .-
|
||||
{ 0b000101010111, 12}, // 'B' -...
|
||||
{ 0b00010111010111, 14}, // 'C' -.-.
|
||||
{ 0b0001010111, 10}, // 'D' -..
|
||||
{ 0b0001, 4}, // 'E' .
|
||||
{ 0b000101110101, 12}, // 'F' ..-.
|
||||
{ 0b000101110111, 12}, // 'G' --.
|
||||
{ 0b0001010101, 10}, // 'H' ....
|
||||
{ 0b000101, 6}, // 'I' ..
|
||||
{0b0001110111011101, 16}, // 'J' .---
|
||||
{ 0b000111010111, 12}, // 'K' -.-
|
||||
{ 0b000101011101, 12}, // 'L' .-..
|
||||
{ 0b0001110111, 10}, // 'M' --
|
||||
{ 0b00010111, 8}, // 'N' -.
|
||||
{ 0b00011101110111, 14}, // 'O' ---
|
||||
{ 0b00010111011101, 14}, // 'P' .--.
|
||||
{0b0001110101110111, 16}, // 'Q' --.-
|
||||
{ 0b0001011101, 10}, // 'R' .-.
|
||||
{ 0b00010101, 8}, // 'S' ...
|
||||
{ 0b000111, 6}, // 'T' -
|
||||
{ 0b0001110101, 10}, // 'U' ..-
|
||||
{ 0b000111010101, 12}, // 'V' ...-
|
||||
{ 0b000111011101, 12}, // 'W' .--
|
||||
{ 0b00011101010111, 14}, // 'X' -..-
|
||||
{0b0001110111010111, 16}, // 'Y' -.--
|
||||
{ 0b00010101110111, 14}, // 'Z' --..
|
||||
};
|
||||
|
||||
|
||||
const char *morse_msg;
|
||||
static const char * volatile morse_ptr;
|
||||
static char morse_repeat;
|
||||
|
||||
void morse(const char *msg, char repeat)
|
||||
{
|
||||
morse_msg = morse_ptr = msg;
|
||||
morse_repeat = repeat;
|
||||
SET_ERROR_STATE(0);
|
||||
}
|
||||
static void morse_update(void)
|
||||
{
|
||||
static uint16_t code;
|
||||
static uint8_t bits;
|
||||
|
||||
if(!morse_ptr) return;
|
||||
|
||||
if(!bits) {
|
||||
char c = *morse_ptr++;
|
||||
if(!c) {
|
||||
if(morse_repeat) {
|
||||
morse_ptr = morse_msg;
|
||||
c = *morse_ptr++;
|
||||
} else {
|
||||
morse_ptr = 0;
|
||||
return;
|
||||
}
|
||||
}
|
||||
if((c >= 'A') && (c <= 'Z')) {
|
||||
c -= 'A';
|
||||
code = morse_letter[c].code;
|
||||
bits = morse_letter[c].bits;
|
||||
} else {
|
||||
code = 0; bits = 4;
|
||||
}
|
||||
}
|
||||
SET_ERROR_STATE(code & 1);
|
||||
code >>= 1; bits--;
|
||||
}
|
||||
|
||||
const char *platform_target_voltage(void)
|
||||
{
|
||||
return "ABSENT!";
|
||||
|
||||
}
|
||||
|
||||
void assert_boot_pin(void)
|
||||
{
|
||||
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, GPIO0);
|
||||
gpio_set(GPIOA, GPIO0);
|
||||
}
|
|
@ -0,0 +1,196 @@
|
|||
/*
|
||||
* 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 <libopencm3/stm32/f1/gpio.h>
|
||||
#include <libopencm3/usb/usbd.h>
|
||||
|
||||
#include <setjmp.h>
|
||||
#include <alloca.h>
|
||||
|
||||
#include "gdb_packet.h"
|
||||
|
||||
#define INLINE_GPIO
|
||||
#define CDCACM_PACKET_SIZE 64
|
||||
/*#define PLATFORM_HAS_TRACESWO*/
|
||||
|
||||
extern usbd_device *usbdev;
|
||||
#define CDCACM_GDB_ENDPOINT 1
|
||||
#define CDCACM_UART_ENDPOINT 3
|
||||
#define BOARD_IDENT "Black Magic Probe (STM32_CAN), (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")"
|
||||
#define DFU_IDENT "Black Magic Firmware Upgrade (STM32_CAN)"
|
||||
|
||||
/* Important pin mappings for STM32 implementation:
|
||||
*
|
||||
* LED0 = PB2 (Yellow LED : Running)
|
||||
* LED1 = PB10 (Yellow LED : Idle)
|
||||
* LED2 = PB11 (Red LED : Error)
|
||||
*
|
||||
* TPWR = RB0 (input) -- analogue on mini design ADC1, ch8
|
||||
* nTRST = PC9
|
||||
* SRST_OUT = NA
|
||||
* TDI = PC12
|
||||
* TMS = PB14(input for SWDP)
|
||||
* TCK = PC10
|
||||
* TDO = PC11(input)
|
||||
* nSRST = PA7 (input)
|
||||
*
|
||||
* Force DFU mode button: PA0 Read High for Bootloader Req
|
||||
*/
|
||||
|
||||
/* Hardware definitions... */
|
||||
#define TDI_PORT GPIOC
|
||||
#define TMS_PORT GPIOB
|
||||
#define TCK_PORT GPIOC
|
||||
#define TDO_PORT GPIOC
|
||||
#define TDI_PIN GPIO12
|
||||
#define TMS_PIN GPIO14
|
||||
#define TCK_PIN GPIO10
|
||||
#define TDO_PIN GPIO11
|
||||
|
||||
#define SWDIO_PORT TMS_PORT
|
||||
#define SWCLK_PORT TCK_PORT
|
||||
#define SWDIO_PIN TMS_PIN
|
||||
#define SWCLK_PIN TCK_PIN
|
||||
|
||||
//#define TRST_PORT GPIOC
|
||||
//#define TRST_PIN GPIO9
|
||||
|
||||
#define LED_PORT GPIOB
|
||||
#define LED_PORT_UART GPIOB
|
||||
#define LED_UART GPIO0
|
||||
|
||||
#define LED_IDLE_RUN GPIO1
|
||||
#define LED_ERROR GPIO12
|
||||
|
||||
#define TMS_SET_MODE() \
|
||||
gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_50_MHZ, \
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, TMS_PIN);
|
||||
#define SWDIO_MODE_FLOAT() \
|
||||
gpio_set_mode(SWDIO_PORT, GPIO_MODE_INPUT, \
|
||||
GPIO_CNF_INPUT_FLOAT, SWDIO_PIN);
|
||||
#define SWDIO_MODE_DRIVE() \
|
||||
gpio_set_mode(SWDIO_PORT, GPIO_MODE_OUTPUT_50_MHZ, \
|
||||
GPIO_CNF_OUTPUT_PUSHPULL, SWDIO_PIN);
|
||||
|
||||
#define UART_PIN_SETUP() \
|
||||
gpio_set_mode(USBUSART_PORT, GPIO_MODE_OUTPUT_2_MHZ, \
|
||||
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, USBUSART_TX_PIN);
|
||||
|
||||
#define USB_DRIVER stm32f107_usb_driver
|
||||
#define USB_IRQ NVIC_OTG_FS_IRQ
|
||||
#define USB_ISR otg_fs_isr
|
||||
/* Interrupt priorities. Low numbers are high priority.
|
||||
* For now USART1 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_TIM3 (0 << 4)
|
||||
|
||||
#define USBUSART USART2
|
||||
#define USBUSART_CR1 USART2_CR1
|
||||
#define USBUSART_IRQ NVIC_USART2_IRQ
|
||||
#define USBUSART_APB_ENR RCC_APB1ENR
|
||||
#define USBUSART_CLK_ENABLE RCC_APB1ENR_USART2EN
|
||||
#define USBUSART_PORT GPIOA
|
||||
#define USBUSART_TX_PIN GPIO2
|
||||
#define USBUSART_ISR usart2_isr
|
||||
|
||||
#define DEBUG(...)
|
||||
|
||||
extern uint8_t running_status;
|
||||
extern volatile uint32_t timeout_counter;
|
||||
|
||||
extern jmp_buf fatal_error_jmpbuf;
|
||||
|
||||
extern const char *morse_msg;
|
||||
|
||||
#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, LED_ERROR, state);}
|
||||
|
||||
#define PLATFORM_SET_FATAL_ERROR_RECOVERY() {setjmp(fatal_error_jmpbuf);}
|
||||
#define PLATFORM_FATAL_ERROR(error) { \
|
||||
if(running_status) gdb_putpacketz("X1D"); \
|
||||
else gdb_putpacketz("EFF"); \
|
||||
running_status = 0; \
|
||||
target_list_free(); \
|
||||
morse("TARGET LOST.", 1); \
|
||||
longjmp(fatal_error_jmpbuf, (error)); \
|
||||
}
|
||||
|
||||
int platform_init(void);
|
||||
void morse(const char *msg, char repeat);
|
||||
const char *platform_target_voltage(void);
|
||||
int platform_hwversion(void);
|
||||
void platform_delay(uint32_t delay);
|
||||
|
||||
/* <cdcacm.c> */
|
||||
void cdcacm_init(void);
|
||||
/* Returns current usb configuration, or 0 if not configured. */
|
||||
int cdcacm_get_config(void);
|
||||
int cdcacm_get_dtr(void);
|
||||
|
||||
/* <platform.h> */
|
||||
void uart_usb_buf_drain(uint8_t ep);
|
||||
|
||||
/* Use newlib provided integer only stdio functions */
|
||||
#define sscanf siscanf
|
||||
#define sprintf siprintf
|
||||
#define vasprintf vasiprintf
|
||||
|
||||
#ifdef INLINE_GPIO
|
||||
static inline void _gpio_set(u32 gpioport, u16 gpios)
|
||||
{
|
||||
GPIO_BSRR(gpioport) = gpios;
|
||||
}
|
||||
#define gpio_set _gpio_set
|
||||
|
||||
static inline void _gpio_clear(u32 gpioport, u16 gpios)
|
||||
{
|
||||
GPIO_BRR(gpioport) = gpios;
|
||||
}
|
||||
#define gpio_clear _gpio_clear
|
||||
|
||||
static inline u16 _gpio_get(u32 gpioport, u16 gpios)
|
||||
{
|
||||
return (u16)GPIO_IDR(gpioport) & gpios;
|
||||
}
|
||||
#define gpio_get _gpio_get
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#define disconnect_usb() usbd_disconnect(usbdev,1)
|
||||
void assert_boot_pin(void);
|
||||
#define setup_vbus_irq()
|
|
@ -0,0 +1,36 @@
|
|||
CROSS_COMPILE ?= arm-none-eabi-
|
||||
CC = $(CROSS_COMPILE)gcc
|
||||
OBJCOPY = $(CROSS_COMPILE)objcopy
|
||||
|
||||
CFLAGS += -Istm32/include -mcpu=cortex-m3 -mthumb \
|
||||
-DSTM32F4 -DUSPS_F407 -I../libopencm3/include
|
||||
|
||||
LDFLAGS_BOOT = -lopencm3_stm32f4 -Wl,--defsym,_stack=0x20020000 \
|
||||
-Wl,-T,platforms/stm32/f4discovery.ld -nostartfiles -lc -lnosys \
|
||||
-Wl,-Map=mapfile -mthumb -mcpu=cortex-m3 -Wl,-gc-sections \
|
||||
-L../libopencm3/lib
|
||||
LDFLAGS = $(LDFLAGS_BOOT) -Wl,-Ttext=0x8010000
|
||||
|
||||
VPATH += platforms/stm32
|
||||
|
||||
SRC += cdcacm.c \
|
||||
platform.c \
|
||||
traceswo.c \
|
||||
usbuart.c \
|
||||
|
||||
all: blackmagic.bin blackmagic_dfu.bin blackmagic_dfu.hex
|
||||
|
||||
blackmagic.bin: blackmagic
|
||||
$(OBJCOPY) -O binary $^ $@
|
||||
|
||||
blackmagic_dfu: usbdfu.o
|
||||
$(CC) $^ -o $@ $(LDFLAGS_BOOT)
|
||||
|
||||
blackmagic_dfu.bin: blackmagic_dfu
|
||||
$(OBJCOPY) -O binary $^ $@
|
||||
|
||||
blackmagic_dfu.hex: blackmagic_dfu
|
||||
$(OBJCOPY) -O ihex $^ $@
|
||||
|
||||
host_clean:
|
||||
-rm blackmagic.bin blackmagic_dfu blackmagic_dfu.bin blackmagic_dfu.hex
|
|
@ -0,0 +1,22 @@
|
|||
Hardware
|
||||
========
|
||||
Find eagle schematics at
|
||||
https://github.com/UweBonnes/wiki_fuer_alex/tree/master/layout
|
||||
The board can be used for F1/L1/F2 and F4 with some changed parts,
|
||||
see the datasheet and hints in the schematic
|
||||
|
||||
JTAG: Reuse the JTAG Connector, unconnect JTAG Tap and reuse JTAG pins
|
||||
in inverse direction.
|
||||
Forced boot request: Connect Jumper Wire X11-34/X11-40 to pull PC15
|
||||
to ground
|
||||
System Bootloader: Jumper Boot0 to '1'
|
||||
|
||||
Led: PB2 (Boot1)
|
||||
|
||||
Application start address:
|
||||
=========================
|
||||
|
||||
Use 0x8010000
|
||||
- lower 3 16 k pages may be used for parameter storage
|
||||
- Erasing a single 64 k Page is faster then erasing 2 16 k Pages
|
||||
eventual the 64 k page
|
|
@ -0,0 +1,207 @@
|
|||
/*
|
||||
* 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 <libopencm3/stm32/f4/rcc.h>
|
||||
#include <libopencm3/cm3/systick.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>
|
||||
|
||||
#include "platform.h"
|
||||
#include "jtag_scan.h"
|
||||
#include <usbuart.h>
|
||||
|
||||
#include <ctype.h>
|
||||
|
||||
uint8_t running_status;
|
||||
volatile uint32_t timeout_counter;
|
||||
|
||||
jmp_buf fatal_error_jmpbuf;
|
||||
|
||||
static void morse_update(void);
|
||||
|
||||
int platform_init(void)
|
||||
{
|
||||
rcc_clock_setup_hse_3v3(&hse_8mhz_3v3[CLOCK_3V3_168MHZ]);
|
||||
|
||||
/* Enable peripherals */
|
||||
rcc_peripheral_enable_clock(&RCC_AHB2ENR, RCC_AHB2ENR_OTGFSEN);
|
||||
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPAEN);
|
||||
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPBEN);
|
||||
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPCEN);
|
||||
|
||||
/* Fix all flaoting pins*/
|
||||
gpio_mode_setup(GPIOA, GPIO_MODE_INPUT, GPIO_PUPD_PULLDOWN,
|
||||
0x1ff);
|
||||
|
||||
gpio_mode_setup(GPIOB, GPIO_MODE_INPUT, GPIO_PUPD_PULLDOWN,
|
||||
0xffe2);
|
||||
|
||||
gpio_mode_setup(GPIOC, GPIO_MODE_INPUT, GPIO_PUPD_PULLDOWN,
|
||||
0xf3ff);
|
||||
|
||||
/* Set up USB Pins and alternate function*/
|
||||
gpio_mode_setup(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE,
|
||||
GPIO9 | GPIO10| GPIO11 | GPIO12);
|
||||
gpio_set_af(GPIOA, GPIO_AF10, GPIO9 | GPIO10| GPIO11 | GPIO12);
|
||||
|
||||
/* Set TMS/TCK/TDI to high speed*/
|
||||
GPIOA_OSPEEDR &=~0xfc00;
|
||||
GPIOA_OSPEEDR |= 0xa800;
|
||||
gpio_mode_setup(JTAG_PORT, GPIO_MODE_OUTPUT,
|
||||
GPIO_PUPD_NONE,
|
||||
TMS_PIN | TCK_PIN | TDI_PIN);
|
||||
|
||||
gpio_mode_setup(TDO_PORT, GPIO_MODE_INPUT,
|
||||
GPIO_PUPD_NONE,
|
||||
TDO_PIN | TRST_PIN);
|
||||
|
||||
gpio_mode_setup(LED_PORT, GPIO_MODE_OUTPUT,
|
||||
GPIO_PUPD_NONE,
|
||||
LED_UART );
|
||||
|
||||
/* Setup heartbeat timer */
|
||||
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
|
||||
systick_set_reload(168000000/(10*8)); /* Interrupt us at 10 Hz */
|
||||
SCB_SHPR(11) &= ~((15 << 4) & 0xff);
|
||||
SCB_SHPR(11) |= ((14 << 4) & 0xff);
|
||||
systick_interrupt_enable();
|
||||
systick_counter_enable();
|
||||
|
||||
usbuart_init();
|
||||
|
||||
SCB_VTOR = 0x10000; // Relocate interrupt vector table here
|
||||
|
||||
cdcacm_init();
|
||||
|
||||
jtag_scan(NULL);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void platform_delay(uint32_t delay)
|
||||
{
|
||||
timeout_counter = delay;
|
||||
while(timeout_counter);
|
||||
}
|
||||
|
||||
void sys_tick_handler(void)
|
||||
{
|
||||
if(timeout_counter)
|
||||
timeout_counter--;
|
||||
|
||||
morse_update();
|
||||
}
|
||||
|
||||
|
||||
/* Morse code patterns and lengths */
|
||||
static const struct {
|
||||
uint16_t code;
|
||||
uint8_t bits;
|
||||
} morse_letter[] = {
|
||||
{ 0b00011101, 8}, // 'A' .-
|
||||
{ 0b000101010111, 12}, // 'B' -...
|
||||
{ 0b00010111010111, 14}, // 'C' -.-.
|
||||
{ 0b0001010111, 10}, // 'D' -..
|
||||
{ 0b0001, 4}, // 'E' .
|
||||
{ 0b000101110101, 12}, // 'F' ..-.
|
||||
{ 0b000101110111, 12}, // 'G' --.
|
||||
{ 0b0001010101, 10}, // 'H' ....
|
||||
{ 0b000101, 6}, // 'I' ..
|
||||
{0b0001110111011101, 16}, // 'J' .---
|
||||
{ 0b000111010111, 12}, // 'K' -.-
|
||||
{ 0b000101011101, 12}, // 'L' .-..
|
||||
{ 0b0001110111, 10}, // 'M' --
|
||||
{ 0b00010111, 8}, // 'N' -.
|
||||
{ 0b00011101110111, 14}, // 'O' ---
|
||||
{ 0b00010111011101, 14}, // 'P' .--.
|
||||
{0b0001110101110111, 16}, // 'Q' --.-
|
||||
{ 0b0001011101, 10}, // 'R' .-.
|
||||
{ 0b00010101, 8}, // 'S' ...
|
||||
{ 0b000111, 6}, // 'T' -
|
||||
{ 0b0001110101, 10}, // 'U' ..-
|
||||
{ 0b000111010101, 12}, // 'V' ...-
|
||||
{ 0b000111011101, 12}, // 'W' .--
|
||||
{ 0b00011101010111, 14}, // 'X' -..-
|
||||
{0b0001110111010111, 16}, // 'Y' -.--
|
||||
{ 0b00010101110111, 14}, // 'Z' --..
|
||||
};
|
||||
|
||||
|
||||
const char *morse_msg;
|
||||
static const char * volatile morse_ptr;
|
||||
static char morse_repeat;
|
||||
|
||||
void morse(const char *msg, char repeat)
|
||||
{
|
||||
morse_msg = morse_ptr = msg;
|
||||
morse_repeat = repeat;
|
||||
SET_ERROR_STATE(0);
|
||||
}
|
||||
|
||||
static void morse_update(void)
|
||||
{
|
||||
static uint16_t code;
|
||||
static uint8_t bits;
|
||||
|
||||
if(!morse_ptr) return;
|
||||
|
||||
if(!bits) {
|
||||
char c = *morse_ptr++;
|
||||
if(!c) {
|
||||
if(morse_repeat) {
|
||||
morse_ptr = morse_msg;
|
||||
c = *morse_ptr++;
|
||||
} else {
|
||||
morse_ptr = 0;
|
||||
return;
|
||||
}
|
||||
}
|
||||
if((c >= 'A') && (c <= 'Z')) {
|
||||
c -= 'A';
|
||||
code = morse_letter[c].code;
|
||||
bits = morse_letter[c].bits;
|
||||
} else {
|
||||
code = 0; bits = 4;
|
||||
}
|
||||
}
|
||||
SET_ERROR_STATE(code & 1);
|
||||
code >>= 1; bits--;
|
||||
}
|
||||
|
||||
const char *platform_target_voltage(void)
|
||||
{
|
||||
return "ABSENT!";
|
||||
}
|
||||
|
||||
void assert_boot_pin(void)
|
||||
{
|
||||
/* Flag Bootloader Request by mimicing a pushed USER button*/
|
||||
gpio_mode_setup(GPIOB, GPIO_MODE_OUTPUT,
|
||||
GPIO_PUPD_NONE, GPIO1);
|
||||
gpio_clear(GPIOB, GPIO11);
|
||||
}
|
|
@ -0,0 +1,208 @@
|
|||
/*
|
||||
* 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 <libopencm3/stm32/f4/gpio.h>
|
||||
#include <libopencm3/usb/usbd.h>
|
||||
|
||||
#include <setjmp.h>
|
||||
#include <alloca.h>
|
||||
|
||||
#include "gdb_packet.h"
|
||||
|
||||
#define INLINE_GPIO
|
||||
#define CDCACM_PACKET_SIZE 64
|
||||
#define PLATFORM_HAS_TRACESWO
|
||||
#define BOARD_IDENT "Black Magic Probe (USPS_F407), (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")"
|
||||
#define DFU_IDENT "Black Magic Firmware Upgrade (USPS_F407)"
|
||||
|
||||
extern usbd_device *usbdev;
|
||||
#define CDCACM_GDB_ENDPOINT 1
|
||||
#define CDCACM_UART_ENDPOINT 3
|
||||
|
||||
/* Important pin mappings for STM32 implementation:
|
||||
*
|
||||
* LED0 = PB2
|
||||
|
||||
* TPWR = XXX (input) -- analogue on mini design ADC1, ch8
|
||||
* nTRST = PD0
|
||||
* SRST_OUT = PD1
|
||||
* TDI = PA1
|
||||
* TMS = PA3 (input for SWDP)
|
||||
* TCK = PA8
|
||||
* TDO = PB4 (input)
|
||||
* nSRST = PD2 (input)
|
||||
*
|
||||
* USB cable pull-up: PA8
|
||||
* USB VBUS detect: PB13 -- New on mini design.
|
||||
* Enable pull up for compatibility.
|
||||
* Force DFU mode button: PB1
|
||||
*/
|
||||
|
||||
/* Hardware definitions... */
|
||||
#define JTAG_PORT GPIOA
|
||||
#define TDI_PORT JTAG_PORT
|
||||
#define TMS_PORT JTAG_PORT
|
||||
#define TCK_PORT JTAG_PORT
|
||||
#define TDO_PORT GPIOB
|
||||
#define TMS_PIN GPIO13
|
||||
#define TCK_PIN GPIO14
|
||||
#define TDI_PIN GPIO15
|
||||
#define TDO_PIN GPIO3
|
||||
|
||||
#define SWDIO_PORT JTAG_PORT
|
||||
#define SWCLK_PORT JTAG_PORT
|
||||
#define SWDIO_PIN TMS_PIN
|
||||
#define SWCLK_PIN TCK_PIN
|
||||
|
||||
#define TRST_PORT TDO_PORT
|
||||
#define TRST_PIN GPIO4
|
||||
#define SRST_PORT GPIOB
|
||||
#define SRST_PIN GPIO4
|
||||
|
||||
#define LED_PORT GPIOB
|
||||
#define LED_PORT_UART GPIOB
|
||||
#define LED_UART GPIO2
|
||||
|
||||
#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 stm32f107_usb_driver
|
||||
#define USB_IRQ NVIC_OTG_FS_IRQ
|
||||
#define USB_ISR otg_fs_isr
|
||||
/* Interrupt priorities. Low numbers are high priority.
|
||||
* For now USART1 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_TRACE (0 << 4)
|
||||
|
||||
#define USBUSART USART3
|
||||
#define USBUSART_CR1 USART3_CR1
|
||||
#define USBUSART_IRQ NVIC_USART3_IRQ
|
||||
#define USBUSART_APB_ENR RCC_APB1ENR
|
||||
#define USBUSART_CLK_ENABLE RCC_APB1ENR_USART3EN
|
||||
#define USBUSART_TX_PORT GPIOC
|
||||
#define USBUSART_TX_PIN GPIO10
|
||||
#define USBUSART_RX_PORT GPIOC
|
||||
#define USBUSART_RX_PIN GPIO11
|
||||
#define USBUSART_ISR usart3_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_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_TIM3EN)
|
||||
#define TRACE_IRQ NVIC_TIM3_IRQ
|
||||
#define TRACE_ISR tim3_isr
|
||||
|
||||
#define DEBUG(...)
|
||||
|
||||
extern uint8_t running_status;
|
||||
extern volatile uint32_t timeout_counter;
|
||||
|
||||
extern jmp_buf fatal_error_jmpbuf;
|
||||
|
||||
extern const char *morse_msg;
|
||||
|
||||
#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)
|
||||
#define SET_ERROR_STATE(state)
|
||||
|
||||
#define PLATFORM_SET_FATAL_ERROR_RECOVERY() {setjmp(fatal_error_jmpbuf);}
|
||||
#define PLATFORM_FATAL_ERROR(error) { \
|
||||
if(running_status) gdb_putpacketz("X1D"); \
|
||||
else gdb_putpacketz("EFF"); \
|
||||
running_status = 0; \
|
||||
target_list_free(); \
|
||||
morse("TARGET LOST.", 1); \
|
||||
longjmp(fatal_error_jmpbuf, (error)); \
|
||||
}
|
||||
|
||||
int platform_init(void);
|
||||
void morse(const char *msg, char repeat);
|
||||
const char *platform_target_voltage(void);
|
||||
int platform_hwversion(void);
|
||||
void platform_delay(uint32_t delay);
|
||||
|
||||
/* <cdcacm.c> */
|
||||
void cdcacm_init(void);
|
||||
/* Returns current usb configuration, or 0 if not configured. */
|
||||
int cdcacm_get_config(void);
|
||||
int cdcacm_get_dtr(void);
|
||||
|
||||
/* <platform.h> */
|
||||
void uart_usb_buf_drain(uint8_t ep);
|
||||
|
||||
/* Use newlib provided integer only stdio functions */
|
||||
#define sscanf siscanf
|
||||
#define sprintf siprintf
|
||||
#define vasprintf vasiprintf
|
||||
|
||||
#ifdef INLINE_GPIO
|
||||
static inline void _gpio_set(u32 gpioport, u16 gpios)
|
||||
{
|
||||
GPIO_BSRR(gpioport) = gpios;
|
||||
}
|
||||
#define gpio_set _gpio_set
|
||||
|
||||
static inline void _gpio_clear(u32 gpioport, u16 gpios)
|
||||
{
|
||||
GPIO_BSRR(gpioport) = gpios<<16;
|
||||
}
|
||||
#define gpio_clear _gpio_clear
|
||||
|
||||
static inline u16 _gpio_get(u32 gpioport, u16 gpios)
|
||||
{
|
||||
return (u16)GPIO_IDR(gpioport) & gpios;
|
||||
}
|
||||
#define gpio_get _gpio_get
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#define disconnect_usb() do {usbd_disconnect(usbdev,1); nvic_disable_irq(USB_IRQ);} while(0)
|
||||
void assert_boot_pin(void);
|
||||
#define setup_vbus_irq()
|
|
@ -93,6 +93,7 @@ static const char stm32hd_xml_memory_map[] = "<?xml version=\"1.0\"?>"
|
|||
#define FLASH_OBR (FPEC_BASE+0x1C)
|
||||
#define FLASH_WRPR (FPEC_BASE+0x20)
|
||||
|
||||
#define FLASH_CR_OBL_LAUNCH (1<<13)
|
||||
#define FLASH_CR_OPTWRE (1 << 9)
|
||||
#define FLASH_CR_STRT (1 << 6)
|
||||
#define FLASH_CR_OPTER (1 << 5)
|
||||
|
@ -104,6 +105,7 @@ static const char stm32hd_xml_memory_map[] = "<?xml version=\"1.0\"?>"
|
|||
|
||||
#define FLASH_OBP_RDP 0x1FFFF800
|
||||
#define FLASH_OBP_RDP_KEY 0x5aa5
|
||||
#define FLASH_OBP_RDP_KEY_F3 0x55AA
|
||||
|
||||
#define KEY1 0x45670123
|
||||
#define KEY2 0xCDEF89AB
|
||||
|
@ -153,10 +155,9 @@ uint16_t stm32f1_flash_write_stub[] = {
|
|||
|
||||
bool stm32f1_probe(struct target_s *target)
|
||||
{
|
||||
uint32_t idcode;
|
||||
|
||||
idcode = adiv5_ap_mem_read(adiv5_target_ap(target), DBGMCU_IDCODE);
|
||||
switch(idcode & 0xFFF) {
|
||||
target->idcode = adiv5_ap_mem_read(adiv5_target_ap(target), DBGMCU_IDCODE) & 0xfff;
|
||||
switch(target->idcode) {
|
||||
case 0x410: /* Medium density */
|
||||
case 0x412: /* Low denisty */
|
||||
case 0x420: /* Value Line, Low-/Medium density */
|
||||
|
@ -164,7 +165,7 @@ bool stm32f1_probe(struct target_s *target)
|
|||
target->xml_mem_map = stm32f1_xml_memory_map;
|
||||
target->flash_erase = stm32md_flash_erase;
|
||||
target->flash_write = stm32f1_flash_write;
|
||||
target_add_commands(target, stm32f1_cmd_list, "STM32");
|
||||
target_add_commands(target, stm32f1_cmd_list, "STM32 LD/MD");
|
||||
return true;
|
||||
case 0x414: /* High density */
|
||||
case 0x418: /* Connectivity Line */
|
||||
|
@ -173,7 +174,7 @@ bool stm32f1_probe(struct target_s *target)
|
|||
target->xml_mem_map = stm32hd_xml_memory_map;
|
||||
target->flash_erase = stm32hd_flash_erase;
|
||||
target->flash_write = stm32f1_flash_write;
|
||||
target_add_commands(target, stm32f1_cmd_list, "STM32");
|
||||
target_add_commands(target, stm32f1_cmd_list, "STM32 HD/CL");
|
||||
return true;
|
||||
case 0x422: /* STM32F30x */
|
||||
case 0x432: /* STM32F37x */
|
||||
|
@ -181,18 +182,18 @@ bool stm32f1_probe(struct target_s *target)
|
|||
target->xml_mem_map = stm32hd_xml_memory_map;
|
||||
target->flash_erase = stm32hd_flash_erase;
|
||||
target->flash_write = stm32f1_flash_write;
|
||||
target_add_commands(target, stm32f1_cmd_list, "STM32");
|
||||
target_add_commands(target, stm32f1_cmd_list, "STM32F3");
|
||||
return true;
|
||||
}
|
||||
|
||||
idcode = adiv5_ap_mem_read(adiv5_target_ap(target), DBGMCU_IDCODE_F0);
|
||||
switch(idcode & 0xFFF) {
|
||||
target->idcode = adiv5_ap_mem_read(adiv5_target_ap(target), DBGMCU_IDCODE_F0) & 0xfff;
|
||||
switch(target->idcode) {
|
||||
case 0x440: /* STM32F0 */
|
||||
target->driver = stm32f0_driver_str;
|
||||
target->xml_mem_map = stm32f1_xml_memory_map;
|
||||
target->flash_erase = stm32md_flash_erase;
|
||||
target->flash_write = stm32f1_flash_write;
|
||||
target_add_commands(target, stm32f1_cmd_list, "STM32");
|
||||
target_add_commands(target, stm32f1_cmd_list, "STM32F0");
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -338,15 +339,24 @@ static bool stm32f1_option_write(target *t, uint32_t addr, uint16_t value)
|
|||
static bool stm32f1_cmd_option(target *t, int argc, char *argv[])
|
||||
{
|
||||
uint32_t addr, val;
|
||||
|
||||
uint32_t flash_obp_rdp_key;
|
||||
ADIv5_AP_t *ap = adiv5_target_ap(t);
|
||||
|
||||
switch(t->idcode) {
|
||||
case 0x422: /* STM32F30x */
|
||||
case 0x432: /* STM32F37x */
|
||||
case 0x440: /* STM32F0 */
|
||||
flash_obp_rdp_key = FLASH_OBP_RDP_KEY_F3;
|
||||
break;
|
||||
default: flash_obp_rdp_key = FLASH_OBP_RDP_KEY;
|
||||
}
|
||||
stm32f1_flash_unlock(ap);
|
||||
adiv5_ap_mem_write(ap, FLASH_OPTKEYR, KEY1);
|
||||
adiv5_ap_mem_write(ap, FLASH_OPTKEYR, KEY2);
|
||||
|
||||
if ((argc == 2) && !strcmp(argv[1], "erase")) {
|
||||
stm32f1_option_erase(t);
|
||||
stm32f1_option_write(t, FLASH_OBP_RDP, FLASH_OBP_RDP_KEY);
|
||||
stm32f1_option_write(t, FLASH_OBP_RDP, flash_obp_rdp_key);
|
||||
} else if (argc == 3) {
|
||||
addr = strtol(argv[1], NULL, 0);
|
||||
val = strtol(argv[2], NULL, 0);
|
||||
|
@ -356,6 +366,15 @@ static bool stm32f1_cmd_option(target *t, int argc, char *argv[])
|
|||
gdb_out("usage: monitor option <addr> <value>\n");
|
||||
}
|
||||
|
||||
if (0 && flash_obp_rdp_key == FLASH_OBP_RDP_KEY_F3) {
|
||||
/* Reload option bytes on F0 and F3*/
|
||||
val = adiv5_ap_mem_read(ap, FLASH_CR);
|
||||
val |= FLASH_CR_OBL_LAUNCH;
|
||||
stm32f1_option_write(t, FLASH_CR, val);
|
||||
val &= ~FLASH_CR_OBL_LAUNCH;
|
||||
stm32f1_option_write(t, FLASH_CR, val);
|
||||
}
|
||||
|
||||
for (int i = 0; i < 0xf; i += 4) {
|
||||
addr = 0x1ffff800 + i;
|
||||
val = adiv5_ap_mem_read(ap, addr);
|
||||
|
|
|
@ -36,6 +36,15 @@
|
|||
#include "general.h"
|
||||
#include "adiv5.h"
|
||||
#include "target.h"
|
||||
#include "command.h"
|
||||
|
||||
static bool stm32f4_cmd_option(target *t, int argc, char *argv[]);
|
||||
|
||||
const struct command_s stm32f4_cmd_list[] = {
|
||||
{"option", (cmd_handler)stm32f4_cmd_option, "Manipulate option bytes"},
|
||||
{NULL, NULL, NULL}
|
||||
};
|
||||
|
||||
|
||||
static int stm32f4_flash_erase(struct target_s *target, uint32_t addr, int len);
|
||||
static int stm32f4_flash_write(struct target_s *target, uint32_t dest,
|
||||
|
@ -85,9 +94,16 @@ static const char stm32f4_xml_memory_map[] = "<?xml version=\"1.0\"?>"
|
|||
|
||||
#define FLASH_SR_BSY (1 << 16)
|
||||
|
||||
#define FLASH_OPTCR_OPTLOCK (1 << 0)
|
||||
#define FLASH_OPTCR_OPTSTRT (1 << 1)
|
||||
#define FLASH_OPTCR_RESERVED 0xf0000013
|
||||
|
||||
#define KEY1 0x45670123
|
||||
#define KEY2 0xCDEF89AB
|
||||
|
||||
#define OPTKEY1 0x08192A3B
|
||||
#define OPTKEY2 0x4C5D6E7F
|
||||
|
||||
#define SR_ERROR_MASK 0xF2
|
||||
#define SR_EOP 0x01
|
||||
|
||||
|
@ -145,6 +161,7 @@ bool stm32f4_probe(struct target_s *target)
|
|||
target->xml_mem_map = stm32f4_xml_memory_map;
|
||||
target->flash_erase = stm32f4_flash_erase;
|
||||
target->flash_write = stm32f4_flash_write;
|
||||
target_add_commands(target, stm32f4_cmd_list, "STM32F4");
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
@ -234,3 +251,45 @@ static int stm32f4_flash_write(struct target_s *target, uint32_t dest,
|
|||
return 0;
|
||||
}
|
||||
|
||||
static bool stm32f4_option_write(target *t, uint32_t value)
|
||||
{
|
||||
ADIv5_AP_t *ap = adiv5_target_ap(t);
|
||||
|
||||
adiv5_ap_mem_write(ap, FLASH_OPTKEYR, OPTKEY1);
|
||||
adiv5_ap_mem_write(ap, FLASH_OPTKEYR, OPTKEY2);
|
||||
value &= ~FLASH_OPTCR_RESERVED;
|
||||
while(adiv5_ap_mem_read(ap, FLASH_SR) & FLASH_SR_BSY)
|
||||
if(target_check_error(t))
|
||||
return -1;
|
||||
|
||||
/* WRITE option bytes instruction */
|
||||
adiv5_ap_mem_write(ap, FLASH_OPTCR, value);
|
||||
adiv5_ap_mem_write(ap, FLASH_OPTCR, value | FLASH_OPTCR_OPTSTRT);
|
||||
/* Read FLASH_SR to poll for BSY bit */
|
||||
while(adiv5_ap_mem_read(ap, FLASH_SR) & FLASH_SR_BSY)
|
||||
if(target_check_error(t))
|
||||
return false;
|
||||
adiv5_ap_mem_write(ap, FLASH_OPTCR, value | FLASH_OPTCR_OPTLOCK);
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool stm32f4_cmd_option(target *t, int argc, char *argv[])
|
||||
{
|
||||
uint32_t addr, val;
|
||||
|
||||
ADIv5_AP_t *ap = adiv5_target_ap(t);
|
||||
|
||||
if ((argc == 3) && !strcmp(argv[1], "write")) {
|
||||
val = strtoul(argv[2], NULL, 0);
|
||||
stm32f4_option_write(t, val);
|
||||
} else {
|
||||
gdb_out("usage: monitor option write <value>\n");
|
||||
}
|
||||
|
||||
for (int i = 0; i < 0xf; i += 8) {
|
||||
addr = 0x1fffC000 + i;
|
||||
val = adiv5_ap_mem_read(ap, addr);
|
||||
gdb_outf("0x%08X: 0x%04X\n", addr, val & 0xFFFF);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue