stm32: Add new component, the mboot bootloader.
Mboot is a custom bootloader for STM32 MCUs. It can provide a USB DFU interface on either the FS or HS peripherals, as well as a custom I2C bootloader interface.
This commit is contained in:
parent
f47eeab0ad
commit
15ddc20436
|
@ -0,0 +1,189 @@
|
|||
# Select the board to build for: if not given on the command line,
|
||||
# then default to PYBV10.
|
||||
BOARD ?= PYBV10
|
||||
ifeq ($(wildcard ../boards/$(BOARD)/.),)
|
||||
$(error Invalid BOARD specified)
|
||||
endif
|
||||
|
||||
# If the build directory is not given, make it reflect the board name.
|
||||
BUILD ?= build-$(BOARD)
|
||||
|
||||
include ../../../py/mkenv.mk
|
||||
include ../boards/$(BOARD)/mpconfigboard.mk
|
||||
|
||||
CMSIS_DIR=$(TOP)/lib/stm32lib/CMSIS/STM32$(MCU_SERIES_UPPER)xx/Include
|
||||
MCU_SERIES_UPPER = $(shell echo $(MCU_SERIES) | tr '[:lower:]' '[:upper:]')
|
||||
HAL_DIR=lib/stm32lib/STM32$(MCU_SERIES_UPPER)xx_HAL_Driver
|
||||
USBDEV_DIR=usbdev
|
||||
DFU=$(TOP)/tools/dfu.py
|
||||
PYDFU ?= $(TOP)/tools/pydfu.py
|
||||
DEVICE=0483:df11
|
||||
STFLASH ?= st-flash
|
||||
OPENOCD ?= openocd
|
||||
OPENOCD_CONFIG ?= boards/openocd_stm32f4.cfg
|
||||
|
||||
CROSS_COMPILE = arm-none-eabi-
|
||||
|
||||
INC += -I.
|
||||
INC += -I..
|
||||
INC += -I$(TOP)
|
||||
INC += -I$(BUILD)
|
||||
INC += -I$(TOP)/lib/cmsis/inc
|
||||
INC += -I$(CMSIS_DIR)/
|
||||
INC += -I$(TOP)/$(HAL_DIR)/Inc
|
||||
INC += -I../$(USBDEV_DIR)/core/inc -I../$(USBDEV_DIR)/class/inc
|
||||
|
||||
# Basic Cortex-M flags
|
||||
CFLAGS_CORTEX_M = -mthumb
|
||||
|
||||
# Options for particular MCU series
|
||||
CFLAGS_MCU_f4 = $(CFLAGS_CORTEX_M) -mtune=cortex-m4 -mcpu=cortex-m4
|
||||
CFLAGS_MCU_f7 = $(CFLAGS_CORTEX_M) -mtune=cortex-m7 -mcpu=cortex-m7
|
||||
CFLAGS_MCU_l4 = $(CFLAGS_CORTEX_M) -mtune=cortex-m4 -mcpu=cortex-m4
|
||||
|
||||
CFLAGS = $(INC) -Wall -Wpointer-arith -Werror -std=gnu99 -nostdlib $(CFLAGS_MOD) $(CFLAGS_EXTRA)
|
||||
CFLAGS += -D$(CMSIS_MCU)
|
||||
CFLAGS += $(CFLAGS_MCU_$(MCU_SERIES))
|
||||
CFLAGS += $(COPT)
|
||||
CFLAGS += -I../boards/$(BOARD)
|
||||
CFLAGS += -DSTM32_HAL_H='<stm32$(MCU_SERIES)xx_hal.h>'
|
||||
CFLAGS += -DBOARD_$(BOARD)
|
||||
CFLAGS += -DAPPLICATION_ADDR=$(TEXT0_ADDR)
|
||||
|
||||
LDFLAGS = -nostdlib -L . -T stm32_generic.ld -Map=$(@:.elf=.map) --cref
|
||||
LIBS = $(shell $(CC) $(CFLAGS) -print-libgcc-file-name)
|
||||
|
||||
# Remove uncalled code from the final image.
|
||||
CFLAGS += -fdata-sections -ffunction-sections
|
||||
LDFLAGS += --gc-sections
|
||||
|
||||
# Debugging/Optimization
|
||||
ifeq ($(DEBUG), 1)
|
||||
CFLAGS += -g -DPENDSV_DEBUG
|
||||
COPT = -O0
|
||||
else
|
||||
COPT += -Os -DNDEBUG
|
||||
endif
|
||||
|
||||
SRC_LIB = $(addprefix lib/,\
|
||||
libc/string0.c \
|
||||
)
|
||||
|
||||
SRC_C = \
|
||||
main.c \
|
||||
drivers/bus/softspi.c \
|
||||
drivers/bus/softqspi.c \
|
||||
drivers/memory/spiflash.c \
|
||||
ports/stm32/i2cslave.c \
|
||||
ports/stm32/qspi.c \
|
||||
ports/stm32/flashbdev.c \
|
||||
ports/stm32/spibdev.c \
|
||||
ports/stm32/usbd_conf.c \
|
||||
$(patsubst $(TOP)/%,%,$(wildcard $(TOP)/ports/stm32/boards/$(BOARD)/*.c))
|
||||
|
||||
SRC_O = \
|
||||
ports/stm32/boards/startup_stm32$(MCU_SERIES).o \
|
||||
ports/stm32/resethandler.o \
|
||||
|
||||
SRC_HAL = $(addprefix $(HAL_DIR)/Src/stm32$(MCU_SERIES)xx_,\
|
||||
hal_cortex.c \
|
||||
hal_flash.c \
|
||||
hal_flash_ex.c \
|
||||
hal_pcd.c \
|
||||
hal_pcd_ex.c \
|
||||
ll_usb.c \
|
||||
)
|
||||
|
||||
SRC_USBDEV = $(addprefix ports/stm32/$(USBDEV_DIR)/,\
|
||||
core/src/usbd_core.c \
|
||||
core/src/usbd_ctlreq.c \
|
||||
core/src/usbd_ioreq.c \
|
||||
)
|
||||
|
||||
OBJ =
|
||||
OBJ += $(addprefix $(BUILD)/, $(SRC_LIB:.c=.o))
|
||||
OBJ += $(addprefix $(BUILD)/, $(SRC_C:.c=.o))
|
||||
OBJ += $(addprefix $(BUILD)/, $(SRC_O))
|
||||
OBJ += $(addprefix $(BUILD)/, $(SRC_HAL:.c=.o))
|
||||
OBJ += $(addprefix $(BUILD)/, $(SRC_USBDEV:.c=.o))
|
||||
|
||||
all: $(TOP)/lib/stm32lib/README.md $(BUILD)/firmware.dfu $(BUILD)/firmware.hex
|
||||
|
||||
# For convenience, automatically fetch required submodules if they don't exist
|
||||
$(TOP)/lib/stm32lib/README.md:
|
||||
$(ECHO) "stm32lib submodule not found, fetching it now..."
|
||||
(cd $(TOP) && git submodule update --init lib/stm32lib)
|
||||
|
||||
.PHONY: deploy
|
||||
|
||||
deploy: $(BUILD)/firmware.dfu
|
||||
$(ECHO) "Writing $< to the board"
|
||||
$(Q)$(PYTHON) $(PYDFU) -u $<
|
||||
|
||||
FLASH_ADDR = 0x08000000
|
||||
|
||||
$(BUILD)/firmware.dfu: $(BUILD)/firmware.elf
|
||||
$(ECHO) "Create $@"
|
||||
$(Q)$(OBJCOPY) -O binary -j .isr_vector -j .text -j .data $^ $(BUILD)/firmware.bin
|
||||
$(Q)$(PYTHON) $(DFU) -b $(FLASH_ADDR):$(BUILD)/firmware.bin $@
|
||||
|
||||
$(BUILD)/firmware.hex: $(BUILD)/firmware.elf
|
||||
$(ECHO) "Create $@"
|
||||
$(Q)$(OBJCOPY) -O ihex $< $@
|
||||
|
||||
$(BUILD)/firmware.elf: $(OBJ)
|
||||
$(ECHO) "LINK $@"
|
||||
$(Q)$(LD) $(LDFLAGS) -o $@ $^ $(LIBS)
|
||||
$(Q)$(SIZE) $@
|
||||
|
||||
#########################################
|
||||
|
||||
vpath %.S . $(TOP)
|
||||
$(BUILD)/%.o: %.S
|
||||
$(ECHO) "CC $<"
|
||||
$(Q)$(CC) $(CFLAGS) -c -o $@ $<
|
||||
|
||||
vpath %.s . $(TOP)
|
||||
$(BUILD)/%.o: %.s
|
||||
$(ECHO) "AS $<"
|
||||
$(Q)$(AS) -o $@ $<
|
||||
|
||||
define compile_c
|
||||
$(ECHO) "CC $<"
|
||||
$(Q)$(CC) $(CFLAGS) -c -MD -o $@ $<
|
||||
@# The following fixes the dependency file.
|
||||
@# See http://make.paulandlesley.org/autodep.html for details.
|
||||
@# Regex adjusted from the above to play better with Windows paths, etc.
|
||||
@$(CP) $(@:.o=.d) $(@:.o=.P); \
|
||||
$(SED) -e 's/#.*//' -e 's/^.*: *//' -e 's/ *\\$$//' \
|
||||
-e '/^$$/ d' -e 's/$$/ :/' < $(@:.o=.d) >> $(@:.o=.P); \
|
||||
$(RM) -f $(@:.o=.d)
|
||||
endef
|
||||
|
||||
vpath %.c . $(TOP)
|
||||
$(BUILD)/%.o: %.c
|
||||
$(call compile_c)
|
||||
|
||||
# $(sort $(var)) removes duplicates
|
||||
#
|
||||
# The net effect of this, is it causes the objects to depend on the
|
||||
# object directories (but only for existence), and the object directories
|
||||
# will be created if they don't exist.
|
||||
OBJ_DIRS = $(sort $(dir $(OBJ)))
|
||||
$(OBJ): | $(OBJ_DIRS)
|
||||
$(OBJ_DIRS):
|
||||
$(MKDIR) -p $@
|
||||
|
||||
clean:
|
||||
$(RM) -rf $(BUILD) $(CLEAN_EXTRA)
|
||||
.PHONY: clean
|
||||
|
||||
###########################################
|
||||
|
||||
$(BUILD)/main.o: $(BUILD)/genhdr/qstrdefs.generated.h
|
||||
|
||||
$(BUILD)/genhdr/qstrdefs.generated.h:
|
||||
$(MKDIR) -p $(BUILD)/genhdr
|
||||
$(Q)echo "// empty" > $@
|
||||
|
||||
-include $(OBJ:.o=.P)
|
|
@ -0,0 +1,52 @@
|
|||
Mboot - MicroPython boot loader
|
||||
===============================
|
||||
|
||||
Mboot is a custom bootloader for STM32 MCUs, and currently supports the
|
||||
STM32F4xx and STM32F7xx families. It can provide a standard USB DFU interface
|
||||
on either the FS or HS peripherals, as well as a sophisticated, custom I2C
|
||||
interface. It fits in 16k of flash space.
|
||||
|
||||
How to use
|
||||
----------
|
||||
|
||||
1. Configure your board to use a boot loader by editing the mpconfigboard.mk
|
||||
and mpconfigboard.h files. For example, for an F767 be sure to have these
|
||||
lines in mpconfigboard.mk:
|
||||
|
||||
LD_FILES = boards/stm32f767.ld boards/common_bl.ld
|
||||
TEXT0_ADDR = 0x08008000
|
||||
|
||||
And this in mpconfigboard.h (recommended to put at the end of the file):
|
||||
|
||||
// Bootloader configuration
|
||||
#define MBOOT_I2C_PERIPH_ID 1
|
||||
#define MBOOT_I2C_SCL (pin_B8)
|
||||
#define MBOOT_I2C_SDA (pin_B9)
|
||||
#define MBOOT_I2C_ALTFUNC (4)
|
||||
|
||||
To configure a pin to force entry into the boot loader the following
|
||||
options can be used (with example configuration):
|
||||
|
||||
#define MBOOT_BOOTPIN_PIN (pin_A0)
|
||||
#define MBOOT_BOOTPIN_PULL (MP_HAL_PIN_PULL_UP)
|
||||
#define MBOOT_BOOTPIN_ACTIVE (0)
|
||||
|
||||
2. Build the board's main application firmware as usual.
|
||||
|
||||
3. Build mboot via:
|
||||
|
||||
$ cd mboot
|
||||
$ make BOARD=<board-id>
|
||||
|
||||
That should produce a DFU file for mboot. It can be deployed using
|
||||
USB DFU programming via (it will be placed at location 0x08000000):
|
||||
|
||||
$ make BOARD=<board-id> deploy
|
||||
|
||||
4. Reset the board while holding USR until all 3 LEDs are lit (the 4th option in
|
||||
the cycle) and then release USR. LED0 will then blink once per second to
|
||||
indicate that it's in mboot
|
||||
|
||||
5. Use either USB DFU or I2C to download firmware. The script mboot.py shows how
|
||||
to communicate with the I2C boot loader interface. It should be run on a
|
||||
pyboard connected via I2C to the target board.
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,177 @@
|
|||
# Driver for Mboot, the MicroPython boot loader
|
||||
# MIT license; Copyright (c) 2018 Damien P. George
|
||||
|
||||
import struct, time, os, hashlib
|
||||
|
||||
|
||||
I2C_CMD_ECHO = 1
|
||||
I2C_CMD_GETID = 2
|
||||
I2C_CMD_GETCAPS = 3
|
||||
I2C_CMD_RESET = 4
|
||||
I2C_CMD_CONFIG = 5
|
||||
I2C_CMD_GETLAYOUT = 6
|
||||
I2C_CMD_MASSERASE = 7
|
||||
I2C_CMD_PAGEERASE = 8
|
||||
I2C_CMD_SETRDADDR = 9
|
||||
I2C_CMD_SETWRADDR = 10
|
||||
I2C_CMD_READ = 11
|
||||
I2C_CMD_WRITE = 12
|
||||
I2C_CMD_COPY = 13
|
||||
I2C_CMD_CALCHASH = 14
|
||||
I2C_CMD_MARKVALID = 15
|
||||
|
||||
|
||||
class Bootloader:
|
||||
def __init__(self, i2c, addr):
|
||||
self.i2c = i2c
|
||||
self.addr = addr
|
||||
self.buf1 = bytearray(1)
|
||||
try:
|
||||
self.i2c.writeto(addr, b'')
|
||||
except OSError:
|
||||
raise Exception('no I2C mboot device found')
|
||||
|
||||
def wait_response(self):
|
||||
start = time.ticks_ms()
|
||||
while 1:
|
||||
try:
|
||||
self.i2c.readfrom_into(self.addr, self.buf1)
|
||||
n = self.buf1[0]
|
||||
break
|
||||
except OSError as er:
|
||||
time.sleep_us(500)
|
||||
if time.ticks_diff(time.ticks_ms(), start) > 5000:
|
||||
raise Exception('timeout')
|
||||
if n >= 129:
|
||||
raise Exception(n)
|
||||
if n == 0:
|
||||
return b''
|
||||
else:
|
||||
return self.i2c.readfrom(self.addr, n)
|
||||
|
||||
def wait_empty_response(self):
|
||||
ret = self.wait_response()
|
||||
if ret:
|
||||
raise Exception('expected empty response got %r' % ret)
|
||||
else:
|
||||
return None
|
||||
|
||||
def echo(self, data):
|
||||
self.i2c.writeto(self.addr, struct.pack('<B', I2C_CMD_ECHO) + data)
|
||||
return self.wait_response()
|
||||
|
||||
def getid(self):
|
||||
self.i2c.writeto(self.addr, struct.pack('<B', I2C_CMD_GETID))
|
||||
ret = self.wait_response()
|
||||
unique_id = ret[:12]
|
||||
mcu_name, board_name = ret[12:].split(b'\x00')
|
||||
return unique_id, str(mcu_name, 'ascii'), str(board_name, 'ascii')
|
||||
|
||||
def reset(self):
|
||||
self.i2c.writeto(self.addr, struct.pack('<B', I2C_CMD_RESET))
|
||||
# we don't expect any response
|
||||
|
||||
def getlayout(self):
|
||||
self.i2c.writeto(self.addr, struct.pack('<B', I2C_CMD_GETLAYOUT))
|
||||
layout = self.wait_response()
|
||||
id, flash_addr, layout = layout.split(b'/')
|
||||
assert id == b'@Internal Flash '
|
||||
flash_addr = int(flash_addr, 16)
|
||||
pages = []
|
||||
for chunk in layout.split(b','):
|
||||
n, sz = chunk.split(b'*')
|
||||
n = int(n)
|
||||
assert sz.endswith(b'Kg')
|
||||
sz = int(sz[:-2]) * 1024
|
||||
for i in range(n):
|
||||
pages.append((flash_addr, sz))
|
||||
flash_addr += sz
|
||||
return pages
|
||||
|
||||
def pageerase(self, addr):
|
||||
self.i2c.writeto(self.addr, struct.pack('<BI', I2C_CMD_PAGEERASE, addr))
|
||||
self.wait_empty_response()
|
||||
|
||||
def setrdaddr(self, addr):
|
||||
self.i2c.writeto(self.addr, struct.pack('<BI', I2C_CMD_SETRDADDR, addr))
|
||||
self.wait_empty_response()
|
||||
|
||||
def setwraddr(self, addr):
|
||||
self.i2c.writeto(self.addr, struct.pack('<BI', I2C_CMD_SETWRADDR, addr))
|
||||
self.wait_empty_response()
|
||||
|
||||
def read(self, n):
|
||||
self.i2c.writeto(self.addr, struct.pack('<BB', I2C_CMD_READ, n))
|
||||
return self.wait_response()
|
||||
|
||||
def write(self, buf):
|
||||
self.i2c.writeto(self.addr, struct.pack('<B', I2C_CMD_WRITE) + buf)
|
||||
self.wait_empty_response()
|
||||
|
||||
def calchash(self, n):
|
||||
self.i2c.writeto(self.addr, struct.pack('<BI', I2C_CMD_CALCHASH, n))
|
||||
return self.wait_response()
|
||||
|
||||
def markvalid(self):
|
||||
self.i2c.writeto(self.addr, struct.pack('<B', I2C_CMD_MARKVALID))
|
||||
self.wait_empty_response()
|
||||
|
||||
def deployfile(self, filename, addr):
|
||||
pages = self.getlayout()
|
||||
page_erased = [False] * len(pages)
|
||||
buf = bytearray(128) # maximum payload supported by I2C protocol
|
||||
start_addr = addr
|
||||
self.setwraddr(addr)
|
||||
fsize = os.stat(filename)[6]
|
||||
local_sha = hashlib.sha256()
|
||||
print('Deploying %s to location 0x%08x' % (filename, addr))
|
||||
with open(filename, 'rb') as f:
|
||||
t0 = time.ticks_ms()
|
||||
while True:
|
||||
n = f.readinto(buf)
|
||||
if n == 0:
|
||||
break
|
||||
|
||||
# check if we need to erase the page
|
||||
for i, p in enumerate(pages):
|
||||
if p[0] <= addr < p[0] + p[1]:
|
||||
# found page
|
||||
if not page_erased[i]:
|
||||
print('\r% 3u%% erase 0x%08x' % (100 * (addr - start_addr) // fsize, addr), end='')
|
||||
self.pageerase(addr)
|
||||
page_erased[i] = True
|
||||
break
|
||||
else:
|
||||
raise Exception('address 0x%08x not valid' % addr)
|
||||
|
||||
# write the data
|
||||
self.write(buf)
|
||||
|
||||
# update local SHA256, with validity bits set
|
||||
if addr == start_addr:
|
||||
buf[0] |= 3
|
||||
if n == len(buf):
|
||||
local_sha.update(buf)
|
||||
else:
|
||||
local_sha.update(buf[:n])
|
||||
|
||||
addr += n
|
||||
ntotal = addr - start_addr
|
||||
if ntotal % 2048 == 0 or ntotal == fsize:
|
||||
print('\r% 3u%% % 7u bytes ' % (100 * ntotal // fsize, ntotal), end='')
|
||||
t1 = time.ticks_ms()
|
||||
print()
|
||||
print('rate: %.2f KiB/sec' % (1024 * ntotal / (t1 - t0) / 1000))
|
||||
|
||||
local_sha = local_sha.digest()
|
||||
print('Local SHA256: ', ''.join('%02x' % x for x in local_sha))
|
||||
|
||||
self.setrdaddr(start_addr)
|
||||
remote_sha = self.calchash(ntotal)
|
||||
print('Remote SHA256:', ''.join('%02x' % x for x in remote_sha))
|
||||
|
||||
if local_sha == remote_sha:
|
||||
print('Marking app firmware as valid')
|
||||
self.markvalid()
|
||||
|
||||
self.reset()
|
|
@ -0,0 +1,155 @@
|
|||
/*
|
||||
* This file is part of the MicroPython project, http://micropython.org/
|
||||
*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2017-2018 Damien P. George
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||
* THE SOFTWARE.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#define mp_hal_delay_us_fast(us) mp_hal_delay_us(us)
|
||||
|
||||
#define MP_HAL_PIN_MODE_INPUT (0)
|
||||
#define MP_HAL_PIN_MODE_OUTPUT (1)
|
||||
#define MP_HAL_PIN_MODE_ALT (2)
|
||||
#define MP_HAL_PIN_MODE_ANALOG (3)
|
||||
#define MP_HAL_PIN_MODE_OPEN_DRAIN (5)
|
||||
#define MP_HAL_PIN_MODE_ALT_OPEN_DRAIN (6)
|
||||
#define MP_HAL_PIN_PULL_NONE (GPIO_NOPULL)
|
||||
#define MP_HAL_PIN_PULL_UP (GPIO_PULLUP)
|
||||
#define MP_HAL_PIN_PULL_DOWN (GPIO_PULLDOWN)
|
||||
|
||||
#define mp_hal_pin_obj_t uint32_t
|
||||
#define mp_hal_pin_input(p) mp_hal_pin_config((p), MP_HAL_PIN_MODE_INPUT, MP_HAL_PIN_PULL_NONE, 0)
|
||||
#define mp_hal_pin_output(p) mp_hal_pin_config((p), MP_HAL_PIN_MODE_OUTPUT, MP_HAL_PIN_PULL_NONE, 0)
|
||||
#define mp_hal_pin_open_drain(p) mp_hal_pin_config((p), MP_HAL_PIN_MODE_OPEN_DRAIN, MP_HAL_PIN_PULL_NONE, 0)
|
||||
#define mp_hal_pin_low(p) (((GPIO_TypeDef*)((p) & ~0xf))->BSRR = 0x10000 << ((p) & 0xf))
|
||||
#define mp_hal_pin_high(p) (((GPIO_TypeDef*)((p) & ~0xf))->BSRR = 1 << ((p) & 0xf))
|
||||
#define mp_hal_pin_od_low(p) mp_hal_pin_low(p)
|
||||
#define mp_hal_pin_od_high(p) mp_hal_pin_high(p)
|
||||
#define mp_hal_pin_read(p) ((((GPIO_TypeDef*)((p) & ~0xf))->IDR >> ((p) & 0xf)) & 1)
|
||||
#define mp_hal_pin_write(p, v) do { if (v) { mp_hal_pin_high(p); } else { mp_hal_pin_low(p); } } while (0)
|
||||
|
||||
void mp_hal_pin_config(uint32_t port_pin, uint32_t mode, uint32_t pull, uint32_t alt);
|
||||
void mp_hal_pin_config_speed(uint32_t port_pin, uint32_t speed);
|
||||
|
||||
#define pin_A0 (GPIOA_BASE | 0)
|
||||
#define pin_A1 (GPIOA_BASE | 1)
|
||||
#define pin_A2 (GPIOA_BASE | 2)
|
||||
#define pin_A3 (GPIOA_BASE | 3)
|
||||
#define pin_A4 (GPIOA_BASE | 4)
|
||||
#define pin_A5 (GPIOA_BASE | 5)
|
||||
#define pin_A6 (GPIOA_BASE | 6)
|
||||
#define pin_A7 (GPIOA_BASE | 7)
|
||||
#define pin_A8 (GPIOA_BASE | 8)
|
||||
#define pin_A9 (GPIOA_BASE | 9)
|
||||
#define pin_A10 (GPIOA_BASE | 10)
|
||||
#define pin_A11 (GPIOA_BASE | 11)
|
||||
#define pin_A12 (GPIOA_BASE | 12)
|
||||
#define pin_A13 (GPIOA_BASE | 13)
|
||||
#define pin_A14 (GPIOA_BASE | 14)
|
||||
#define pin_A15 (GPIOA_BASE | 15)
|
||||
|
||||
#define pin_B0 (GPIOB_BASE | 0)
|
||||
#define pin_B1 (GPIOB_BASE | 1)
|
||||
#define pin_B2 (GPIOB_BASE | 2)
|
||||
#define pin_B3 (GPIOB_BASE | 3)
|
||||
#define pin_B4 (GPIOB_BASE | 4)
|
||||
#define pin_B5 (GPIOB_BASE | 5)
|
||||
#define pin_B6 (GPIOB_BASE | 6)
|
||||
#define pin_B7 (GPIOB_BASE | 7)
|
||||
#define pin_B8 (GPIOB_BASE | 8)
|
||||
#define pin_B9 (GPIOB_BASE | 9)
|
||||
#define pin_B10 (GPIOB_BASE | 10)
|
||||
#define pin_B11 (GPIOB_BASE | 11)
|
||||
#define pin_B12 (GPIOB_BASE | 12)
|
||||
#define pin_B13 (GPIOB_BASE | 13)
|
||||
#define pin_B14 (GPIOB_BASE | 14)
|
||||
#define pin_B15 (GPIOB_BASE | 15)
|
||||
|
||||
#define pin_C0 (GPIOC_BASE | 0)
|
||||
#define pin_C1 (GPIOC_BASE | 1)
|
||||
#define pin_C2 (GPIOC_BASE | 2)
|
||||
#define pin_C3 (GPIOC_BASE | 3)
|
||||
#define pin_C4 (GPIOC_BASE | 4)
|
||||
#define pin_C5 (GPIOC_BASE | 5)
|
||||
#define pin_C6 (GPIOC_BASE | 6)
|
||||
#define pin_C7 (GPIOC_BASE | 7)
|
||||
#define pin_C8 (GPIOC_BASE | 8)
|
||||
#define pin_C9 (GPIOC_BASE | 9)
|
||||
#define pin_C10 (GPIOC_BASE | 10)
|
||||
#define pin_C11 (GPIOC_BASE | 11)
|
||||
#define pin_C12 (GPIOC_BASE | 12)
|
||||
#define pin_C13 (GPIOC_BASE | 13)
|
||||
#define pin_C14 (GPIOC_BASE | 14)
|
||||
#define pin_C15 (GPIOC_BASE | 15)
|
||||
|
||||
#define pin_D0 (GPIOD_BASE | 0)
|
||||
#define pin_D1 (GPIOD_BASE | 1)
|
||||
#define pin_D2 (GPIOD_BASE | 2)
|
||||
#define pin_D3 (GPIOD_BASE | 3)
|
||||
#define pin_D4 (GPIOD_BASE | 4)
|
||||
#define pin_D5 (GPIOD_BASE | 5)
|
||||
#define pin_D6 (GPIOD_BASE | 6)
|
||||
#define pin_D7 (GPIOD_BASE | 7)
|
||||
#define pin_D8 (GPIOD_BASE | 8)
|
||||
#define pin_D9 (GPIOD_BASE | 9)
|
||||
#define pin_D10 (GPIOD_BASE | 10)
|
||||
#define pin_D11 (GPIOD_BASE | 11)
|
||||
#define pin_D12 (GPIOD_BASE | 12)
|
||||
#define pin_D13 (GPIOD_BASE | 13)
|
||||
#define pin_D14 (GPIOD_BASE | 14)
|
||||
#define pin_D15 (GPIOD_BASE | 15)
|
||||
|
||||
#define pin_E0 (GPIOE_BASE | 0)
|
||||
#define pin_E1 (GPIOE_BASE | 1)
|
||||
#define pin_E2 (GPIOE_BASE | 2)
|
||||
#define pin_E3 (GPIOE_BASE | 3)
|
||||
#define pin_E4 (GPIOE_BASE | 4)
|
||||
#define pin_E5 (GPIOE_BASE | 5)
|
||||
#define pin_E6 (GPIOE_BASE | 6)
|
||||
#define pin_E7 (GPIOE_BASE | 7)
|
||||
#define pin_E8 (GPIOE_BASE | 8)
|
||||
#define pin_E9 (GPIOE_BASE | 9)
|
||||
#define pin_E10 (GPIOE_BASE | 10)
|
||||
#define pin_E11 (GPIOE_BASE | 11)
|
||||
#define pin_E12 (GPIOE_BASE | 12)
|
||||
#define pin_E13 (GPIOE_BASE | 13)
|
||||
#define pin_E14 (GPIOE_BASE | 14)
|
||||
#define pin_E15 (GPIOE_BASE | 15)
|
||||
|
||||
#define pin_F0 (GPIOF_BASE | 0)
|
||||
#define pin_F1 (GPIOF_BASE | 1)
|
||||
#define pin_F2 (GPIOF_BASE | 2)
|
||||
#define pin_F3 (GPIOF_BASE | 3)
|
||||
#define pin_F4 (GPIOF_BASE | 4)
|
||||
#define pin_F5 (GPIOF_BASE | 5)
|
||||
#define pin_F6 (GPIOF_BASE | 6)
|
||||
#define pin_F7 (GPIOF_BASE | 7)
|
||||
#define pin_F8 (GPIOF_BASE | 8)
|
||||
#define pin_F9 (GPIOF_BASE | 9)
|
||||
#define pin_F10 (GPIOF_BASE | 10)
|
||||
#define pin_F11 (GPIOF_BASE | 11)
|
||||
#define pin_F12 (GPIOF_BASE | 12)
|
||||
#define pin_F13 (GPIOF_BASE | 13)
|
||||
#define pin_F14 (GPIOF_BASE | 14)
|
||||
#define pin_F15 (GPIOF_BASE | 15)
|
|
@ -0,0 +1,77 @@
|
|||
/*
|
||||
GNU linker script for generic STM32xxx MCU
|
||||
*/
|
||||
|
||||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
FLASH_BL (rx) : ORIGIN = 0x08000000, LENGTH = 16K /* sector 0 (can be 32K) */
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 32K
|
||||
}
|
||||
|
||||
/* produce a link error if there is not this amount of RAM for these sections */
|
||||
_minimum_stack_size = 2K;
|
||||
|
||||
/* Define tho top end of the stack. The stack is full descending so begins just
|
||||
above last byte of RAM. Note that EABI requires the stack to be 8-byte
|
||||
aligned for a call. */
|
||||
_estack = ORIGIN(RAM) + LENGTH(RAM);
|
||||
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
/* The startup code goes first into FLASH */
|
||||
.isr_vector :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
KEEP(*(.isr_vector)) /* Startup code */
|
||||
. = ALIGN(4);
|
||||
} >FLASH_BL
|
||||
|
||||
/* The program code and other data goes into FLASH */
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.text*)
|
||||
*(.rodata*)
|
||||
. = ALIGN(4);
|
||||
_etext = .;
|
||||
} >FLASH_BL
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = LOADADDR(.data);
|
||||
|
||||
/* Initialized data section */
|
||||
.data :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sdata = .;
|
||||
*(.data*)
|
||||
|
||||
. = ALIGN(4);
|
||||
_edata = .;
|
||||
} >RAM AT> FLASH_BL
|
||||
|
||||
/* Uninitialized data section */
|
||||
.bss :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sbss = .;
|
||||
*(.bss*)
|
||||
*(COMMON)
|
||||
|
||||
. = ALIGN(4);
|
||||
_ebss = .;
|
||||
} >RAM
|
||||
|
||||
/* this just checks there is enough RAM for the stack */
|
||||
.stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
. = . + _minimum_stack_size;
|
||||
. = ALIGN(4);
|
||||
} >RAM
|
||||
|
||||
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||
}
|
Loading…
Reference in New Issue