summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorBirte Kristina Friesel <birte.friesel@uos.de>2024-02-08 13:46:48 +0100
committerBirte Kristina Friesel <birte.friesel@uos.de>2024-02-08 13:46:48 +0100
commitec871ef8ae230bcb779c8535c3c4526817fd5d93 (patch)
tree558e731639f7ece070d7abd14c3c82afa11f9647
parent18db600341bcf1c21e4282515d458b898639f349 (diff)
Add preliminary STM32F746ZG-Nucleo support
-rw-r--r--include/arch/stm32f746zg-nucleo/driver/counter.h40
-rw-r--r--include/arch/stm32f746zg-nucleo/driver/gpio.h134
-rw-r--r--include/arch/stm32f746zg-nucleo/driver/stdout.h24
-rw-r--r--include/arch/stm32f746zg-nucleo/driver/uptime.h32
-rw-r--r--src/arch/stm32f746zg-nucleo/Kconfig10
-rw-r--r--src/arch/stm32f746zg-nucleo/Makefile.inc140
-rw-r--r--src/arch/stm32f746zg-nucleo/arch.cc122
-rw-r--r--src/arch/stm32f746zg-nucleo/driver/counter.cc19
-rw-r--r--src/arch/stm32f746zg-nucleo/driver/gpio.cc8
-rw-r--r--src/arch/stm32f746zg-nucleo/driver/stdout.cc36
-rw-r--r--src/arch/stm32f746zg-nucleo/driver/uptime.cc8
-rw-r--r--src/arch/stm32f746zg-nucleo/prompt1
-rw-r--r--src/arch/stm32f746zg-nucleo/stm32f746zg.ld13
13 files changed, 587 insertions, 0 deletions
diff --git a/include/arch/stm32f746zg-nucleo/driver/counter.h b/include/arch/stm32f746zg-nucleo/driver/counter.h
new file mode 100644
index 0000000..ef993bd
--- /dev/null
+++ b/include/arch/stm32f746zg-nucleo/driver/counter.h
@@ -0,0 +1,40 @@
+/*
+ * Copyright 2024 Birte Kristina Friesel
+ *
+ * SPDX-License-Identifier: BSD-2-Clause
+ */
+#ifndef COUNTER_H
+#define COUNTER_H
+
+#include <libopencm3/stm32/timer.h>
+
+#include "arch.h"
+
+typedef uint32_t counter_value_t;
+typedef uint32_t counter_overflow_t;
+
+class Counter {
+ private:
+ Counter(const Counter &copy);
+
+ public:
+ counter_value_t value;
+ volatile counter_overflow_t overflow;
+
+ Counter() : overflow(0) {}
+
+ inline void start() {
+ overflow = 0;
+ timer_set_counter(TIM2, 0);
+ timer_enable_counter(TIM2);
+ }
+
+ inline void stop() {
+ timer_disable_counter(TIM2);
+ value = timer_get_counter(TIM2);
+ }
+};
+
+extern Counter counter;
+
+#endif
diff --git a/include/arch/stm32f746zg-nucleo/driver/gpio.h b/include/arch/stm32f746zg-nucleo/driver/gpio.h
new file mode 100644
index 0000000..9eb81c0
--- /dev/null
+++ b/include/arch/stm32f746zg-nucleo/driver/gpio.h
@@ -0,0 +1,134 @@
+/*
+ * Copyright 2024 Birte Kristina Friesel
+ *
+ * SPDX-License-Identifier: BSD-2-Clause
+ */
+#ifndef GPIO_H
+#define GPIO_H
+
+#include <libopencm3/stm32/rcc.h>
+#include <libopencm3/stm32/gpio.h>
+
+class GPIO {
+ private:
+ GPIO(const GPIO &copy);
+
+ public:
+ GPIO () {}
+
+ enum Pin : unsigned char {
+ pa0 = 0, pa1, pa2, pa3, pa4, pa5, pa6, pa7,
+ pa8, pa9, pa10, pa11, pa12, pa13, pa14, pa15,
+ pb0, pb1, pb2, pb3, pb4, pb5, pb6, pb7,
+ pb8, pb9, pb10, pb11, pb12, pb13, pb14, pb15,
+ pc0, pc1, pc2, pc3, pc4, pc5, pc6, pc7,
+ pc8, pc9, pc10, pc11, pc12, pc13, pc14, pc15,
+ pd0, pd1, pd2, pd3, pd4, pd5, pd6, pd7,
+ pd8, pd9, pd10, pd11, pd12, pd13, pd14, pd15,
+ pe0, pe1, pe2, pe3, pe4, pe5, pe6, pe7,
+ pe8, pe9, pe10, pe11, pe12, pe13, pe14, pe15,
+ pf0, pf1, pf2, pf3, pf4, pf5, pf6, pf7,
+ pf8, pf9, pf10, pf11, pf12, pf13, pf14, pf15,
+ pg0, pg1, pg2, pg3, pg4, pg5, pg6, pg7,
+ pg8, pg9, pg10, pg11, pg12, pg13, pg14, pg15,
+ ph0, ph1, ph2, ph3, ph4, ph5, ph6, ph7,
+ ph8, ph9, ph10, ph11, ph12, ph13, ph14, ph15,
+ PIN_INVALID
+ };
+
+ inline void setup() {
+ rcc_periph_clock_enable(RCC_GPIOA);
+ rcc_periph_clock_enable(RCC_GPIOB);
+ rcc_periph_clock_enable(RCC_GPIOC);
+ rcc_periph_clock_enable(RCC_GPIOD);
+
+ // Set LEDs as output
+ gpio_mode_setup(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO0);
+ gpio_mode_setup(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO7);
+ gpio_mode_setup(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO14);
+ }
+ inline void led_on(unsigned char id = 0) {
+ if (id == 2) {
+ gpio_set(GPIOB, GPIO0);
+ } else if (id == 1) {
+ gpio_set(GPIOB, GPIO7);
+ } else {
+ gpio_set(GPIOB, GPIO14);
+ }
+ }
+ inline void led_off(unsigned char id = 0) {
+ if (id == 2) {
+ gpio_clear(GPIOB, GPIO0);
+ } else if (id == 1) {
+ gpio_clear(GPIOB, GPIO7);
+ } else {
+ gpio_clear(GPIOB, GPIO14);
+ }
+ }
+ inline void led_toggle(unsigned char id = 0) {
+ if (id == 2) {
+ gpio_toggle(GPIOB, GPIO0);
+ } else if (id == 1) {
+ gpio_toggle(GPIOB, GPIO7);
+ } else {
+ gpio_toggle(GPIOB, GPIO14);
+ }
+ }
+ inline void input(unsigned char const pin) {
+ if (pin < pb0) {
+ gpio_mode_setup(GPIOA, GPIO_MODE_INPUT, GPIO_PUPD_NONE, 1 << pin);
+ } else if (pin < pc0) {
+ gpio_mode_setup(GPIOB, GPIO_MODE_INPUT, GPIO_PUPD_NONE, 1 << (pin - pb0));
+ } else if (pin < PIN_INVALID) {
+ gpio_mode_setup(GPIOC, GPIO_MODE_INPUT, GPIO_PUPD_NONE, 1 << (pin - pc0));
+ }
+ }
+ inline void input(unsigned char const pin, unsigned char const pull) {
+ }
+ inline void output(unsigned char const pin) {
+ if (pin < pb0) {
+ gpio_mode_setup(GPIOA, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, 1 << pin);
+ } else if (pin < pc0) {
+ gpio_mode_setup(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, 1 << (pin - pb0));
+ } else if (pin < PIN_INVALID) {
+ gpio_mode_setup(GPIOC, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, 1 << (pin - pc0));
+ }
+ }
+ /*
+ inline void output(unsigned char const pin, unsigned char const value) {
+ }*/
+ inline unsigned int read(unsigned char const pin) {
+ if (pin < pb0) {
+ return gpio_get(GPIOA, 1 << pin);
+ } else if (pin < pc0) {
+ return gpio_get(GPIOB, 1 << (pin-pb0));
+ } else if (pin < PIN_INVALID) {
+ return gpio_get(GPIOC, 1 << (pin-pc0));
+ }
+ }
+ inline void write(unsigned char const pin, unsigned char value) {
+ if (pin < pb0) {
+ if (value) {
+ gpio_port_write(GPIOA, gpio_port_read(GPIOA) | (1 << pin));
+ } else {
+ gpio_port_write(GPIOA, gpio_port_read(GPIOA) & ~(1 << pin));
+ }
+ } else if (pin < pc0) {
+ if (value) {
+ gpio_port_write(GPIOB, gpio_port_read(GPIOB) | (1 << (pin-pb0)));
+ } else {
+ gpio_port_write(GPIOB, gpio_port_read(GPIOB) & ~(1 << (pin-pb0)));
+ }
+ } else if (pin < PIN_INVALID) {
+ if (value) {
+ gpio_port_write(GPIOC, gpio_port_read(GPIOC) | (1 << (pin-pc0)));
+ } else {
+ gpio_port_write(GPIOC, gpio_port_read(GPIOC) & ~(1 << (pin-pc0)));
+ }
+ }
+ }
+};
+
+extern GPIO gpio;
+
+#endif
diff --git a/include/arch/stm32f746zg-nucleo/driver/stdout.h b/include/arch/stm32f746zg-nucleo/driver/stdout.h
new file mode 100644
index 0000000..fa04e1b
--- /dev/null
+++ b/include/arch/stm32f746zg-nucleo/driver/stdout.h
@@ -0,0 +1,24 @@
+/*
+ * Copyright 2024 Birte Kristina Friesel
+ *
+ * SPDX-License-Identifier: BSD-2-Clause
+ */
+#ifndef STANDARDOUTPUT_H
+#define STANDARDOUTPUT_H
+
+#include "object/outputstream.h"
+
+class StandardOutput : public OutputStream {
+ private:
+ StandardOutput(const StandardOutput &copy);
+
+ public:
+ StandardOutput () {}
+ void setup();
+
+ virtual void put(char c) override;
+};
+
+extern StandardOutput kout;
+
+#endif
diff --git a/include/arch/stm32f746zg-nucleo/driver/uptime.h b/include/arch/stm32f746zg-nucleo/driver/uptime.h
new file mode 100644
index 0000000..cae3424
--- /dev/null
+++ b/include/arch/stm32f746zg-nucleo/driver/uptime.h
@@ -0,0 +1,32 @@
+/*
+ * Copyright 2024 Birte Kristina Friesel
+ *
+ * SPDX-License-Identifier: BSD-2-Clause
+ */
+#ifndef UPTIME_H
+#define UPTIME_H
+
+#include <stdint.h>
+
+class Uptime {
+ private:
+ Uptime(const Uptime &copy);
+#ifdef TIMER_S
+ uint32_t seconds;
+#endif
+
+ public:
+#ifdef TIMER_S
+ Uptime () : seconds(0) {}
+#else
+ Uptime () {}
+#endif
+#ifdef TIMER_S
+ inline uint32_t get_s() { return seconds; }
+ inline void tick_s() { seconds++; }
+#endif
+};
+
+extern Uptime uptime;
+
+#endif
diff --git a/src/arch/stm32f746zg-nucleo/Kconfig b/src/arch/stm32f746zg-nucleo/Kconfig
new file mode 100644
index 0000000..1b634a7
--- /dev/null
+++ b/src/arch/stm32f746zg-nucleo/Kconfig
@@ -0,0 +1,10 @@
+# Copyright 2024 Birte Kristina Friesel
+#
+# SPDX-License-Identifier: CC0-1.0
+config arch_stm32f746zg_nucleo_driver_counter
+bool "Cycle Counter"
+select meta_driver_counter
+
+config arch_stm32f746zg_nucleo_driver_uptime
+bool "Uptime Counter"
+select meta_driver_uptime
diff --git a/src/arch/stm32f746zg-nucleo/Makefile.inc b/src/arch/stm32f746zg-nucleo/Makefile.inc
new file mode 100644
index 0000000..b6e1944
--- /dev/null
+++ b/src/arch/stm32f746zg-nucleo/Makefile.inc
@@ -0,0 +1,140 @@
+# vim:ft=make
+#
+# Copyright 2024 Birte Kristina Friesel
+#
+# SPDX-License-Identifier: BSD-2-Clause
+
+SERIAL_PORT ?= ttyACM0
+
+cpu_freq ?= 216000000
+
+INCLUDES += -Iext/libopencm3/include
+
+COMMON_FLAGS += --static -nostartfiles -g3 -Os -fno-common
+COMMON_FLAGS += -ffunction-sections -fdata-sections
+COMMON_FLAGS += -mcpu=cortex-m7 -mthumb -mfloat-abi=hard -mfpu=fpv5-sp-d16 -DSTM32F7
+
+CC = arm-none-eabi-gcc
+CXX = arm-none-eabi-g++
+OBJCOPY = arm-none-eabi-objcopy
+OBJDUMP = arm-none-eabi-objdump
+SIZE = arm-none-eabi-size
+
+ARCH_SHORTNAME = stm32f7
+
+CXX_TARGETS += src/arch/stm32f746zg-nucleo/arch.cc
+
+ifdef CONFIG_aspectc
+ CXX = ag++ -r build/repo.acp -v 0 --c_compiler arm-none-eabi-g++ -p . --Xcompiler
+endif
+
+CXX_TARGETS += src/arch/stm32f746zg-nucleo/driver/gpio.cc
+CXX_TARGETS += src/arch/stm32f746zg-nucleo/driver/stdout.cc
+
+# Commandline
+
+ifneq ($(findstring counter,${arch_drivers}), )
+ CONFIG_arch_stm32f746zg_nucleo_driver_counter = y
+endif
+
+#ifneq ($(findstring timer,${arch_drivers}), )
+# CONFIG_arch_stm32f746zg_nucleo_driver_timer = y
+#endif
+
+ifeq (${timer_s}, 1)
+ CONFIG_arch_stm32f746zg_nucleo_driver_uptime = y
+endif
+
+# Kconfig
+
+ifdef CONFIG_arch_stm32f746zg_nucleo_driver_counter
+ CXX_TARGETS += src/arch/stm32f746zg-nucleo/driver/counter.cc
+endif
+
+#ifdef CONFIG_arch_stm32f746zg_nucleo_driver_i2c
+# CXX_TARGETS += src/arch/stm32f746zg-nucleo/driver/i2c.cc
+#endif
+
+#ifdef CONFIG_arch_stm32f746zg_nucleo_driver_timer
+# CXX_TARGETS += src/arch/stm32f746zg-nucleo/driver/timer.cc
+#endif
+
+ifdef CONFIG_arch_stm32f746zg_nucleo_driver_uptime
+ COMMON_FLAGS += -DTIMER_S
+ CXX_TARGETS += src/arch/stm32f746zg-nucleo/driver/uptime.cc
+endif
+
+
+ifneq (${cpu_freq}, )
+ COMMON_FLAGS += -DF_CPU=${cpu_freq}UL
+else
+ COMMON_FLAGS += -DF_CPU=216000000UL
+endif
+
+
+OBJECTS = ${CXX_TARGETS:.cc=.o} ${C_TARGETS:.c=.o} ${ASM_TARGETS:.S=.o}
+
+%.o : %.cc | include/config.h
+ ${QUIET}${CXX} ${INCLUDES} ${COMMON_FLAGS} ${CXXFLAGS} -c -o $@ ${@:.o=.cc}
+
+%.o : %.c | include/config.h
+ ${QUIET}${CC} ${INCLUDES} ${COMMON_FLAGS} ${CFLAGS} -c -o $@ ${@:.o=.c}
+
+%.o : %.S | include/config.h
+ ${QUIET}${CC} ${INCLUDES} ${COMMON_FLAGS} -c -o $@ ${@:.o=.S}
+
+%.o : %.s | include/config.h
+ ${QUIET}${CC} ${INCLUDES} ${COMMON_FLAGS} -c -o $@ ${@:.o=.S}
+
+build/system.elf: ${OBJECTS} ext/libopencm3/lib/libopencm3_stm32f7.a
+ ${QUIET}mkdir -p build
+ ${QUIET}${CXX} ${INCLUDES} ${COMMON_FLAGS} ${CXXFLAGS} \
+ -Lext/libopencm3/lib -Wl,--gc-sections \
+ -Wl,--start-group -lc -lgcc -lnosys -Wl,--end-group \
+ -T src/arch/stm32f746zg-nucleo/stm32f746zg.ld \
+ ${OBJECTS} -lopencm3_stm32f7 \
+ -o $@
+ ${QUIET}${SIZE} build/system.elf | tail -n1 | awk '{ print " ROM: " ($$1+$$2) " (" int(($$1+$$2)*100/1048576) "%) RAM: " ($$2 + $$3) " (" int(($$2+$$3)*100/327680) "%)" }'
+
+ext/libopencm3/Makefile:
+ git submodule update --init
+
+ext/libopencm3/lib/libopencm3_stm32f7.a: ext/libopencm3/Makefile
+ ${MAKE} -C ext/libopencm3
+
+program: build/system.elf
+ openocd -c 'source [find interface/stlink.cfg]' \
+ -c 'transport select hla_swd' -c 'source [find target/stm32f7x.cfg]' \
+ -c 'reset_config srst_only' -c '$$_TARGETNAME configure -rtos auto' \
+ -c 'reset_config connect_assert_srst' -c init -c targets \
+ -c 'reset halt' -c 'flash write_image erase "build/system.elf" 0' \
+ -c 'verify_image "build/system.elf" 0' -c 'reset run' -c 'shutdown'
+
+arch_clean:
+ ${QUIET}rm -f ${OBJECTS}
+
+cat:
+ ${QUIET}script/cat.py /dev/${SERIAL_PORT} 115200 ${cpu_freq} 65536
+
+monitor:
+ ${QUIET}screen /dev/${SERIAL_PORT} 115200
+
+arch_help:
+ @echo "stm32f746zg-nucleo specific flags:"
+ @echo " cpu_freq = ${cpu_freq} (desired CPU frequency in Hz)"
+ @echo " supported frequencies: 84 / 168 / 180 MHz"
+
+arch_info:
+ @echo "CPU Freq: ${cpu_freq} Hz"
+ @echo "Timer Freq: ${timer_freq} Hz -> $(shell src/arch/stm32f746zg-nucleo/model.py f_timer "${cpu_freq}" "${timer_freq}")"
+ @echo "I2C Freq: ${i2c_freq} Hz"
+ @echo "Counter Overflow: 4294967296/255"
+ @echo "Monitor: /dev/${SERIAL_PORT} 115200"
+
+attributes: build/system.elf
+ ${QUIET}script/size.py ${SIZE} text,data data,bss
+
+nfpvalues: build/system.elf
+ ${QUIET}script/nfpvalues.py ${SIZE} text,data data,bss
+
+.PHONY: arch_clean arch_help arch_info attributes cat monitor program
diff --git a/src/arch/stm32f746zg-nucleo/arch.cc b/src/arch/stm32f746zg-nucleo/arch.cc
new file mode 100644
index 0000000..4adb883
--- /dev/null
+++ b/src/arch/stm32f746zg-nucleo/arch.cc
@@ -0,0 +1,122 @@
+/*
+ * Copyright 2024 Birte Kristina Friesel
+ *
+ * SPDX-License-Identifier: BSD-2-Clause
+ */
+#include <libopencm3/cm3/nvic.h>
+#include <libopencm3/stm32/rcc.h>
+#include <libopencm3/stm32/gpio.h>
+#include <libopencm3/stm32/timer.h>
+#include "arch.h"
+
+#ifdef __acweaving
+#define __delay_cycles(x)
+#endif
+
+void Arch::setup(void)
+{
+#if F_CPU == 216000000UL
+ rcc_clock_setup_hsi(&rcc_3v3[RCC_CLOCK_3V3_216MHZ]);
+#else
+#error Unsupported F_CPU
+#endif
+
+ // counter
+ rcc_periph_clock_enable(RCC_TIM2);
+ nvic_enable_irq(NVIC_TIM2_IRQ);
+ rcc_periph_reset_pulse(RST_TIM2);
+ timer_set_mode(TIM2, TIM_CR1_CKD_CK_INT,
+ TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP);
+ timer_set_prescaler(TIM2, 0);
+ timer_disable_preload(TIM2);
+ timer_continuous_mode(TIM2);
+ timer_set_period(TIM2, 4294967295);
+ timer_enable_irq(TIM2, TIM_DIER_UIE);
+
+#ifdef CONFIG_loop
+ rcc_periph_clock_enable(RCC_TIM3);
+ nvic_enable_irq(NVIC_TIM3_IRQ);
+ rcc_periph_reset_pulse(RST_TIM3);
+
+
+ timer_set_mode(TIM3, TIM_CR1_CKD_CK_INT,
+ TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP);
+ // 10 kHz timer frequency
+ timer_set_prescaler(TIM3, ((rcc_apb1_frequency * 2) / 10000));
+
+ timer_continuous_mode(TIM3); // ?
+
+ timer_set_period(TIM3, 10000);
+
+ timer_enable_counter(TIM3);
+ timer_enable_irq(TIM3, TIM_DIER_UIE);
+#endif
+}
+
+#ifdef CONFIG_wakeup
+extern void wakeup();
+#endif
+
+#if defined(CONFIG_loop)
+extern void loop();
+volatile char run_loop = 0;
+#endif
+
+// for 216 MHz(?)
+void Arch::delay_us(unsigned int const us)
+{
+ volatile int x = us * 145;
+ while (x--) {
+ __asm("nop");
+ }
+}
+void Arch::delay_ms(unsigned int const ms)
+{
+ for (unsigned int i = 0; i < ms; i++) {
+ volatile int x = 143990;
+ while (x--) {
+ __asm("nop");
+ }
+ }
+}
+
+void Arch::idle_loop(void)
+{
+ while (1) {
+ //pwr_set_standby_mode();
+ __asm__("wfi");
+#ifdef CONFIG_loop
+ if (run_loop) {
+ loop();
+ run_loop = 0;
+ }
+#endif
+ }
+}
+
+void Arch::idle(void)
+{
+#ifdef CONFIG_wakeup
+ wakeup();
+#endif
+}
+
+Arch arch;
+
+#if defined(CONFIG_loop) || defined(TIMER_S)
+
+#include "driver/uptime.h"
+
+void tim3_isr(void)
+{
+ if (timer_get_flag(TIM3, TIM_SR_UIF)) {
+ timer_clear_flag(TIM3, TIM_SR_UIF);
+#ifdef CONFIG_loop
+ run_loop = 1;
+#endif
+#ifdef TIMER_S
+ uptime.tick_s();
+#endif
+ }
+}
+#endif
diff --git a/src/arch/stm32f746zg-nucleo/driver/counter.cc b/src/arch/stm32f746zg-nucleo/driver/counter.cc
new file mode 100644
index 0000000..5f007f1
--- /dev/null
+++ b/src/arch/stm32f746zg-nucleo/driver/counter.cc
@@ -0,0 +1,19 @@
+/*
+ * Copyright 2024 Birte Kristina Friesel
+ *
+ * SPDX-License-Identifier: BSD-2-Clause
+ */
+#include "arch.h"
+#include "driver/counter.h"
+
+Counter counter;
+
+void tim2_isr(void)
+{
+ if (timer_get_flag(TIM2, TIM_SR_UIF)) {
+ timer_clear_flag(TIM2, TIM_SR_UIF);
+ if (counter.overflow < 4294967295) {
+ counter.overflow++;
+ }
+ }
+}
diff --git a/src/arch/stm32f746zg-nucleo/driver/gpio.cc b/src/arch/stm32f746zg-nucleo/driver/gpio.cc
new file mode 100644
index 0000000..82a9fd0
--- /dev/null
+++ b/src/arch/stm32f746zg-nucleo/driver/gpio.cc
@@ -0,0 +1,8 @@
+/*
+ * Copyright 2024 Birte Kristina Friesel
+ *
+ * SPDX-License-Identifier: BSD-2-Clause
+ */
+#include "driver/gpio.h"
+
+GPIO gpio;
diff --git a/src/arch/stm32f746zg-nucleo/driver/stdout.cc b/src/arch/stm32f746zg-nucleo/driver/stdout.cc
new file mode 100644
index 0000000..9a5bdfb
--- /dev/null
+++ b/src/arch/stm32f746zg-nucleo/driver/stdout.cc
@@ -0,0 +1,36 @@
+/*
+ * Copyright 2024 Birte Kristina Friesel
+ *
+ * SPDX-License-Identifier: BSD-2-Clause
+ */
+#include "driver/stdout.h"
+
+#include <libopencm3/stm32/rcc.h>
+#include <libopencm3/stm32/gpio.h>
+#include <libopencm3/stm32/usart.h>
+
+void StandardOutput::setup()
+{
+ rcc_periph_clock_enable(RCC_USART3);
+ gpio_mode_setup(GPIOD, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO8);
+ gpio_set_af(GPIOD, GPIO_AF7, GPIO8);
+
+ usart_set_baudrate(USART3, 115200);
+ usart_set_databits(USART3, 8);
+ usart_set_stopbits(USART3, USART_STOPBITS_1);
+ usart_set_mode(USART3, USART_MODE_TX);
+ usart_set_parity(USART3, USART_PARITY_NONE);
+ usart_set_flow_control(USART3, USART_FLOWCONTROL_NONE);
+
+ usart_enable(USART3);
+}
+
+void StandardOutput::put(char c)
+{
+ usart_send_blocking(USART3, c);
+ if (c == '\n') {
+ put('\r');
+ }
+}
+
+StandardOutput kout;
diff --git a/src/arch/stm32f746zg-nucleo/driver/uptime.cc b/src/arch/stm32f746zg-nucleo/driver/uptime.cc
new file mode 100644
index 0000000..8ddb57a
--- /dev/null
+++ b/src/arch/stm32f746zg-nucleo/driver/uptime.cc
@@ -0,0 +1,8 @@
+/*
+ * Copyright 2024 Birte Kristina Friesel
+ *
+ * SPDX-License-Identifier: BSD-2-Clause
+ */
+#include "driver/uptime.h"
+
+Uptime uptime;
diff --git a/src/arch/stm32f746zg-nucleo/prompt b/src/arch/stm32f746zg-nucleo/prompt
new file mode 100644
index 0000000..168f0e0
--- /dev/null
+++ b/src/arch/stm32f746zg-nucleo/prompt
@@ -0,0 +1 @@
+STM32F746ZG Nucleo
diff --git a/src/arch/stm32f746zg-nucleo/stm32f746zg.ld b/src/arch/stm32f746zg-nucleo/stm32f746zg.ld
new file mode 100644
index 0000000..7680d9f
--- /dev/null
+++ b/src/arch/stm32f746zg-nucleo/stm32f746zg.ld
@@ -0,0 +1,13 @@
+/*
+ * Copyright 2024 Birte Kristina Friesel
+ *
+ * SPDX-License-Identifier: CC0-1.0
+ */
+
+MEMORY
+{
+ rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 320K
+}
+
+INCLUDE ext/libopencm3/lib/cortex-m-generic.ld