Commit 2d4e4148 by Enrico Pozzobon

STM32F1 template using libopencm3

parent 279ba0a8
...@@ -61,6 +61,9 @@ function run() { ...@@ -61,6 +61,9 @@ function run() {
mv "$cipher/LWC_AEAD_KAT.txt" "$TEST_PATH" mv "$cipher/LWC_AEAD_KAT.txt" "$TEST_PATH"
case $TEMPLATE in case $TEMPLATE in
f1-libopencm3) mv $cipher/firmware.{bin,elf} "$TEST_PATH"
;;
f7) mv $cipher/build/f7.* "$TEST_PATH" f7) mv $cipher/build/f7.* "$TEST_PATH"
;; ;;
...@@ -111,7 +114,7 @@ else ...@@ -111,7 +114,7 @@ else
TMPDIR=$(mktemp -d -t submission-XXXXXXXXXX) TMPDIR=$(mktemp -d -t submission-XXXXXXXXXX)
echo "Extracting in $TMPDIR" echo "Extracting in $TMPDIR"
unzip $ZIP_PATH -d $TMPDIR unzip $ZIP_PATH -d $TMPDIR
for i in templates/*; do for i in templates/{uno,bluepill,esp32,f7,maixduino}; do
TEMPLATE="${i##*/}" TEMPLATE="${i##*/}"
echo "Template is $TEMPLATE" echo "Template is $TEMPLATE"
touch $MAINDIR/locky.lock touch $MAINDIR/locky.lock
......
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
###############################################################################
# Source files
SRCS := main.c uartp.c $(SRC_FILES)
OBJS := $(SRCS:%.c=%.o)
BINARY = firmware
LDSCRIPT = stm32f103c8t6_128k.ld
LIBNAME = opencm3_stm32f1
DEFS += -DSTM32F1
FP_FLAGS ?= -msoft-float
ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd
################################################################################
# OpenOCD specific variables
OOCD ?= openocd
OOCD_INTERFACE ?= flossjtag
OOCD_TARGET ?= stm32f1x
################################################################################
# Black Magic Probe specific variables
# Set the BMP_PORT to a serial port and then BMP is used for flashing
BMP_PORT ?=
################################################################################
# texane/stlink specific variables
#STLINK_PORT ?= :4242
# Be silent per default, but 'make V=1' will show all compiler calls.
ifneq ($(V),1)
Q := @
NULL := 2>/dev/null
endif
###############################################################################
# Executables
PREFIX ?= arm-none-eabi-
CC := $(PREFIX)gcc
CXX := $(PREFIX)g++
LD := $(PREFIX)gcc
AR := $(PREFIX)ar
AS := $(PREFIX)as
OBJCOPY := $(PREFIX)objcopy
OBJDUMP := $(PREFIX)objdump
GDB := $(PREFIX)gdb
STFLASH = $(shell which st-flash)
STYLECHECK := /checkpatch.pl
STYLECHECKFLAGS := --no-tree -f --terse --mailback
STYLECHECKFILES := $(shell find . -name '*.[ch]')
OPT := -O2
#DEBUG := -ggdb3
CSTD ?= -std=c99
###############################################################################
# Libraries
ifeq ($(strip $(OPENCM3_DIR)),)
# user has not specified the library path, so we try to detect it
# where we search for the library
LIBPATHS := ../../../libopencm3
OPENCM3_DIR := $(wildcard $(LIBPATHS:=/locm3.sublime-project))
OPENCM3_DIR := $(firstword $(dir $(OPENCM3_DIR)))
ifeq ($(strip $(OPENCM3_DIR)),)
$(warning Cannot find libopencm3 library in the standard search paths.)
$(error Please specify it through OPENCM3_DIR variable!)
endif
endif
ifeq ($(V),1)
$(info Using $(OPENCM3_DIR) path to library)
endif
define ERR_DEVICE_LDSCRIPT_CONFLICT
You can either specify DEVICE=blah, and have the LDSCRIPT generated,
or you can provide LDSCRIPT, and ensure CPPFLAGS, LDFLAGS and LDLIBS
all contain the correct values for the target you wish to use.
You cannot provide both!
endef
ifeq ($(strip $(DEVICE)),)
# Old style, assume LDSCRIPT exists
DEFS += -I$(OPENCM3_DIR)/include
LDFLAGS += -L$(OPENCM3_DIR)/lib
LDLIBS += -l$(LIBNAME)
LDSCRIPT ?= $(BINARY).ld
else
# New style, assume device is provided, and we're generating the rest.
ifneq ($(strip $(LDSCRIPT)),)
$(error $(ERR_DEVICE_LDSCRIPT_CONFLICT))
endif
include $(OPENCM3_DIR)/mk/genlink-config.mk
endif
OPENCM3_SCRIPT_DIR = $(OPENCM3_DIR)/scripts
EXAMPLES_SCRIPT_DIR = $(OPENCM3_DIR)/../scripts
###############################################################################
# C flags
TGT_CFLAGS += $(OPT) $(CSTD) $(DEBUG)
TGT_CFLAGS += $(ARCH_FLAGS)
TGT_CFLAGS += -Wextra -Wshadow -Wimplicit-function-declaration
TGT_CFLAGS += -Wredundant-decls -Wmissing-prototypes -Wstrict-prototypes
TGT_CFLAGS += -fno-common -ffunction-sections -fdata-sections
###############################################################################
# C++ flags
TGT_CXXFLAGS += $(OPT) $(CXXSTD) $(DEBUG)
TGT_CXXFLAGS += $(ARCH_FLAGS)
TGT_CXXFLAGS += -Wextra -Wshadow -Wredundant-decls -Weffc++
TGT_CXXFLAGS += -fno-common -ffunction-sections -fdata-sections
###############################################################################
# C & C++ preprocessor common flags
TGT_CPPFLAGS += -MD
TGT_CPPFLAGS += -Wall -Wundef
TGT_CPPFLAGS += $(DEFS)
###############################################################################
# Linker flags
TGT_LDFLAGS += --static -nostartfiles
TGT_LDFLAGS += -T$(LDSCRIPT)
TGT_LDFLAGS += $(ARCH_FLAGS) $(DEBUG)
TGT_LDFLAGS += -Wl,-Map=$(*).map -Wl,--cref
TGT_LDFLAGS += -Wl,--gc-sections
ifeq ($(V),99)
TGT_LDFLAGS += -Wl,--print-gc-sections
endif
###############################################################################
# Used libraries
LDLIBS += -Wl,--start-group -lc -lgcc -lnosys -Wl,--end-group
###############################################################################
###############################################################################
###############################################################################
.SUFFIXES: .elf .bin .hex .srec .list .map .images
.SECONDEXPANSION:
.SECONDARY:
all: elf bin
elf: $(BINARY).elf
bin: $(BINARY).bin
hex: $(BINARY).hex
srec: $(BINARY).srec
list: $(BINARY).list
GENERATED_BINARIES=$(BINARY).elf $(BINARY).bin $(BINARY).hex $(BINARY).srec $(BINARY).list $(BINARY).map
images: $(BINARY).images
flash: $(BINARY).flash
# Either verify the user provided LDSCRIPT exists, or generate it.
ifeq ($(strip $(DEVICE)),)
$(LDSCRIPT):
ifeq (,$(wildcard $(LDSCRIPT)))
$(error Unable to find specified linker script: $(LDSCRIPT))
endif
else
include $(OPENCM3_DIR)/mk/genlink-rules.mk
endif
$(OPENCM3_DIR)/lib/lib$(LIBNAME).a:
ifeq (,$(wildcard $@))
$(warning $(LIBNAME).a not found, attempting to rebuild in $(OPENCM3_DIR))
$(MAKE) -C $(OPENCM3_DIR)
endif
# Define a helper macro for debugging make errors online
# you can type "make print-OPENCM3_DIR" and it will show you
# how that ended up being resolved by all of the included
# makefiles.
print-%:
@echo $*=$($*)
%.images: %.bin %.hex %.srec %.list %.map
@#printf "*** $* images generated ***\n"
%.bin: %.elf
@#printf " OBJCOPY $(*).bin\n"
$(Q)$(OBJCOPY) -Obinary $(*).elf $(*).bin
%.hex: %.elf
@#printf " OBJCOPY $(*).hex\n"
$(Q)$(OBJCOPY) -Oihex $(*).elf $(*).hex
%.srec: %.elf
@#printf " OBJCOPY $(*).srec\n"
$(Q)$(OBJCOPY) -Osrec $(*).elf $(*).srec
%.list: %.elf
@#printf " OBJDUMP $(*).list\n"
$(Q)$(OBJDUMP) -S $(*).elf > $(*).list
%.elf %.map: $(OBJS) $(LDSCRIPT) $(OPENCM3_DIR)/lib/lib$(LIBNAME).a
@#printf " LD $(*).elf\n"
$(Q)$(LD) $(TGT_LDFLAGS) $(LDFLAGS) $(OBJS) $(LDLIBS) -o $(*).elf
%.o: %.c
@#printf " CC $(*).c\n"
$(Q)$(CC) $(TGT_CFLAGS) $(CFLAGS) $(TGT_CPPFLAGS) $(CPPFLAGS) -o $(*).o -c $(*).c
%.o: %.cxx
@#printf " CXX $(*).cxx\n"
$(Q)$(CXX) $(TGT_CXXFLAGS) $(CXXFLAGS) $(TGT_CPPFLAGS) $(CPPFLAGS) -o $(*).o -c $(*).cxx
%.o: %.cpp
@#printf " CXX $(*).cpp\n"
$(Q)$(CXX) $(TGT_CXXFLAGS) $(CXXFLAGS) $(TGT_CPPFLAGS) $(CPPFLAGS) -o $(*).o -c $(*).cpp
clean:
@#printf " CLEAN\n"
$(Q)$(RM) $(GENERATED_BINARIES) generated.* $(OBJS) $(OBJS:%.o=%.d)
stylecheck: $(STYLECHECKFILES:=.stylecheck)
styleclean: $(STYLECHECKFILES:=.styleclean)
# the cat is due to multithreaded nature - we like to have consistent chunks of text on the output
%.stylecheck: %
$(Q)$(OPENCM3_SCRIPT_DIR)$(STYLECHECK) $(STYLECHECKFLAGS) $* > $*.stylecheck; \
if [ -s $*.stylecheck ]; then \
cat $*.stylecheck; \
else \
rm -f $*.stylecheck; \
fi;
%.styleclean:
$(Q)rm -f $*.stylecheck;
%.stlink-flash: %.bin
@printf " FLASH $<\n"
$(STFLASH) write $(*).bin 0x8000000
ifeq ($(BMP_PORT),)
ifeq ($(OOCD_FILE),)
%.flash: %.elf
@printf " FLASH $<\n"
(echo "halt; program $(realpath $(*).elf) verify reset" | nc -4 localhost 4444 2>/dev/null) || \
$(OOCD) -f interface/$(OOCD_INTERFACE).cfg \
-f target/$(OOCD_TARGET).cfg \
-c "program $(*).elf verify reset exit" \
$(NULL)
else
%.flash: %.elf
@printf " FLASH $<\n"
(echo "halt; program $(realpath $(*).elf) verify reset" | nc -4 localhost 4444 2>/dev/null) || \
$(OOCD) -f $(OOCD_FILE) \
-c "program $(*).elf verify reset exit" \
$(NULL)
endif
else
%.flash: %.elf
@printf " GDB $(*).elf (flash)\n"
$(GDB) --batch \
-ex 'target extended-remote $(BMP_PORT)' \
-x $(EXAMPLES_SCRIPT_DIR)/black_magic_probe_flash.scr \
$(*).elf
endif
.PHONY: images clean stylecheck styleclean elf bin hex srec list
-include $(OBJS:.o=.d)
#ifdef __cplusplus
extern "C" {
#endif
int crypto_aead_encrypt(
unsigned char *c,unsigned long long *clen,
const unsigned char *m,unsigned long long mlen,
const unsigned char *ad,unsigned long long adlen,
const unsigned char *nsec,
const unsigned char *npub,
const unsigned char *k
);
int crypto_aead_decrypt(
unsigned char *m,unsigned long long *outputmlen,
unsigned char *nsec,
const unsigned char *c,unsigned long long clen,
const unsigned char *ad,unsigned long long adlen,
const unsigned char *npub,
const unsigned char *k
);
#ifdef __cplusplus
}
#endif
#include <libopencm3/stm32/rcc.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/stm32/usart.h>
#include <libopencmsis/core_cm3.h>
#include <string.h>
#include "crypto_aead.h"
#include "api.h"
#include "uartp.h"
void uart_wbyte(uint8_t x);
uint8_t uart_rbyte(void);
static void loop(void);
static void my_assert(bool b);
#define MAX_BYTES 100
#define CMDBUF_LEN 72
static uint8_t cmdbuf[CMDBUF_LEN];
uint8_t npub[CRYPTO_NPUBBYTES];
uint8_t nsec[CRYPTO_NSECBYTES];
uint8_t k[CRYPTO_KEYBYTES];
uint8_t ad[MAX_BYTES];
uint8_t m[MAX_BYTES];
uint8_t c[MAX_BYTES];
unsigned long long int adlen = 0;
unsigned long long int mlen = 0;
unsigned long long int clen = 0;
void uart_wbyte(uint8_t x) {
usart_send_blocking(USART1, x);
}
uint8_t uart_rbyte() {
uint16_t r = usart_recv_blocking(USART1);
return (uint8_t) (0xff & r);
}
static void my_assert(bool b) {
if (b)
return;
for(;;);
}
static void clock_setup(void)
{
rcc_clock_setup_in_hse_8mhz_out_72mhz();
/* Enable GPIOA clock. */
rcc_periph_clock_enable(RCC_GPIOA);
/* Enable clocks for GPIO port A (for GPIO_USART1_TX) and USART1. */
rcc_periph_clock_enable(RCC_USART1);
}
static void usart_setup(void)
{
/* Setup GPIO pin GPIO_USART1_TX. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART1_TX);
/* Setup UART parameters. */
usart_set_baudrate(USART1, 115200);
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);
/* Finally enable the USART. */
usart_enable(USART1);
}
static void gpio_setup(void)
{
/* Set GPIO (in GPIO port A) to 'output push-pull'. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO7);
}
int main(void)
{
int i;
clock_setup();
gpio_setup();
usart_setup();
memset(npub, 0, CRYPTO_NPUBBYTES);
memset(nsec, 0, CRYPTO_NSECBYTES);
memset(k, 0, CRYPTO_KEYBYTES);
memset(ad, 0, MAX_BYTES);
memset(m, 0, MAX_BYTES);
memset(c, 0, MAX_BYTES);
for (i = 0; i < 1000000; i++) /* Wait a bit. */
__asm__("nop");
for (i=0; i<13; i++) {
usart_send_blocking(USART1, "Hello, World!"[i]);
}
while (1) {
loop();
}
return 0;
}
static void loop() {
int res;
uint16_t len = uartp_recv(cmdbuf, CMDBUF_LEN - 1);
uint8_t action = cmdbuf[0];
if (len == 0 || len > CMDBUF_LEN - 1)
return;
uint16_t l = len - 1;
uint16_t rl = 0;
uint8_t *var = cmdbuf+1;
switch (action) {
case 'm': my_assert(l <= MAX_BYTES); memcpy(m, var, l); mlen = l; break;
case 'c': my_assert(l <= MAX_BYTES); memcpy(c, var, l); clen = l; break;
case 'a': my_assert(l <= MAX_BYTES); memcpy(ad, var, l); adlen = l; break;
case 'k': my_assert(l == CRYPTO_KEYBYTES); memcpy(k, var, l); break;
case 'p': my_assert(l == CRYPTO_NPUBBYTES); memcpy(npub, var, l); break;
case 's': my_assert(l == CRYPTO_NSECBYTES); memcpy(nsec, var, l); break;
case 'e':
__disable_irq();
__asm__("nop");
gpio_clear(GPIOA, GPIO7);
res = crypto_aead_encrypt(c, &clen, m, mlen, ad, adlen, nsec, npub, k);
gpio_set(GPIOA, GPIO7);
__asm__("nop");
__enable_irq();
break;
case 'd':
__disable_irq();
__asm__("nop");
gpio_clear(GPIOA, GPIO7);
res = crypto_aead_decrypt(m, &mlen, nsec, c, clen, ad, adlen, npub, k);
gpio_set(GPIOA, GPIO7);
__asm__("nop");
__enable_irq();
break;
case'M': var = m; rl = mlen; break;
case'C': var = c; rl = clen; break;
case'A': var = ad; rl = adlen; break;
case'K': var = k; rl = CRYPTO_KEYBYTES; break;
case'P': var = npub; rl = CRYPTO_NPUBBYTES; break;
case'S': var = nsec; rl = CRYPTO_NSECBYTES; break;
case'R': var = (uint8_t *) &res; rl = sizeof(res); break;
default:
my_assert(false);
}
cmdbuf[0] = action;
memcpy(cmdbuf+1, var, rl);
uartp_send(cmdbuf, rl+1);
}
interface ftdi
transport select jtag
ftdi_device_desc "FT2232H MiniModule"
ftdi_vid_pid 0x0403 0x6010
# The other channel is used for UART
ftdi_channel 1
ftdi_layout_init 0x0018 0x05fb
ftdi_serial FT2XCRZ1
# BDBUS4 is connected to JTAG TRST
ftdi_layout_signal nTRST -data 0x0010
# BDBUS5 is connected to System Reset
ftdi_layout_signal nSRST -data 0x0020
set WORKAREASIZE 0x2000
source [find target/stm32f103c8t6_128k.cfg]
#tpiu config internal swodump.stm32f103-generic.log uart off 72000000
reset_config srst_only srst_push_pull srst_nogate connect_assert_srst
#reset_config none srst_push_pull srst_nogate
/* Define memory regions. */
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
}
/* Include the common ld script. */
INCLUDE cortex-m-generic.ld
#!/usr/bin/env python3
import os
import sys
import serial.tools.list_ports
from test_common import (
DeviceUnderTestAeadUARTP,
eprint,
OpenOcd,
FileMutex,
run_nist_lws_aead_test
)
def get_serial():
ports = serial.tools.list_ports.comports()
devices = [
p.device
for p in ports
if p.serial_number == 'FT2XCRZ1'
]
devices.sort()
eprint("Serial port for BluePill is %s" % devices[0])
return devices[0]
class BluePill(DeviceUnderTestAeadUARTP):
RAM_SIZE = 0x5000
def __init__(self, build_dir):
DeviceUnderTestAeadUARTP.__init__(self)
self.uart_device = get_serial()
devname = os.path.basename(self.uart_device)
self.lock = FileMutex('/var/lock/lwc-compare.%s.lock' % devname)
self.build_dir = build_dir
self.template_path = os.path.dirname(sys.argv[0])
self.firmware_path = os.path.join(
build_dir, 'firmware.elf')
self.firmware_bin_path = os.path.join(
build_dir, 'firmware.bin')
self.ram_pattern_path = os.path.join(
self.template_path, 'empty_ram.bin')
self.ram_dump_path = os.path.join(
build_dir, 'ram_dump.bin')
self.openocd_cfg_path = os.path.join(
self.template_path, 'openocd.cfg')
self.ocd = OpenOcd(self.openocd_cfg_path)
self.ser = serial.Serial(
self.uart_device,
baudrate=115200,
timeout=5)
def firmware_size(self):
return os.stat(self.firmware_bin_path).st_size
def flash(self):
ocd_cmd = 'program %s verify reset' % self.firmware_path
res = self.ocd.send(ocd_cmd)
eprint(res)
assert res == ''
eprint("Firmware flashed.")
ocd_cmd = 'reset halt'
res = self.ocd.send(ocd_cmd)
eprint(res)
assert res == ''
ocd_cmd = 'load_image %s 0x20000000' % self.ram_pattern_path
res = self.ocd.send(ocd_cmd)
eprint(res)
assert res == ''
eprint("RAM flashed.")
ocd_cmd = 'resume'
res = self.ocd.send(ocd_cmd)
eprint(res)
assert res == ''
self.ser = serial.Serial(
self.uart_device,
baudrate=115200,
timeout=5)
self.reset()
def reset(self, halt=False):
ocd_cmd = 'reset halt' if halt else 'reset run'
res = self.ocd.send(ocd_cmd)
eprint(res)
assert res == ''
eprint("Reset!")
def dump_ram(self):
res = self.ocd.send(
'dump_image %s 0x20000000 0x%x' %
(self.ram_dump_path, BluePill.RAM_SIZE))
eprint(res)
assert res == ''
eprint("RAM dumped.")
with open(self.ram_dump_path, 'rb') as ram:
ram = ram.read()
if len(ram) != BluePill.RAM_SIZE:
raise Exception(
"RAM dump was %d bytes instead of %d" %
(len(ram), BluePill.RAM_SIZE))
return ram
def main(argv):
if len(argv) != 2:
print("Usage: test build_dir")
return 1
build_dir = argv[1]
kat_path = os.path.join(build_dir, 'LWC_AEAD_KAT.txt')
dut = BluePill(build_dir)
run_nist_lws_aead_test(dut, kat_path, build_dir, 0x0002)
return 0
if __name__ == "__main__":
sys.exit(main(sys.argv))
#include <stdint.h>
#include "uartp.h"
extern void uart_wbyte(uint8_t x);
extern uint8_t uart_rbyte(void);
// Simple serial protocol with packets and checksum
const uint8_t AMUX_TAG = 0xf9;
const uint8_t AMUX_END = 0xf3;
const uint8_t AMUX_EXT = 0x80;
void uartp_send(const void *src, uint16_t len) {
uint8_t len_ind_0, len_ind_1, fcs, info;
const uint8_t *buf = (const uint8_t *) src;
uart_wbyte(AMUX_TAG);
len_ind_0 = (uint8_t) (0xff & len);
len_ind_1 = (uint8_t) (0xff & (len >> 7));
if (len < 128) {
uart_wbyte(len_ind_0);
} else {
uart_wbyte(len_ind_0 | AMUX_EXT);
uart_wbyte(len_ind_1);
}
fcs = 0;
for (uint16_t i = 0; i < len; i++) {
info = buf[i];
fcs += info;
uart_wbyte(buf[i]);
}
fcs = 255 - fcs;
uart_wbyte(fcs);
uart_wbyte(AMUX_END);
}
uint16_t uartp_recv(void *dst, uint16_t buf_len) {
uint8_t *buf = (uint8_t *) dst;
uint8_t tag_old, tag, info, cs;
uint16_t len;
tag = AMUX_END;
while (1) {
do {
tag_old = tag;
tag = uart_rbyte();
} while(tag != AMUX_TAG || tag_old != AMUX_END);
len = (uint16_t) uart_rbyte();
if (len & AMUX_EXT) {
len &= (~AMUX_EXT);
len |= (uint16_t) (uart_rbyte() << 7);
}
if (len > buf_len) {
return len;
}
uint16_t i = 0;
cs = 0;
for (i = 0; i < len; i++) {
info = uart_rbyte();
buf[i] = info;
cs += info;
}
cs += uart_rbyte();
tag = uart_rbyte();
if (0xff == cs) {
if (AMUX_END == tag) {
return len;
}
}
}
}
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
void uartp_send(const void *src, uint16_t len);
uint16_t uartp_recv(void *dst, uint16_t buf_len);
#ifdef __cplusplus
}
#endif
...@@ -329,6 +329,7 @@ if __name__ == '__main__': ...@@ -329,6 +329,7 @@ if __name__ == '__main__':
runners.append(Runner('uno', 'Arduino Uno')) runners.append(Runner('uno', 'Arduino Uno'))
runners.append(Runner('esp32', 'ESP32')) runners.append(Runner('esp32', 'ESP32'))
runners.append(Runner('bluepill', 'BluePill')) runners.append(Runner('bluepill', 'BluePill'))
runners.append(Runner('f1-libopencm3', 'STM32F1 libopencm3'))
def signal_handler(signal, frame): def signal_handler(signal, frame):
print("Process interrupted!", file=sys.stderr) print("Process interrupted!", file=sys.stderr)
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or sign in to comment