Add support for HydraBus (tested with SWD with STM32F405 and SWD+JTAG with LPC4330 M0/M4)
This commit is contained in:
parent
c731c6ece3
commit
9f0c29d329
|
@ -0,0 +1,142 @@
|
||||||
|
#!/usr/bin/python2
|
||||||
|
|
||||||
|
# Written by Antonio Galea - 2010/11/18
|
||||||
|
# Distributed under Gnu LGPL 3.0
|
||||||
|
# see http://www.gnu.org/licenses/lgpl-3.0.txt
|
||||||
|
|
||||||
|
import sys,struct,zlib,os
|
||||||
|
from optparse import OptionParser
|
||||||
|
from intelhex import IntelHex
|
||||||
|
|
||||||
|
DEFAULT_DEVICE="0x0483:0xdf11"
|
||||||
|
|
||||||
|
def named(tuple,names):
|
||||||
|
return dict(zip(names.split(),tuple))
|
||||||
|
def consume(fmt,data,names):
|
||||||
|
n = struct.calcsize(fmt)
|
||||||
|
return named(struct.unpack(fmt,data[:n]),names),data[n:]
|
||||||
|
def cstring(string):
|
||||||
|
return string.split('\0',1)[0]
|
||||||
|
def compute_crc(data):
|
||||||
|
return 0xFFFFFFFF & -zlib.crc32(data) -1
|
||||||
|
|
||||||
|
def parse(file,dump_images=False):
|
||||||
|
print 'File: "%s"' % file
|
||||||
|
data = open(file,'rb').read()
|
||||||
|
crc = compute_crc(data[:-4])
|
||||||
|
prefix, data = consume('<5sBIB',data,'signature version size targets')
|
||||||
|
print '%(signature)s v%(version)d, image size: %(size)d, targets: %(targets)d' % prefix
|
||||||
|
for t in range(prefix['targets']):
|
||||||
|
tprefix, data = consume('<6sBI255s2I',data,'signature altsetting named name size elements')
|
||||||
|
tprefix['num'] = t
|
||||||
|
if tprefix['named']:
|
||||||
|
tprefix['name'] = cstring(tprefix['name'])
|
||||||
|
else:
|
||||||
|
tprefix['name'] = ''
|
||||||
|
print '%(signature)s %(num)d, alt setting: %(altsetting)s, name: "%(name)s", size: %(size)d, elements: %(elements)d' % tprefix
|
||||||
|
tsize = tprefix['size']
|
||||||
|
target, data = data[:tsize], data[tsize:]
|
||||||
|
for e in range(tprefix['elements']):
|
||||||
|
eprefix, target = consume('<2I',target,'address size')
|
||||||
|
eprefix['num'] = e
|
||||||
|
print ' %(num)d, address: 0x%(address)08x, size: %(size)d' % eprefix
|
||||||
|
esize = eprefix['size']
|
||||||
|
image, target = target[:esize], target[esize:]
|
||||||
|
if dump_images:
|
||||||
|
out = '%s.target%d.image%d.bin' % (file,t,e)
|
||||||
|
open(out,'wb').write(image)
|
||||||
|
print ' DUMPED IMAGE TO "%s"' % out
|
||||||
|
if len(target):
|
||||||
|
print "target %d: PARSE ERROR" % t
|
||||||
|
suffix = named(struct.unpack('<4H3sBI',data[:16]),'device product vendor dfu ufd len crc')
|
||||||
|
print 'usb: %(vendor)04x:%(product)04x, device: 0x%(device)04x, dfu: 0x%(dfu)04x, %(ufd)s, %(len)d, 0x%(crc)08x' % suffix
|
||||||
|
if crc != suffix['crc']:
|
||||||
|
print "CRC ERROR: computed crc32 is 0x%08x" % crc
|
||||||
|
data = data[16:]
|
||||||
|
if data:
|
||||||
|
print "PARSE ERROR"
|
||||||
|
|
||||||
|
def build(file,targets,device=DEFAULT_DEVICE):
|
||||||
|
data = ''
|
||||||
|
for t,target in enumerate(targets):
|
||||||
|
tdata = ''
|
||||||
|
for image in target:
|
||||||
|
tdata += struct.pack('<2I',image['address'],len(image['data']))+image['data']
|
||||||
|
tdata = struct.pack('<6sBI255s2I','Target',0,1,'ST...',len(tdata),len(target)) + tdata
|
||||||
|
data += tdata
|
||||||
|
data = struct.pack('<5sBIB','DfuSe',1,len(data)+11,len(targets)) + data
|
||||||
|
v,d=map(lambda x: int(x,0) & 0xFFFF, device.split(':',1))
|
||||||
|
data += struct.pack('<4H3sB',0,d,v,0x011a,'UFD',16)
|
||||||
|
crc = compute_crc(data)
|
||||||
|
data += struct.pack('<I',crc)
|
||||||
|
open(file,'wb').write(data)
|
||||||
|
|
||||||
|
if __name__=="__main__":
|
||||||
|
usage = """
|
||||||
|
%prog [-d|--dump] infile.dfu
|
||||||
|
%prog {-b|--build} address:file.bin [-b address:file.bin ...] [{-D|--device}=vendor:device] outfile.dfu
|
||||||
|
%prog {-i|--ihex} file.hex [-i file.hex ...] [{-D|--device}=vendor:device] outfile.dfu"""
|
||||||
|
|
||||||
|
parser = OptionParser(usage=usage)
|
||||||
|
parser.add_option("-b", "--build", action="append", dest="binfiles",
|
||||||
|
help="build a DFU file from given BINFILES", metavar="BINFILES")
|
||||||
|
parser.add_option("-i", "--ihex", action="append", dest="hexfiles",
|
||||||
|
help="build a DFU file from given HEXFILES", metavar="HEXFILES")
|
||||||
|
parser.add_option("-D", "--device", action="store", dest="device",
|
||||||
|
help="build for DEVICE, defaults to %s" % DEFAULT_DEVICE, metavar="DEVICE")
|
||||||
|
parser.add_option("-d", "--dump", action="store_true", dest="dump_images",
|
||||||
|
default=False, help="dump contained images to current directory")
|
||||||
|
(options, args) = parser.parse_args()
|
||||||
|
|
||||||
|
if (options.binfiles or options.hexfiles) and len(args)==1:
|
||||||
|
target = []
|
||||||
|
|
||||||
|
if options.binfiles:
|
||||||
|
for arg in options.binfiles:
|
||||||
|
try:
|
||||||
|
address,binfile = arg.split(':',1)
|
||||||
|
except ValueError:
|
||||||
|
print "Address:file couple '%s' invalid." % arg
|
||||||
|
sys.exit(1)
|
||||||
|
try:
|
||||||
|
address = int(address,0) & 0xFFFFFFFF
|
||||||
|
except ValueError:
|
||||||
|
print "Address %s invalid." % address
|
||||||
|
sys.exit(1)
|
||||||
|
if not os.path.isfile(binfile):
|
||||||
|
print "Unreadable file '%s'." % binfile
|
||||||
|
sys.exit(1)
|
||||||
|
target.append({ 'address': address, 'data': open(binfile,'rb').read() })
|
||||||
|
|
||||||
|
if options.hexfiles:
|
||||||
|
for hex in options.hexfiles:
|
||||||
|
ih = IntelHex(hex)
|
||||||
|
address = ih.minaddr()
|
||||||
|
data = ih.tobinstr()
|
||||||
|
try:
|
||||||
|
address = address & 0xFFFFFFFF
|
||||||
|
except ValueError:
|
||||||
|
print "Address %s invalid." % address
|
||||||
|
sys.exit(1)
|
||||||
|
target.append({ 'address': address, 'data': data })
|
||||||
|
|
||||||
|
outfile = args[0]
|
||||||
|
device = DEFAULT_DEVICE
|
||||||
|
if options.device:
|
||||||
|
device=options.device
|
||||||
|
try:
|
||||||
|
v,d=map(lambda x: int(x,0) & 0xFFFF, device.split(':',1))
|
||||||
|
except:
|
||||||
|
print "Invalid device '%s'." % device
|
||||||
|
sys.exit(1)
|
||||||
|
build(outfile,[target],device)
|
||||||
|
elif len(args)==1:
|
||||||
|
infile = args[0]
|
||||||
|
if not os.path.isfile(infile):
|
||||||
|
print "Unreadable file '%s'." % infile
|
||||||
|
sys.exit(1)
|
||||||
|
parse(infile, dump_images=options.dump_images)
|
||||||
|
else:
|
||||||
|
parser.print_help()
|
||||||
|
sys.exit(1)
|
||||||
|
|
|
@ -0,0 +1,38 @@
|
||||||
|
CROSS_COMPILE ?= arm-none-eabi-
|
||||||
|
CC = $(CROSS_COMPILE)gcc
|
||||||
|
OBJCOPY = $(CROSS_COMPILE)objcopy
|
||||||
|
|
||||||
|
CFLAGS += -Istm32/include -mcpu=cortex-m4 -mthumb \
|
||||||
|
-mfloat-abi=hard -mfpu=fpv4-sp-d16 \
|
||||||
|
-DSTM32F4 -DHYDRABUS -I../libopencm3/include \
|
||||||
|
-Iplatforms/stm32
|
||||||
|
|
||||||
|
LDFLAGS = -lopencm3_stm32f4 -Wl,--defsym,_stack=0x20006000 \
|
||||||
|
-Wl,-T,platforms/stm32/f4discovery.ld -nostartfiles -lc -lnosys \
|
||||||
|
-Wl,-Map=mapfile -mthumb -mcpu=cortex-m4 -Wl,-gc-sections \
|
||||||
|
-mfloat-abi=hard -mfpu=fpv4-sp-d16 \
|
||||||
|
-L../libopencm3/lib
|
||||||
|
|
||||||
|
VPATH += platforms/stm32
|
||||||
|
|
||||||
|
SRC += cdcacm.c \
|
||||||
|
platform.c \
|
||||||
|
traceswo.c \
|
||||||
|
usbuart.c \
|
||||||
|
serialno.c \
|
||||||
|
timing.c \
|
||||||
|
|
||||||
|
all: blackmagic.bin blackmagic.hex blackmagic.dfu
|
||||||
|
|
||||||
|
blackmagic.bin: blackmagic
|
||||||
|
$(OBJCOPY) -O binary $^ $@
|
||||||
|
|
||||||
|
blackmagic.hex: blackmagic.bin
|
||||||
|
$(OBJCOPY) -O ihex blackmagic $@
|
||||||
|
|
||||||
|
blackmagic.dfu: blackmagic.hex
|
||||||
|
@echo Creating $@
|
||||||
|
@python ../scripts/dfu-convert.py -i $< $@
|
||||||
|
|
||||||
|
host_clean:
|
||||||
|
-rm blackmagic.bin blackmagic.hex blackmagic.dfu
|
|
@ -0,0 +1,30 @@
|
||||||
|
Connections
|
||||||
|
====================
|
||||||
|
* PA0: User button to force system bootloader entry with reset (enter USB DFU)
|
||||||
|
|
||||||
|
* JTAG/SWD
|
||||||
|
* PC0: TMS/SWDIO
|
||||||
|
* PC1: TCK/SWCLK
|
||||||
|
* PC2: TDI
|
||||||
|
* PC3: TDO/TRACESWO
|
||||||
|
* PC4: SRST (NRST/System Reset)
|
||||||
|
* PC5: TRST (optional Test Reset)
|
||||||
|
|
||||||
|
* Green Led(ULED/PA4): Indicator that system bootloader is entered via BMP
|
||||||
|
|
||||||
|
* USB USART
|
||||||
|
* PA9: USART1 TX (usbuart_xxx)
|
||||||
|
* PA10: USART1 RX (usbuart_xxx)
|
||||||
|
|
||||||
|
How to Build
|
||||||
|
============
|
||||||
|
```
|
||||||
|
cd blackmagic/src
|
||||||
|
make PROBE_HOST=hydrabus
|
||||||
|
```
|
||||||
|
|
||||||
|
How to Flash the firmware with Windows
|
||||||
|
========================================
|
||||||
|
* After build:
|
||||||
|
* 1) Force the F4 into system bootloader mode by jumpering "BOOT0" to "3V3" and "PB2/BOOT1" to "GND" and reset (RESET button). System bootloader should appear.
|
||||||
|
* 2) Double click on "update_fw_usb_dfu_blackmagic.bat"
|
|
@ -0,0 +1,103 @@
|
||||||
|
/*
|
||||||
|
* This file is part of the Black Magic Debug project.
|
||||||
|
*
|
||||||
|
* Copyright (C) 2011 Black Sphere Technologies Ltd.
|
||||||
|
* Written by Gareth McMullin <gareth@blacksphere.co.nz>
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* This file implements the platform specific functions for the STM32
|
||||||
|
* implementation.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "general.h"
|
||||||
|
#include "cdcacm.h"
|
||||||
|
#include "usbuart.h"
|
||||||
|
#include "morse.h"
|
||||||
|
|
||||||
|
#include <libopencm3/stm32/f4/rcc.h>
|
||||||
|
#include <libopencm3/cm3/scb.h>
|
||||||
|
#include <libopencm3/cm3/nvic.h>
|
||||||
|
#include <libopencm3/stm32/exti.h>
|
||||||
|
#include <libopencm3/stm32/usart.h>
|
||||||
|
#include <libopencm3/stm32/syscfg.h>
|
||||||
|
#include <libopencm3/usb/usbd.h>
|
||||||
|
|
||||||
|
jmp_buf fatal_error_jmpbuf;
|
||||||
|
|
||||||
|
void platform_init(void)
|
||||||
|
{
|
||||||
|
/* Check the USER button*/
|
||||||
|
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPAEN);
|
||||||
|
if(gpio_get(GPIOA, GPIO0)) {
|
||||||
|
platform_request_boot();
|
||||||
|
scb_reset_core();
|
||||||
|
}
|
||||||
|
|
||||||
|
rcc_clock_setup_hse_3v3(&hse_8mhz_3v3[CLOCK_3V3_48MHZ]);
|
||||||
|
|
||||||
|
/* Enable peripherals */
|
||||||
|
rcc_peripheral_enable_clock(&RCC_AHB2ENR, RCC_AHB2ENR_OTGFSEN);
|
||||||
|
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPCEN);
|
||||||
|
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPDEN);
|
||||||
|
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_CRCEN);
|
||||||
|
|
||||||
|
/* 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);
|
||||||
|
|
||||||
|
GPIOC_OSPEEDR &=~0xF30;
|
||||||
|
GPIOC_OSPEEDR |= 0xA20;
|
||||||
|
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_BOOTLOADER);
|
||||||
|
|
||||||
|
platform_timing_init();
|
||||||
|
usbuart_init();
|
||||||
|
cdcacm_init();
|
||||||
|
}
|
||||||
|
|
||||||
|
const char *platform_target_voltage(void)
|
||||||
|
{
|
||||||
|
return "ABSENT!";
|
||||||
|
}
|
||||||
|
|
||||||
|
void platform_request_boot(void)
|
||||||
|
{
|
||||||
|
/* Disconnect USB cable */
|
||||||
|
usbd_disconnect(usbdev, 1);
|
||||||
|
nvic_disable_irq(USB_IRQ);
|
||||||
|
|
||||||
|
/* Assert blue LED as indicator we are in the bootloader */
|
||||||
|
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPDEN);
|
||||||
|
gpio_mode_setup(LED_PORT, GPIO_MODE_OUTPUT,
|
||||||
|
GPIO_PUPD_NONE, LED_BOOTLOADER);
|
||||||
|
gpio_set(LED_PORT, LED_BOOTLOADER);
|
||||||
|
|
||||||
|
/* 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;
|
||||||
|
}
|
||||||
|
|
|
@ -0,0 +1,171 @@
|
||||||
|
/*
|
||||||
|
* This file is part of the Black Magic Debug project.
|
||||||
|
*
|
||||||
|
* Copyright (C) 2015 Black Sphere Technologies Ltd.
|
||||||
|
* Written by Gareth McMullin <gareth@blacksphere.co.nz>
|
||||||
|
* Copyright (C) 2015 Benjamin Vernoux <bvernoux@gmail.com>
|
||||||
|
*
|
||||||
|
* 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 "gdb_packet.h"
|
||||||
|
#include "gpio.h"
|
||||||
|
#include "morse.h"
|
||||||
|
#include "timing.h"
|
||||||
|
|
||||||
|
#include <setjmp.h>
|
||||||
|
|
||||||
|
#define INLINE_GPIO
|
||||||
|
#define CDCACM_PACKET_SIZE 64
|
||||||
|
#define PLATFORM_HAS_TRACESWO
|
||||||
|
#define BOARD_IDENT "Black Magic Probe (HydraBus), (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")"
|
||||||
|
#define BOARD_IDENT_DFU "Black Magic (Upgrade) for HydraBus, (Firmware 1.5" VERSION_SUFFIX ", build " BUILDDATE ")"
|
||||||
|
#define DFU_IDENT "Black Magic Firmware Upgrade (HydraBus)"
|
||||||
|
#define DFU_IFACE_STRING "@Internal Flash /0x08000000/1*016Ka,3*016Kg,1*064Kg,7*128Kg"
|
||||||
|
|
||||||
|
/* Important pin mappings for STM32 implementation:
|
||||||
|
*
|
||||||
|
* LED0 = PA4 (Green LED : Running)
|
||||||
|
* LED0 = PA4 (Green LED : Idle)
|
||||||
|
* LED0 = PA4 (Green LED : Error)
|
||||||
|
* LED0 = PA4 (Green LED : Bootloader active)
|
||||||
|
*
|
||||||
|
* TMS = PC0 (SWDIO)
|
||||||
|
* TCK = PC1 (SWCLK)
|
||||||
|
* TDO = PC2 (input for TRACESWO)
|
||||||
|
* TDI = PC3
|
||||||
|
* nSRST = PC4 (nRST /RESET / System Reset)
|
||||||
|
* nTRST = PC5 (Test Reset optional)
|
||||||
|
*
|
||||||
|
* USB VBUS detect: PB13
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Hardware definitions... */
|
||||||
|
#define JTAG_PORT GPIOC
|
||||||
|
#define TMS_PORT JTAG_PORT
|
||||||
|
#define TCK_PORT JTAG_PORT
|
||||||
|
#define TDO_PORT JTAG_PORT
|
||||||
|
#define TDI_PORT JTAG_PORT
|
||||||
|
|
||||||
|
#define TMS_PIN GPIO0
|
||||||
|
#define TCK_PIN GPIO1
|
||||||
|
#define TDO_PIN GPIO2
|
||||||
|
#define TDI_PIN GPIO3
|
||||||
|
|
||||||
|
#define SWDIO_PORT JTAG_PORT
|
||||||
|
#define SWCLK_PORT JTAG_PORT
|
||||||
|
#define SWDIO_PIN TMS_PIN
|
||||||
|
#define SWCLK_PIN TCK_PIN
|
||||||
|
|
||||||
|
#define SRST_PORT GPIOC
|
||||||
|
#define SRST_PIN GPIO4
|
||||||
|
|
||||||
|
#define TRST_PORT GPIOC
|
||||||
|
#define TRST_PIN GPIO5
|
||||||
|
|
||||||
|
#define LED_PORT GPIOA
|
||||||
|
#define LED_PORT_UART GPIOA
|
||||||
|
#define LED_UART GPIO4
|
||||||
|
#define LED_IDLE_RUN GPIO4
|
||||||
|
#define LED_ERROR GPIO4
|
||||||
|
#define LED_BOOTLOADER GPIO4
|
||||||
|
|
||||||
|
#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_USBUSART_TIM (3 << 4)
|
||||||
|
#define IRQ_PRI_TRACE (0 << 4)
|
||||||
|
|
||||||
|
#define USBUSART USART1
|
||||||
|
#define USBUSART_CR1 USART1_CR1
|
||||||
|
#define USBUSART_IRQ NVIC_USART1_IRQ
|
||||||
|
#define USBUSART_CLK RCC_USART1
|
||||||
|
#define USBUSART_TX_PORT GPIOA
|
||||||
|
#define USBUSART_TX_PIN GPIO9
|
||||||
|
#define USBUSART_RX_PORT GPIOA
|
||||||
|
#define USBUSART_RX_PIN GPIO10
|
||||||
|
#define USBUSART_ISR usart1_isr
|
||||||
|
#define USBUSART_TIM TIM4
|
||||||
|
#define USBUSART_TIM_CLK_EN() rcc_periph_clock_enable(RCC_TIM4)
|
||||||
|
#define USBUSART_TIM_IRQ NVIC_TIM4_IRQ
|
||||||
|
#define USBUSART_TIM_ISR tim4_isr
|
||||||
|
|
||||||
|
#define UART_PIN_SETUP() do { \
|
||||||
|
gpio_mode_setup(USBUSART_TX_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, \
|
||||||
|
USBUSART_TX_PIN); \
|
||||||
|
gpio_mode_setup(USBUSART_RX_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, \
|
||||||
|
USBUSART_RX_PIN); \
|
||||||
|
gpio_set_af(USBUSART_TX_PORT, GPIO_AF7, USBUSART_TX_PIN); \
|
||||||
|
gpio_set_af(USBUSART_RX_PORT, GPIO_AF7, USBUSART_RX_PIN); \
|
||||||
|
} while(0)
|
||||||
|
|
||||||
|
#define TRACE_TIM TIM3
|
||||||
|
#define TRACE_TIM_CLK_EN() rcc_periph_clock_enable(RCC_TIM3)
|
||||||
|
#define TRACE_IRQ NVIC_TIM3_IRQ
|
||||||
|
#define TRACE_ISR tim3_isr
|
||||||
|
|
||||||
|
#define DEBUG(...)
|
||||||
|
|
||||||
|
extern jmp_buf fatal_error_jmpbuf;
|
||||||
|
|
||||||
|
#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)); \
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline int platform_hwversion(void)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Use newlib provided integer only stdio functions */
|
||||||
|
#define sscanf siscanf
|
||||||
|
#define sprintf siprintf
|
||||||
|
#define vasprintf vasiprintf
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -0,0 +1,78 @@
|
||||||
|
/*
|
||||||
|
* This file is part of the Black Magic Debug project.
|
||||||
|
*
|
||||||
|
* Copyright (C) 2013 Gareth McMullin <gareth@blacksphere.co.nz>
|
||||||
|
* Copyright (C) 2015 Benjamin Vernoux <bvernoux@gmail.com>
|
||||||
|
*
|
||||||
|
* 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>
|
||||||
|
#include <libopencm3/cm3/scb.h>
|
||||||
|
|
||||||
|
#include "usbdfu.h"
|
||||||
|
|
||||||
|
extern void dfu_protect_enable(void);
|
||||||
|
|
||||||
|
void dfu_detach(void)
|
||||||
|
{
|
||||||
|
/* USB device must detach, we just reset... */
|
||||||
|
scb_reset_system();
|
||||||
|
}
|
||||||
|
|
||||||
|
int main(void)
|
||||||
|
{
|
||||||
|
/* Check the force bootloader pin*/
|
||||||
|
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPAEN);
|
||||||
|
if(!gpio_get(GPIOA, GPIO0))
|
||||||
|
dfu_jump_app_if_valid();
|
||||||
|
|
||||||
|
dfu_protect_enable();
|
||||||
|
|
||||||
|
/* Set up clock*/
|
||||||
|
rcc_clock_setup_hse_3v3(&hse_8mhz_3v3[CLOCK_3V3_168MHZ]);
|
||||||
|
systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8);
|
||||||
|
systick_set_reload(2100000);
|
||||||
|
|
||||||
|
systick_interrupt_enable();
|
||||||
|
systick_counter_enable();
|
||||||
|
|
||||||
|
/* Handle LED */
|
||||||
|
rcc_peripheral_enable_clock(&RCC_AHB1ENR, RCC_AHB1ENR_IOPDEN);
|
||||||
|
gpio_clear(GPIOA, GPIO4);
|
||||||
|
gpio_mode_setup(GPIOA, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE,
|
||||||
|
GPIO4);
|
||||||
|
|
||||||
|
/* Set up USB*/
|
||||||
|
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);
|
||||||
|
dfu_init(&stm32f107_usb_driver, DFU_MODE);
|
||||||
|
|
||||||
|
dfu_main();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void sys_tick_handler(void)
|
||||||
|
{
|
||||||
|
gpio_toggle(GPIOA, GPIO4); /* Green LED on/off */
|
||||||
|
}
|
||||||
|
|
Loading…
Reference in New Issue