aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--.gitignore17
-rw-r--r--examples/Makefile10
-rw-r--r--examples/Makefile.include123
-rw-r--r--examples/mb525/fancyblink/Makefile76
-rw-r--r--examples/mb525/pwmleds/Makefile76
-rw-r--r--examples/mb525/pwmleds/pwmleds.c33
-rw-r--r--examples/obldc/Makefile56
-rw-r--r--examples/obldc/can/Makefile22
-rw-r--r--examples/obldc/can/can.c216
-rw-r--r--examples/obldc/can/can.ld31
-rw-r--r--examples/obldc/led/Makefile22
-rw-r--r--examples/obldc/led/led.c67
-rw-r--r--examples/obldc/led/led.ld31
-rw-r--r--examples/obldc/systick/Makefile22
-rw-r--r--examples/obldc/systick/systick.c90
-rw-r--r--examples/obldc/systick/systick.ld31
-rw-r--r--examples/obldc/usart/Makefile22
-rw-r--r--examples/obldc/usart/usart.c91
-rw-r--r--examples/obldc/usart/usart.ld31
-rw-r--r--examples/obldc/usart_irq/Makefile24
-rw-r--r--examples/obldc/usart_irq/usart_irq.c126
-rw-r--r--examples/obldc/usart_irq/usart_irq.ld31
-rw-r--r--examples/other/adc_temperature_sensor/Makefile75
-rw-r--r--examples/other/dma_mem2mem/Makefile75
-rw-r--r--examples/other/dogm128/Makefile75
-rw-r--r--examples/other/i2c_stts75_sensor/Makefile75
-rw-r--r--examples/other/rtc/Makefile75
-rw-r--r--examples/other/systick/Makefile75
-rw-r--r--examples/other/timer_interrupt/Makefile75
-rw-r--r--examples/other/usb_cdcacm/Makefile75
-rw-r--r--examples/other/usb_dfu/Makefile75
-rw-r--r--examples/other/usb_hid/Makefile75
-rw-r--r--examples/other/usb_hid/README4
-rw-r--r--examples/stm32-h103/fancyblink/Makefile75
-rw-r--r--examples/stm32-h103/miniblink/Makefile75
-rw-r--r--examples/stm32-h103/spi/Makefile75
-rw-r--r--examples/stm32-h103/usart/Makefile75
-rw-r--r--examples/stm32-h103/usart/usart.c6
-rw-r--r--examples/stm32-h103/usb_cdcacm/Makefile78
-rw-r--r--include/libopenstm32.h1
-rw-r--r--include/libopenstm32/can.h642
-rw-r--r--include/libopenstm32/common.h1
-rw-r--r--include/libopenstm32/ethernet.h203
-rw-r--r--include/libopenstm32/gpio.h171
-rw-r--r--include/libopenstm32/usart.h58
-rw-r--r--lib/Makefile7
-rw-r--r--lib/can.c305
-rw-r--r--lib/ethernet.c53
-rw-r--r--lib/gpio.c14
-rw-r--r--lib/libopenstm32.ld14
-rw-r--r--lib/rcc.c2
-rw-r--r--lib/usart.c36
52 files changed, 2554 insertions, 1339 deletions
diff --git a/.gitignore b/.gitignore
index 44e1627..580cdee 100644
--- a/.gitignore
+++ b/.gitignore
@@ -1,9 +1,10 @@
-examples/miniblink/*.o
+*.o
examples/miniblink/miniblink
-examples/miniblink/miniblink.bin
-examples/miniblink/miniblink.hex
-examples/miniblink/miniblink.list
-examples/miniblink/miniblink.srec
-lib/*.o
-lib/libopenstm32.a
-
+*.bin
+*.hex
+*.list
+*.srec
+*.a
+*.elf
+\#*
+.\#*
diff --git a/examples/Makefile b/examples/Makefile
index 0f772e2..30e2505 100644
--- a/examples/Makefile
+++ b/examples/Makefile
@@ -24,7 +24,7 @@ Q := @
MAKEFLAGS += --no-print-directory
endif
-all: stm32-h103 mb525 other lisa-m
+all: stm32-h103 mb525 lisa-m obldc other
stm32-h103:
@printf " BUILD examples/stm32-h103\n"
@@ -42,6 +42,10 @@ other:
@printf " BUILD examples/other\n"
$(Q)$(MAKE) -C other
+obldc:
+ @printf " BUILD examples/obldc\n"
+ $(Q)$(MAKE) -C obldc
+
clean:
@printf " CLEAN examples/stm32-h103\n"
$(Q)$(MAKE) -C stm32-h103 clean
@@ -51,6 +55,8 @@ clean:
$(Q)$(MAKE) -C lisa-m clean
@printf " CLEAN examples/other\n"
$(Q)$(MAKE) -C other clean
+ @printf " CLEAN examples/obldc\n"
+ $(Q)$(MAKE) -C obldc clean
-.PHONY: stm32-h103 mb525 lisa-m other clean
+.PHONY: stm32-h103 mb525 lisa-m other obldc clean
diff --git a/examples/Makefile.include b/examples/Makefile.include
new file mode 100644
index 0000000..bd978fe
--- /dev/null
+++ b/examples/Makefile.include
@@ -0,0 +1,123 @@
+## This file is part of the libopenstm32 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+## Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
+##
+## 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/>.
+##
+
+# PREFIX ?= arm-none-eabi
+PREFIX ?= arm-elf
+CC = $(PREFIX)-gcc
+LD = $(PREFIX)-gcc
+OBJCOPY = $(PREFIX)-objcopy
+OBJDUMP = $(PREFIX)-objdump
+# Uncomment this line if you want to use the installed (not local) library.
+# TOOLCHAIN_DIR = `dirname \`which $(CC)\``/../$(PREFIX)
+TOOLCHAIN_DIR = ../../..
+CFLAGS += -Os -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
+ -mcpu=cortex-m3 -mthumb
+LDSCRIPT = $(BINARY).ld
+LDFLAGS += -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles \
+ -Wl,--gc-sections
+OBJS += $(BINARY).o
+
+OOCD ?= openocd
+OOCD_INTERFACE ?= flossjtag
+OOCD_BOARD ?= olimex_stm32_h103
+
+# Be silent per default, but 'make V=1' will show all compiler calls.
+ifneq ($(V),1)
+Q := @
+NULL := 2>/dev/null
+else
+LDFLAGS += -Wl,--print-gc-sections
+endif
+
+.SUFFIXES: .elf .bin .hex .srec .list .images
+.SECONDEXPANSION:
+.SECONDARY:
+
+all: images
+
+images: $(BINARY).images
+flash: $(BINARY).flash
+
+%.images: %.bin %.hex %.srec %.list
+ @echo "*** $* images generated ***"
+
+%.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: $(OBJS) $(LDSCRIPT)
+ @printf " LD $(subst $(shell pwd)/,,$(@))\n"
+ $(Q)$(LD) $(LDFLAGS) -o $(*).elf $(OBJS) -lopenstm32
+
+%.o: %.c Makefile
+ @printf " CC $(subst $(shell pwd)/,,$(@))\n"
+ $(Q)$(CC) $(CFLAGS) -o $@ -c $<
+
+clean:
+ @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
+ $(Q)rm -f *.o
+ @printf " CLEAN *.elf\n"
+ $(Q)rm -f *.elf
+ @printf " CLEAN *.bin\n"
+ $(Q)rm -f *.bin
+ @printf " CLEAN *.hex\n"
+ $(Q)rm -f *.hex
+ @printf " CLEAN *.srec\n"
+ $(Q)rm -f *.srec
+ @printf " CLEAN *.list\n"
+ $(Q)rm -f *.list
+
+ifeq ($(OOCD_SERIAL),)
+%.flash: %.hex
+ @printf " FLASH $<\n"
+ @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
+ $(Q)$(OOCD) -f interface/$(OOCD_INTERFACE).cfg \
+ -f board/$(OOCD_BOARD).cfg \
+ -c "init" -c "reset init" \
+ -c "stm32x mass_erase 0" \
+ -c "flash write_image $(*).hex" \
+ -c "reset" \
+ -c "shutdown" $(NULL)
+else
+%.flash: %.hex
+ @printf " FLASH $<\n"
+ @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
+ $(Q)$(OOCD) -f interface/$(OOCD_INTERFACE).cfg \
+ -f board/$(OOCD_BOARD).cfg \
+ -c "ft2232_serial $(OOCD_SERIAL)" \
+ -c "init" -c "reset init" \
+ -c "stm32x mass_erase 0" \
+ -c "flash write_image $(*).hex" \
+ -c "reset" \
+ -c "shutdown" $(NULL)
+endif
+
+.PHONY: images clean
diff --git a/examples/mb525/fancyblink/Makefile b/examples/mb525/fancyblink/Makefile
index ae68552..a712cc4 100644
--- a/examples/mb525/fancyblink/Makefile
+++ b/examples/mb525/fancyblink/Makefile
@@ -19,78 +19,4 @@
BINARY = fancyblink
-# PREFIX ?= arm-none-eabi
-PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-ld
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-# TOOLCHAIN_DIR = `dirname \`which $(CC)\``/../$(PREFIX)
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
-#LDFLAGS = -T$(LDSCRIPT) -nostartfiles
-OBJS = $(BINARY).o
-
-OPENOCD_BASE = /usr
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/parport.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/board/olimex_stm32_h103.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
-
+include ../../Makefile.include
diff --git a/examples/mb525/pwmleds/Makefile b/examples/mb525/pwmleds/Makefile
index ee3e8eb..241e1fa 100644
--- a/examples/mb525/pwmleds/Makefile
+++ b/examples/mb525/pwmleds/Makefile
@@ -19,78 +19,4 @@
BINARY = pwmleds
-# PREFIX ?= arm-none-eabi
-PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-ld
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-# TOOLCHAIN_DIR = `dirname \`which $(CC)\``/../$(PREFIX)
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
-#LDFLAGS = -T$(LDSCRIPT) -nostartfiles
-OBJS = $(BINARY).o
-
-OPENOCD_BASE = /usr
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/parport.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/board/olimex_stm32_h103.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
-
+include ../../Makefile.include
diff --git a/examples/mb525/pwmleds/pwmleds.c b/examples/mb525/pwmleds/pwmleds.c
index 23ebbe1..ca707ac 100644
--- a/examples/mb525/pwmleds/pwmleds.c
+++ b/examples/mb525/pwmleds/pwmleds.c
@@ -245,7 +245,7 @@ void clock_setup(void)
/* Enable GPIOC, Alternate Function clocks. */
rcc_peripheral_enable_clock(&RCC_APB2ENR,
- RCC_APB2ENR_IOPCEN | RCC_APB2ENR_AFIOEN);
+ RCC_APB2ENR_IOPCEN | RCC_APB2ENR_AFIOEN);
}
void gpio_setup(void)
@@ -255,8 +255,11 @@ void gpio_setup(void)
* 'output alternate function push-pull'.
*/
gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
- GPIO_CNF_OUTPUT_ALTFN_PUSHPULL,
- GPIO6 | GPIO7 | GPIO8 | GPIO9);
+ GPIO_CNF_OUTPUT_ALTFN_PUSHPULL,
+ GPIO_TIM3_FR_CH1 |
+ GPIO_TIM3_FR_CH2 |
+ GPIO_TIM3_FR_CH3 |
+ GPIO_TIM3_FR_CH4);
/* Remap TIM3:
* CH1 -> PC6
@@ -454,18 +457,18 @@ int main(void)
if (j == 100) {
j = 0;
switch (k += kd) {
- case 0:
- j0 = 255;
- break;
- case 1:
- j1 = 255;
- break;
- case 2:
- j2 = 255;
- break;
- case 3:
- j3 = 255;
- break;
+ case 0:
+ j0 = 255;
+ break;
+ case 1:
+ j1 = 255;
+ break;
+ case 2:
+ j2 = 255;
+ break;
+ case 3:
+ j3 = 255;
+ break;
}
if (k == 3)
kd =- 1;
diff --git a/examples/obldc/Makefile b/examples/obldc/Makefile
new file mode 100644
index 0000000..8014fce
--- /dev/null
+++ b/examples/obldc/Makefile
@@ -0,0 +1,56 @@
+##
+## This file is part of the libopenstm32 project.
+##
+## Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
+##
+## 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/>.
+##
+
+# Be silent per default, but 'make V=1' will show all compiler calls.
+ifneq ($(V),1)
+Q := @
+# Do not print "Entering directory ...".
+MAKEFLAGS += --no-print-directory
+endif
+
+all: led systick usart can
+
+led:
+ @printf " BUILD examples/obldc/led\n"
+ $(Q)$(MAKE) -C led
+
+systick:
+ @printf " BUILD examples/obldc/systick\n"
+ $(Q)$(MAKE) -C systick
+
+usart:
+ @printf " BUILD examples/obldc/usart\n"
+ $(Q)$(MAKE) -C usart
+
+can:
+ @printf " BUILD examples/obldc/can\n"
+ $(Q)$(MAKE) -C can
+
+clean:
+ @printf " CLEAN examples/obldc/led\n"
+ $(Q)$(MAKE) -C led clean
+ @printf " CLEAN examples/obldc/systick\n"
+ $(Q)$(MAKE) -C systick clean
+ @printf " CLEAN examples/obldc/usart\n"
+ $(Q)$(MAKE) -C usart clean
+ @printf " CLEAN examples/obldc/can\n"
+ $(Q)$(MAKE) -C can clean
+
+.PHONY: led systick usart can
+
diff --git a/examples/obldc/can/Makefile b/examples/obldc/can/Makefile
new file mode 100644
index 0000000..397a445
--- /dev/null
+++ b/examples/obldc/can/Makefile
@@ -0,0 +1,22 @@
+##
+## This file is part of the libopenstm32 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+##
+## 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/>.
+##
+
+BINARY = can
+
+include ../../Makefile.include
diff --git a/examples/obldc/can/can.c b/examples/obldc/can/can.c
new file mode 100644
index 0000000..d96d1c9
--- /dev/null
+++ b/examples/obldc/can/can.c
@@ -0,0 +1,216 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
+ * Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
+ *
+ * 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 <libopenstm32/rcc.h>
+#include <libopenstm32/flash.h>
+#include <libopenstm32/gpio.h>
+#include <libopenstm32/nvic.h>
+#include <libopenstm32/systick.h>
+#include <libopenstm32/can.h>
+
+struct can_tx_msg {
+ u32 std_id;
+ u32 ext_id;
+ u8 ide;
+ u8 rtr;
+ u8 dlc;
+ u8 data[8];
+};
+
+struct can_rx_msg {
+ u32 std_id;
+ u32 ext_id;
+ u8 ide;
+ u8 rtr;
+ u8 dlc;
+ u8 data[8];
+ u8 fmi;
+};
+
+struct can_tx_msg can_tx_msg;
+struct can_rx_msg can_rx_msg;
+
+void gpio_setup(void)
+{
+ /* Enable GPIOA clock. */
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+
+ /* Enable GPIOB clock. */
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
+
+ gpio_set(GPIOA, GPIO6); /* LED0 off */
+ gpio_set(GPIOA, GPIO7); /* LED1 off */
+ gpio_set(GPIOB, GPIO0); /* LED2 off */
+ gpio_set(GPIOB, GPIO1); /* LED3 off */
+
+ /* Set GPIO6/7 (in GPIO port A) to 'output push-pull' for the LEDs. */
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO6);
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO7);
+
+ /* Set GPIO6/7 (in GPIO port B) to 'output push-pull' for the LEDs. */
+ gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO0);
+ gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO1);
+}
+
+void systick_setup(void)
+{
+ /* 72MHz / 8 => 9000000 counts per second */
+ systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
+
+ /* 9000000/9000 = 1000 overflows per second - every 1ms one interrupt */
+ systick_set_reload(9000);
+
+ systick_interrupt_enable();
+
+ /* Start counting. */
+ systick_counter_enable();
+}
+
+void can_setup(void)
+{
+ /* Enable peripheral clocks. */
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_CANEN);
+
+ /* Configure CAN pin: RX (input pull-up). */
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT,
+ GPIO_CNF_INPUT_PULL_UPDOWN, GPIO_CAN_RX);
+ gpio_set(GPIOA, GPIO_CAN_RX);
+
+ /* Configure CAN pin: TX. */
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_CAN_TX);
+
+ /* NVIC setup. */
+ nvic_enable_irq(NVIC_USB_LP_CAN_RX0_IRQ);
+ nvic_set_priority(NVIC_USB_LP_CAN_RX0_IRQ, 1);
+
+ /* Reset CAN. */
+ can_reset(CAN1);
+
+ /* CAN cell init. */
+ if (can_init(CAN1,
+ false, /* TTCM: Time triggered comm mode? */
+ true, /* ABOM: Automatic bus-off management? */
+ false, /* AWUM: Automatic wakeup mode? */
+ false, /* NART: No automatic retransmission? */
+ false, /* RFLM: Receive FIFO locked mode? */
+ false, /* TXFP: Transmit FIFO priority? */
+ CAN_BTR_SJW_1TQ,
+ CAN_BTR_TS1_3TQ,
+ CAN_BTR_TS2_4TQ,
+ 12)) /* BRP+1: Baud rate prescaler */
+ {
+ gpio_set(GPIOA, GPIO6); /* LED0 off */
+ gpio_set(GPIOA, GPIO7); /* LED1 off */
+ gpio_set(GPIOB, GPIO0); /* LED2 off */
+ gpio_clear(GPIOB, GPIO1); /* LED3 on */
+
+ /* Die because we failed to initialize. */
+ while (1)
+ __asm__("nop");
+ }
+
+ /* CAN filter 0 init. */
+ can_filter_id_mask_32bit_init(CAN1,
+ 0, /* Filter ID */
+ 0, /* CAN ID */
+ 0, /* CAN ID mask */
+ 0, /* FIFO assignment (here: FIFO0) */
+ true); /* Enable the filter. */
+
+ /* Enable CAN RX interrupt. */
+ can_enable_irq(CAN1, CAN_IER_FMPIE0);
+}
+
+void sys_tick_handler(void)
+{
+ static int temp32 = 0;
+ static u8 data[8] = {0, 1, 2, 0, 0, 0, 0, 0};
+
+ /* We call this handler every 1ms so 1000ms = 1s on/off. */
+ if (++temp32 != 1000)
+ return;
+
+ temp32 = 0;
+
+ /* Transmit CAN frame. */
+ data[0]++;
+ if (can_transmit(CAN1,
+ 0, /* (EX/ST)ID: CAN ID */
+ false, /* IDE: CAN ID extended? */
+ false, /* RTR: Request transmit? */
+ 8, /* DLC: Data length */
+ data) == -1)
+ {
+ gpio_set(GPIOA, GPIO6); /* LED0 off */
+ gpio_set(GPIOA, GPIO7); /* LED1 off */
+ gpio_clear(GPIOB, GPIO0); /* LED2 on */
+ gpio_set(GPIOB, GPIO1); /* LED3 off */
+ }
+}
+
+void usb_lp_can_rx0_isr(void)
+{
+ u32 id, fmi;
+ bool ext, rtr;
+ u8 length, data[8];
+
+ can_receive(CAN1, 0, false, &id, &ext, &rtr, &fmi, &length, data);
+
+ if (data[0] & 1)
+ gpio_clear(GPIOA, GPIO6);
+ else
+ gpio_set(GPIOA, GPIO6);
+
+ if (data[0] & 2)
+ gpio_clear(GPIOA, GPIO7);
+ else
+ gpio_set(GPIOA, GPIO7);
+
+ if (data[0] & 4)
+ gpio_clear(GPIOB, GPIO0);
+ else
+ gpio_set(GPIOB, GPIO0);
+
+ if (data[0] & 8)
+ gpio_clear(GPIOB, GPIO1);
+ else
+ gpio_set(GPIOB, GPIO1);
+
+ can_fifo_release(CAN1, 0);
+}
+
+int main(void)
+{
+ rcc_clock_setup_in_hse_8mhz_out_72mhz();
+ gpio_setup();
+ can_setup();
+ systick_setup();
+
+ while (1); /* Halt. */
+
+ return 0;
+}
diff --git a/examples/obldc/can/can.ld b/examples/obldc/can/can.ld
new file mode 100644
index 0000000..a1e9de5
--- /dev/null
+++ b/examples/obldc/can/can.ld
@@ -0,0 +1,31 @@
+/*
+ * 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/>.
+ */
+
+/* Linker script for an STM32F103RBT6 board (128K flash, 20K RAM). */
+
+/* Define memory regions. */
+MEMORY
+{
+ rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
+}
+
+/* Include the common ld script from libopenstm32. */
+INCLUDE libopenstm32.ld
+
diff --git a/examples/obldc/led/Makefile b/examples/obldc/led/Makefile
new file mode 100644
index 0000000..40d30f3
--- /dev/null
+++ b/examples/obldc/led/Makefile
@@ -0,0 +1,22 @@
+##
+## This file is part of the libopenstm32 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+##
+## 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/>.
+##
+
+BINARY = led
+
+include ../../Makefile.include
diff --git a/examples/obldc/led/led.c b/examples/obldc/led/led.c
new file mode 100644
index 0000000..7784106
--- /dev/null
+++ b/examples/obldc/led/led.c
@@ -0,0 +1,67 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+ * Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
+ *
+ * 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 <libopenstm32/rcc.h>
+#include <libopenstm32/gpio.h>
+
+/* Set STM32 to 72 MHz. */
+void clock_setup(void)
+{
+ rcc_clock_setup_in_hse_8mhz_out_72mhz();
+
+ /* Enable GPIOA clock. */
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+
+ /* Enable GPIOB clock. */
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
+}
+
+void gpio_setup(void)
+{
+ /* Set GPIO6 and 7 (in GPIO port A) to 'output push-pull'. */
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO6 | GPIO7);
+
+ /* Set GPIO0 and 1 (in GPIO port B) to 'output push-pull'. */
+ gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO0 | GPIO1);
+}
+
+int main(void)
+{
+ int i;
+
+ clock_setup();
+ gpio_setup();
+
+ /* Blink the LEDs on the board. */
+ while (1) {
+ gpio_toggle(GPIOA, GPIO6); /* LED on/off */
+ for (i = 0; i < 800000; i++); /* Wait (needs -O0 CFLAGS). */
+ gpio_toggle(GPIOA, GPIO7); /* LED on/off */
+ for (i = 0; i < 800000; i++); /* Wait (needs -O0 CFLAGS). */
+ gpio_toggle(GPIOB, GPIO0); /* LED on/off */
+ for (i = 0; i < 800000; i++); /* Wait (needs -O0 CFLAGS). */
+ gpio_toggle(GPIOB, GPIO1); /* LED on/off */
+ for (i = 0; i < 800000; i++); /* Wait (needs -O0 CFLAGS). */
+ }
+
+ return 0;
+}
diff --git a/examples/obldc/led/led.ld b/examples/obldc/led/led.ld
new file mode 100644
index 0000000..c8683d5
--- /dev/null
+++ b/examples/obldc/led/led.ld
@@ -0,0 +1,31 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+ *
+ * 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/>.
+ */
+
+/* Linker script for Open-BLDC (STM32F103CBT6, 128K flash, 20K RAM). */
+
+/* Define memory regions. */
+MEMORY
+{
+ rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
+}
+
+/* Include the common ld script from libopenstm32. */
+INCLUDE libopenstm32.ld
+
diff --git a/examples/obldc/systick/Makefile b/examples/obldc/systick/Makefile
new file mode 100644
index 0000000..a83b7ff
--- /dev/null
+++ b/examples/obldc/systick/Makefile
@@ -0,0 +1,22 @@
+##
+## This file is part of the libopenstm32 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+##
+## 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/>.
+##
+
+BINARY = systick
+
+include ../../Makefile.include
diff --git a/examples/obldc/systick/systick.c b/examples/obldc/systick/systick.c
new file mode 100644
index 0000000..c469c1c
--- /dev/null
+++ b/examples/obldc/systick/systick.c
@@ -0,0 +1,90 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
+ * Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
+ *
+ * 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 <libopenstm32/rcc.h>
+#include <libopenstm32/flash.h>
+#include <libopenstm32/gpio.h>
+#include <libopenstm32/nvic.h>
+#include <libopenstm32/systick.h>
+
+u32 temp32;
+
+void gpio_setup(void)
+{
+ /* Enable GPIOA clock. */
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+
+ /* Enable GPIOB clock. */
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
+
+ gpio_set(GPIOA, GPIO6); /* LED0 off */
+ gpio_set(GPIOA, GPIO7); /* LED1 off */
+ gpio_set(GPIOB, GPIO0); /* LED2 off */
+ gpio_set(GPIOB, GPIO1); /* LED3 off */
+
+ /* Set GPIO6/7 (in GPIO port A) to 'output push-pull' for the LEDs. */
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO6);
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO7);
+
+ /* Set GPIO6/7 (in GPIO port B) to 'output push-pull' for the LEDs. */
+ gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO0);
+ gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO1);
+}
+
+void sys_tick_handler(void)
+{
+ temp32++;
+
+ /* We call this handler every 1ms so 1000ms = 1s on/off. */
+ if (temp32 == 1000) {
+ gpio_toggle(GPIOA, GPIO6); /* LED2 on/off */
+ temp32 = 0;
+ }
+}
+
+int main(void)
+{
+ rcc_clock_setup_in_hse_8mhz_out_72mhz();
+ gpio_setup();
+
+ gpio_clear(GPIOA, GPIO7); /* LED1 on */
+ gpio_set(GPIOA, GPIO6); /* LED2 off */
+
+ temp32 = 0;
+
+ /* 72MHz / 8 => 9000000 counts per second */
+ systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
+
+ /* 9000000/9000 = 1000 overflows per second - every 1ms one interrupt */
+ systick_set_reload(9000);
+
+ systick_interrupt_enable();
+
+ /* Start counting. */
+ systick_counter_enable();
+
+ while (1); /* Halt. */
+
+ return 0;
+}
diff --git a/examples/obldc/systick/systick.ld b/examples/obldc/systick/systick.ld
new file mode 100644
index 0000000..0d79751
--- /dev/null
+++ b/examples/obldc/systick/systick.ld
@@ -0,0 +1,31 @@
+/*
+ * 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/>.
+ */
+
+/* Linker script for an STM32F103CBT6 board (128K flash, 20K RAM). */
+
+/* Define memory regions. */
+MEMORY
+{
+ rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
+}
+
+/* Include the common ld script from libopenstm32. */
+INCLUDE libopenstm32.ld
+
diff --git a/examples/obldc/usart/Makefile b/examples/obldc/usart/Makefile
new file mode 100644
index 0000000..6484117
--- /dev/null
+++ b/examples/obldc/usart/Makefile
@@ -0,0 +1,22 @@
+##
+## This file is part of the libopenstm32 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+##
+## 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/>.
+##
+
+BINARY = usart
+
+include ../../Makefile.include
diff --git a/examples/obldc/usart/usart.c b/examples/obldc/usart/usart.c
new file mode 100644
index 0000000..8712181
--- /dev/null
+++ b/examples/obldc/usart/usart.c
@@ -0,0 +1,91 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+ *
+ * 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 <libopenstm32/rcc.h>
+#include <libopenstm32/gpio.h>
+#include <libopenstm32/usart.h>
+
+void clock_setup(void)
+{
+ rcc_clock_setup_in_hse_8mhz_out_72mhz();
+
+ /* Enable GPIOA clock. For LED gpio's */
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+
+ /* Enable clocks for GPIO port B (for GPIO_USART1_TX) and USART1. */
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_USART1EN);
+}
+
+void usart_setup(void)
+{
+
+ /* Setup GPIO6 (in GPIO port A) to 'output push-pull' for led use. */
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL,
+ GPIO6);
+
+ AFIO_MAPR |= AFIO_MAPR_USART1_REMAP;
+
+ /* Setup GPIO pin GPIO_USART3_TX/GPIO10 on GPIO port B for transmit. */
+ gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART1_RE_TX);
+
+ /* Setup UART parameters. */
+ usart_set_baudrate(USART1, 230400);
+ usart_set_databits(USART1, 8);
+ usart_set_stopbits(USART1, USART_STOPBITS_1);
+ usart_set_mode(USART1, USART_MODE_TX);
+ usart_set_parity(USART1, USART_PARITY_NONE);
+ usart_set_flow_control(USART1, USART_FLOWCONTROL_NONE);
+
+ /* Finally enable the USART. */
+ usart_enable(USART1);
+}
+
+void gpio_setup(void)
+{
+ /* Set GPIO12 (in GPIO port C) to 'output push-pull'. */
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO6);
+}
+
+int main(void)
+{
+ int i, j = 0, c = 0;
+
+ clock_setup();
+ gpio_setup();
+ usart_setup();
+
+ /* Blink the LED (PC12) on the board with every transmitted byte. */
+ while (1) {
+ gpio_toggle(GPIOA, GPIO6); /* LED on/off */
+ usart_send_blocking(USART1, c + '0'); /* Send one byte on USART3. */
+ c = (c == 9) ? 0 : c + 1; /* Increment c. */
+ if ((j++ % 80) == 0) { /* Newline after line full. */
+ usart_send_blocking(USART1, '\r');
+ usart_send_blocking(USART1, '\n');
+ }
+ for (i = 0; i < 80000; i++); /* Wait (needs -O0 CFLAGS). */
+ }
+
+ return 0;
+}
diff --git a/examples/obldc/usart/usart.ld b/examples/obldc/usart/usart.ld
new file mode 100644
index 0000000..c8683d5
--- /dev/null
+++ b/examples/obldc/usart/usart.ld
@@ -0,0 +1,31 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+ *
+ * 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/>.
+ */
+
+/* Linker script for Open-BLDC (STM32F103CBT6, 128K flash, 20K RAM). */
+
+/* Define memory regions. */
+MEMORY
+{
+ rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
+}
+
+/* Include the common ld script from libopenstm32. */
+INCLUDE libopenstm32.ld
+
diff --git a/examples/obldc/usart_irq/Makefile b/examples/obldc/usart_irq/Makefile
new file mode 100644
index 0000000..1c0a6c2
--- /dev/null
+++ b/examples/obldc/usart_irq/Makefile
@@ -0,0 +1,24 @@
+##
+## This file is part of the libopenstm32 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+##
+## 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/>.
+##
+
+BINARY = usart_irq
+
+OOCD_BOARD = open-bldc
+
+include ../../Makefile.include
diff --git a/examples/obldc/usart_irq/usart_irq.c b/examples/obldc/usart_irq/usart_irq.c
new file mode 100644
index 0000000..5be24d2
--- /dev/null
+++ b/examples/obldc/usart_irq/usart_irq.c
@@ -0,0 +1,126 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+ *
+ * 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 <libopenstm32/rcc.h>
+#include <libopenstm32/gpio.h>
+#include <libopenstm32/usart.h>
+#include <libopenstm32/nvic.h>
+
+void clock_setup(void)
+{
+ rcc_clock_setup_in_hse_8mhz_out_72mhz();
+
+ /* Enable GPIOA clock. For LED gpio's */
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+
+ /* Enable clocks for GPIO port B (for GPIO_USART1_TX) and USART1. */
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_USART1EN);
+}
+
+void usart_setup(void)
+{
+
+ /* Enable the USART1 interrupt. */
+ nvic_enable_irq(NVIC_USART1_IRQ);
+
+ /* enable USART1 pin software remapping */
+ AFIO_MAPR |= AFIO_MAPR_USART1_REMAP;
+
+ /* Setup GPIO pin GPIO_USART1_RE_TX on GPIO port B for transmit. */
+ gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART1_RE_TX);
+
+ /* Setup GPIO pin GPIO_USART1_RE_RX on GPIO port B for receive. */
+ gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
+ GPIO_CNF_INPUT_FLOAT, GPIO_USART1_RE_RX);
+
+ /* Setup UART parameters. */
+ usart_set_baudrate(USART1, 230400);
+ usart_set_databits(USART1, 8);
+ usart_set_stopbits(USART1, USART_STOPBITS_1);
+ usart_set_parity(USART1, USART_PARITY_NONE);
+ usart_set_flow_control(USART1, USART_FLOWCONTROL_NONE);
+ usart_set_mode(USART1, USART_MODE_TX_RX);
+
+ /* Enable USART1 Receive interrupt. */
+ USART_CR1(USART1) |= USART_CR1_RXNEIE;
+
+ /* Finally enable the USART. */
+ usart_enable(USART1);
+}
+
+void gpio_setup(void)
+{
+
+ gpio_set(GPIOA, GPIO6 | GPIO7);
+
+ /* Setup GPIO6 and 7 (in GPIO port A) for led use. */
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL,
+ GPIO6 | GPIO7);
+
+}
+
+void usart1_isr(void)
+{
+ static u8 data = 'A';
+
+ /* Check if we were called because of RXNE. */
+ if ((USART_SR(USART1) & USART_SR_RXNE) != 0) {
+
+ /* Indicate that we got data. */
+ gpio_toggle(GPIOA, GPIO6);
+
+ /* Retrieve the data from the peripheral. */
+ data = usart_recv(USART1);
+
+ /* Enable transmit interrupt so it sends back the data. */
+ USART_CR1(USART1) |= USART_CR1_TXEIE;
+ }
+
+ /* Check if we were called because of TXE. */
+ if ((USART_SR(USART1) & USART_SR_TXE) != 0) {
+
+ /* Indicate that we are sending out data. */
+ gpio_toggle(GPIOA, GPIO7);
+
+ /* Put data into the transmit register */
+ usart_send(USART1, data);
+
+ /* Disable the TXE interrupt as we don't need it anymore */
+ USART_CR1(USART1) &= ~USART_CR1_TXEIE;
+ }
+}
+
+int main(void)
+{
+
+ clock_setup();
+ gpio_setup();
+ usart_setup();
+
+ /* Wait forever and do nothing. */
+ while (1) {
+ __asm("nop");
+ }
+
+ return 0;
+}
diff --git a/examples/obldc/usart_irq/usart_irq.ld b/examples/obldc/usart_irq/usart_irq.ld
new file mode 100644
index 0000000..c8683d5
--- /dev/null
+++ b/examples/obldc/usart_irq/usart_irq.ld
@@ -0,0 +1,31 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+ *
+ * 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/>.
+ */
+
+/* Linker script for Open-BLDC (STM32F103CBT6, 128K flash, 20K RAM). */
+
+/* Define memory regions. */
+MEMORY
+{
+ rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
+}
+
+/* Include the common ld script from libopenstm32. */
+INCLUDE libopenstm32.ld
+
diff --git a/examples/other/adc_temperature_sensor/Makefile b/examples/other/adc_temperature_sensor/Makefile
index a708bcb..2b26a1b 100644
--- a/examples/other/adc_temperature_sensor/Makefile
+++ b/examples/other/adc_temperature_sensor/Makefile
@@ -19,77 +19,4 @@
BINARY = adc
-# PREFIX ?= arm-none-eabi
-PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-ld
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-#TOOLCHAIN_DIR = `dirname \`which $(CC)\``/..
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
-OBJS = $(BINARY).o
-
-OPENOCD_BASE = /usr
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/jtagkey.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/target/stm32.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
-
+include ../../Makefile.include
diff --git a/examples/other/dma_mem2mem/Makefile b/examples/other/dma_mem2mem/Makefile
index 085aa60..b92e395 100644
--- a/examples/other/dma_mem2mem/Makefile
+++ b/examples/other/dma_mem2mem/Makefile
@@ -19,77 +19,4 @@
BINARY = dma
-# PREFIX ?= arm-none-eabi
-PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-ld
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-#TOOLCHAIN_DIR = `dirname \`which $(CC)\``/..
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
-OBJS = $(BINARY).o
-
-OPENOCD_BASE = /usr
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/jtagkey.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/target/stm32.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
-
+include ../../Makefile.include
diff --git a/examples/other/dogm128/Makefile b/examples/other/dogm128/Makefile
index 9f33720..158b33b 100644
--- a/examples/other/dogm128/Makefile
+++ b/examples/other/dogm128/Makefile
@@ -19,77 +19,6 @@
BINARY = main
-# PREFIX ?= arm-none-eabi
-PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-ld
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-#TOOLCHAIN_DIR = `dirname \`which $(CC)\``/..
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
-OBJS = $(BINARY).o dogm128.o
-
-OPENOCD_BASE = /usr
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/jtagkey.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/target/stm32.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
+OBJS = dogm128.o
+include ../../Makefile.include
diff --git a/examples/other/i2c_stts75_sensor/Makefile b/examples/other/i2c_stts75_sensor/Makefile
index 6b4fa69..6ca704e 100644
--- a/examples/other/i2c_stts75_sensor/Makefile
+++ b/examples/other/i2c_stts75_sensor/Makefile
@@ -19,77 +19,6 @@
BINARY = i2c_stts75_sensor
-# PREFIX ?= arm-none-eabi
-PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-ld
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-# TOOLCHAIN_DIR = `dirname \`which $(CC)\``/../$(PREFIX)
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
-OBJS = $(BINARY).o stts75.o
-
-OPENOCD_BASE = /usr
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/jtagkey.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/target/stm32.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
+OBJS = stts75.o
+include ../../Makefile.include
diff --git a/examples/other/rtc/Makefile b/examples/other/rtc/Makefile
index 3270192..10fa5af 100644
--- a/examples/other/rtc/Makefile
+++ b/examples/other/rtc/Makefile
@@ -19,77 +19,4 @@
BINARY = rtc
-# PREFIX ?= arm-none-eabi
-PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-ld
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-# TOOLCHAIN_DIR = `dirname \`which $(CC)\``/../$(PREFIX)
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
-OBJS = $(BINARY).o
-
-OPENOCD_BASE = /usr
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/parport.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/board/olimex_stm32_h103.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
-
+include ../../Makefile.include
diff --git a/examples/other/systick/Makefile b/examples/other/systick/Makefile
index 488f3d6..20c889f 100644
--- a/examples/other/systick/Makefile
+++ b/examples/other/systick/Makefile
@@ -19,77 +19,4 @@
BINARY = systick
-# PREFIX ?= arm-none-eabi
-PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-ld
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-#TOOLCHAIN_DIR = `dirname \`which $(CC)\``/..
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
-OBJS = $(BINARY).o
-
-OPENOCD_BASE = /usr
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/jtagkey.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/target/stm32.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
-
+include ../../Makefile.include
diff --git a/examples/other/timer_interrupt/Makefile b/examples/other/timer_interrupt/Makefile
index b01d859..c4cd3b6 100644
--- a/examples/other/timer_interrupt/Makefile
+++ b/examples/other/timer_interrupt/Makefile
@@ -19,77 +19,4 @@
BINARY = timer
-# PREFIX ?= arm-none-eabi
-PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-ld
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-#TOOLCHAIN_DIR = `dirname \`which $(CC)\``/..
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
-OBJS = $(BINARY).o
-
-OPENOCD_BASE = /usr
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/jtagkey.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/target/stm32.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
-
+include ../../Makefile.include
diff --git a/examples/other/usb_cdcacm/Makefile b/examples/other/usb_cdcacm/Makefile
index 9b19ee0..1ca37fc 100644
--- a/examples/other/usb_cdcacm/Makefile
+++ b/examples/other/usb_cdcacm/Makefile
@@ -19,77 +19,4 @@
BINARY = cdcacm
-# PREFIX ?= arm-none-eabi
-PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-gcc
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-#TOOLCHAIN_DIR = `dirname \`which $(CC)\``/..
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
-OBJS = $(BINARY).o
-
-OPENOCD_BASE = /usr
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/jtagkey.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/target/stm32.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
-
+include ../../Makefile.include
diff --git a/examples/other/usb_dfu/Makefile b/examples/other/usb_dfu/Makefile
index 775a991..9b107aa 100644
--- a/examples/other/usb_dfu/Makefile
+++ b/examples/other/usb_dfu/Makefile
@@ -19,77 +19,4 @@
BINARY = usbdfu
-# PREFIX ?= arm-none-eabi
-PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-gcc
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-#TOOLCHAIN_DIR = `dirname \`which $(CC)\``/..
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g3 -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles -Wl,--defsym,_stack=0x20001000
-OBJS = $(BINARY).o
-
-OPENOCD_BASE = /usr
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/jtagkey.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/target/stm32.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
-
+include ../../Makefile.include
diff --git a/examples/other/usb_hid/Makefile b/examples/other/usb_hid/Makefile
index 380d513..378a374 100644
--- a/examples/other/usb_hid/Makefile
+++ b/examples/other/usb_hid/Makefile
@@ -19,77 +19,4 @@
BINARY = usbhid
-# PREFIX ?= arm-none-eabi
-PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-gcc
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-#TOOLCHAIN_DIR = `dirname \`which $(CC)\``/..
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g3 -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb -I../usb_dfu
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles -Wl,--defsym,_stack=0x20001000 -Wl,-Ttext,0x8002000
-OBJS = $(BINARY).o
-
-OPENOCD_BASE = /usr
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/jtagkey.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/target/stm32.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
-
+include ../../Makefile.include
diff --git a/examples/other/usb_hid/README b/examples/other/usb_hid/README
index 3ba2aa6..792e0bd 100644
--- a/examples/other/usb_hid/README
+++ b/examples/other/usb_hid/README
@@ -2,7 +2,7 @@
README
------------------------------------------------------------------------------
-This example implements a USB Human Interface Device (HID)
+This example implements a USB Human Interface Device (HID)
to demonstrate the use of the USB device stack.
Building
@@ -39,5 +39,5 @@ Or you can do the same manually via:
> reset
Replace the "jtagkey-tiny.cfg" with whatever JTAG device you are using, and/or
-replace "stm.cfg" with your respective config file.
+replace "stm32.cfg" with your respective config file.
diff --git a/examples/stm32-h103/fancyblink/Makefile b/examples/stm32-h103/fancyblink/Makefile
index 06d821e..a712cc4 100644
--- a/examples/stm32-h103/fancyblink/Makefile
+++ b/examples/stm32-h103/fancyblink/Makefile
@@ -19,77 +19,4 @@
BINARY = fancyblink
-# PREFIX ?= arm-none-eabi
-PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-ld
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-# TOOLCHAIN_DIR = `dirname \`which $(CC)\``/../$(PREFIX)
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
-OBJS = $(BINARY).o
-
-OPENOCD_BASE = /usr
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/parport.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/board/olimex_stm32_h103.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
-
+include ../../Makefile.include
diff --git a/examples/stm32-h103/miniblink/Makefile b/examples/stm32-h103/miniblink/Makefile
index fa729ae..37c70fd 100644
--- a/examples/stm32-h103/miniblink/Makefile
+++ b/examples/stm32-h103/miniblink/Makefile
@@ -19,77 +19,4 @@
BINARY = miniblink
-# PREFIX ?= arm-none-eabi
-PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-ld
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-# TOOLCHAIN_DIR = `dirname \`which $(CC)\``/../$(PREFIX)
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
-OBJS = $(BINARY).o
-
-OPENOCD_BASE = /usr
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/parport.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/board/olimex_stm32_h103.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
-
+include ../../Makefile.include
diff --git a/examples/stm32-h103/spi/Makefile b/examples/stm32-h103/spi/Makefile
index 080ebfc..1e22919 100644
--- a/examples/stm32-h103/spi/Makefile
+++ b/examples/stm32-h103/spi/Makefile
@@ -19,77 +19,4 @@
BINARY = spi
-# PREFIX ?= arm-none-eabi
-PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-ld
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-# TOOLCHAIN_DIR = `dirname \`which $(CC)\``/../$(PREFIX)
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
-OBJS = $(BINARY).o
-
-OPENOCD_BASE = /usr
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/parport.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/board/olimex_stm32_h103.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
-
+include ../../Makefile.include
diff --git a/examples/stm32-h103/usart/Makefile b/examples/stm32-h103/usart/Makefile
index 193be89..6484117 100644
--- a/examples/stm32-h103/usart/Makefile
+++ b/examples/stm32-h103/usart/Makefile
@@ -19,77 +19,4 @@
BINARY = usart
-# PREFIX ?= arm-none-eabi
-PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-ld
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-# TOOLCHAIN_DIR = `dirname \`which $(CC)\``/../$(PREFIX)
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
-OBJS = $(BINARY).o
-
-OPENOCD_BASE = /usr
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/parport.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/board/olimex_stm32_h103.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
-
+include ../../Makefile.include
diff --git a/examples/stm32-h103/usart/usart.c b/examples/stm32-h103/usart/usart.c
index d8ffe3d..4470348 100644
--- a/examples/stm32-h103/usart/usart.c
+++ b/examples/stm32-h103/usart/usart.c
@@ -69,11 +69,11 @@ int main(void)
/* Blink the LED (PC12) on the board with every transmitted byte. */
while (1) {
gpio_toggle(GPIOC, GPIO12); /* LED on/off */
- usart_send(USART3, c + '0'); /* Send one byte on USART3. */
+ usart_send_blocking(USART3, c + '0'); /* Send one byte on USART3. */
c = (c == 9) ? 0 : c + 1; /* Increment c. */
if ((j++ % 80) == 0) { /* Newline after line full. */
- usart_send(USART3, '\r');
- usart_send(USART3, '\n');
+ usart_send_blocking(USART3, '\r');
+ usart_send_blocking(USART3, '\n');
}
for (i = 0; i < 80000; i++); /* Wait (needs -O0 CFLAGS). */
}
diff --git a/examples/stm32-h103/usb_cdcacm/Makefile b/examples/stm32-h103/usb_cdcacm/Makefile
index 531bb96..1ca37fc 100644
--- a/examples/stm32-h103/usb_cdcacm/Makefile
+++ b/examples/stm32-h103/usb_cdcacm/Makefile
@@ -19,80 +19,4 @@
BINARY = cdcacm
-PREFIX=/opt/paparazzi/stm32/bin/arm-none-eabi
-# PREFIX ?= arm-none-eabi
-#PREFIX ?= arm-elf
-CC = $(PREFIX)-gcc
-LD = $(PREFIX)-gcc
-OBJCOPY = $(PREFIX)-objcopy
-OBJDUMP = $(PREFIX)-objdump
-# Uncomment this line if you want to use the installed (not local) library.
-#TOOLCHAIN_DIR = `dirname \`which $(CC)\``/..
-TOOLCHAIN_DIR = ../../..
-CFLAGS = -O0 -g -Wall -Wextra -I$(TOOLCHAIN_DIR)/include -fno-common \
- -mcpu=cortex-m3 -mthumb
-LDSCRIPT = $(BINARY).ld
-LDFLAGS = -L$(TOOLCHAIN_DIR)/lib -T$(LDSCRIPT) -nostartfiles
-OBJS = $(BINARY).o
-
-#OPENOCD_BASE = /usr
-OPENOCD_BASE = /opt/paparazzi/stm32
-OPENOCD = $(OPENOCD_BASE)/bin/openocd
-OPENOCD_SCRIPTS = $(OPENOCD_BASE)/share/openocd/scripts
-#OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/openocd-usb.cfg
-OPENOCD_FLASHER = $(OPENOCD_SCRIPTS)/interface/jtagkey-tiny.cfg
-OPENOCD_BOARD = $(OPENOCD_SCRIPTS)/board/olimex_stm32_h103.cfg
-
-# Be silent per default, but 'make V=1' will show all compiler calls.
-ifneq ($(V),1)
-Q := @
-NULL := 2>/dev/null
-endif
-
-all: images
-
-images: $(BINARY)
- @printf " OBJCOPY $(BINARY).bin\n"
- $(Q)$(OBJCOPY) -Obinary $(BINARY) $(BINARY).bin
- @printf " OBJCOPY $(BINARY).hex\n"
- $(Q)$(OBJCOPY) -Oihex $(BINARY) $(BINARY).hex
- @printf " OBJCOPY $(BINARY).srec\n"
- $(Q)$(OBJCOPY) -Osrec $(BINARY) $(BINARY).srec
- @printf " OBJDUMP $(BINARY).list\n"
- $(Q)$(OBJDUMP) -S $(BINARY) > $(BINARY).list
-
-$(BINARY): $(OBJS) $(LDSCRIPT)
- @printf " LD $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(LD) $(LDFLAGS) -o $(BINARY) $(OBJS) -lopenstm32
-
-%.o: %.c Makefile
- @printf " CC $(subst $(shell pwd)/,,$(@))\n"
- $(Q)$(CC) $(CFLAGS) -o $@ -c $<
-
-clean:
- @printf " CLEAN $(subst $(shell pwd)/,,$(OBJS))\n"
- $(Q)rm -f *.o
- @printf " CLEAN $(BINARY)\n"
- $(Q)rm -f $(BINARY)
- @printf " CLEAN $(BINARY).bin\n"
- $(Q)rm -f $(BINARY).bin
- @printf " CLEAN $(BINARY).hex\n"
- $(Q)rm -f $(BINARY).hex
- @printf " CLEAN $(BINARY).srec\n"
- $(Q)rm -f $(BINARY).srec
- @printf " CLEAN $(BINARY).list\n"
- $(Q)rm -f $(BINARY).list
-
-flash: images
- @printf " FLASH $(BINARY).bin\n"
- @# IMPORTANT: Don't use "resume", only "reset" will work correctly!
- $(Q)$(OPENOCD) -s $(OPENOCD_SCRIPTS) \
- -f $(OPENOCD_FLASHER) \
- -f $(OPENOCD_BOARD) \
- -c "init" -c "reset halt" \
- -c "flash write_image erase $(BINARY).hex" \
- -c "reset" \
- -c "shutdown" $(NULL)
-
-.PHONY: images clean
-
+include ../../Makefile.include
diff --git a/include/libopenstm32.h b/include/libopenstm32.h
index 4dbde73..2893cb5 100644
--- a/include/libopenstm32.h
+++ b/include/libopenstm32.h
@@ -32,6 +32,7 @@
#include <libopenstm32/flash.h>
#include <libopenstm32/usb.h>
#include <libopenstm32/usb_desc.h>
+#include <libopenstm32/can.h>
#include <libopenstm32/nvic.h>
#include <libopenstm32/rtc.h>
#include <libopenstm32/i2c.h>
diff --git a/include/libopenstm32/can.h b/include/libopenstm32/can.h
new file mode 100644
index 0000000..e00574b
--- /dev/null
+++ b/include/libopenstm32/can.h
@@ -0,0 +1,642 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
+ *
+ * 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/>.
+ */
+
+#ifndef LIBOPENSTM32_CAN_H
+#define LIBOPENSTM32_CAN_H
+
+#include <libopenstm32/memorymap.h>
+#include <libopenstm32/common.h>
+
+/* --- Convenience macros -------------------------------------------------- */
+
+/* CAN register base adresses (for convenience) */
+#define CAN1 BX_CAN1_BASE
+#define CAN2 BX_CAN2_BASE
+
+/* --- CAN registers ------------------------------------------------------- */
+
+/* CAN master control register (CAN_MCR) */
+#define CAN_MCR(can_base) MMIO32(can_base + 0x000)
+/* CAN master status register (CAN_MSR) */
+#define CAN_MSR(can_base) MMIO32(can_base + 0x004)
+/* CAN transmit status register (CAN_TSR) */
+#define CAN_TSR(can_base) MMIO32(can_base + 0x008)
+
+/* CAN receive FIFO 0 register (CAN_RF0R) */
+#define CAN_RF0R(can_base) MMIO32(can_base + 0x00C)
+/* CAN receive FIFO 1 register (CAN_RF1R) */
+#define CAN_RF1R(can_base) MMIO32(can_base + 0x010)
+
+/* CAN interrupt enable register (CAN_IER) */
+#define CAN_IER(can_base) MMIO32(can_base + 0x014)
+/* CAN error status register (CAN_ESR) */
+#define CAN_ESR(can_base) MMIO32(can_base + 0x018)
+/* CAN bit timing register (CAN_BTR) */
+#define CAN_BTR(can_base) MMIO32(can_base + 0x01C)
+
+/* Registers in the offset range 0x020 to 0x17F are reserved. */
+
+/* --- CAN mailbox registers ----------------------------------------------- */
+
+/* CAN mailbox / FIFO register offsets */
+#define CAN_MBOX0 0x180
+#define CAN_MBOX1 0x190
+#define CAN_MBOX2 0x1A0
+#define CAN_FIFO0 0x1B0
+#define CAN_FIFO1 0x1C0
+
+/* CAN TX mailbox identifier register (CAN_TIxR) */
+#define CAN_TIxR(can_base, mbox) MMIO32(can_base + mbox + 0x0)
+#define CAN_TI0R(can_base) CAN_TIxR(can_base, CAN_MBOX0)
+#define CAN_TI1R(can_base) CAN_TIxR(can_base, CAN_MBOX1)
+#define CAN_TI2R(can_base) CAN_TIxR(can_base, CAN_MBOX2)
+
+/* CAN mailbox data length control and time stamp register (CAN_TDTxR) */
+#define CAN_TDTxR(can_base, mbox) MMIO32(can_base + mbox + 0x4)
+#define CAN_TDT0R(can_base) CAN_TDTxR(can_base, CAN_MBOX0)
+#define CAN_TDT1R(can_base) CAN_TDTxR(can_base, CAN_MBOX1)
+#define CAN_TDT2R(can_base) CAN_TDTxR(can_base, CAN_MBOX2)
+
+/* CAN mailbox data low register (CAN_TDLxR) */
+#define CAN_TDLxR(can_base, mbox) MMIO32(can_base + mbox + 0x8)
+#define CAN_TDL0R(can_base) CAN_TDLxR(can_base, CAN_MBOX0)
+#define CAN_TDL1R(can_base) CAN_TDLxR(can_base, CAN_MBOX1)
+#define CAN_TDL2R(can_base) CAN_TDLxR(can_base, CAN_MBOX2)
+
+/* CAN mailbox data high register (CAN_TDHxR) */
+#define CAN_TDHxR(can_base, mbox) MMIO32(can_base + mbox + 0xC)
+#define CAN_TDH0R(can_base) CAN_TDHxR(can_base, CAN_MBOX0)
+#define CAN_TDH1R(can_base) CAN_TDHxR(can_base, CAN_MBOX1)
+#define CAN_TDH2R(can_base) CAN_TDHxR(can_base, CAN_MBOX2)
+
+/* CAN RX FIFO identifier register (CAN_RIxR) */
+#define CAN_RIxR(can_base, fifo) MMIO32(can_base + fifo + 0x0)
+#define CAN_RI0R(can_base) CAN_RIxR(can_base, CAN_FIFO0)
+#define CAN_RI1R(can_base) CAN_RIxR(can_base, CAN_FIFO1)
+
+/* CAN RX FIFO mailbox data length control & time stamp register (CAN_RDTxR) */
+#define CAN_RDTxR(can_base, fifo) MMIO32(can_base + fifo + 0x4)
+#define CAN_RDT0R(can_base) CAN_RDTxR(can_base, CAN_FIFO0)
+#define CAN_RDT1R(can_base) CAN_RDTxR(can_base, CAN_FIFO1)
+
+/* CAN RX FIFO mailbox data low register (CAN_RDLxR) */
+#define CAN_RDLxR(can_base, fifo) MMIO32(can_base + fifo + 0x8)
+#define CAN_RDL0R(can_base) CAN_RDLxR(can_base, CAN_FIFO0)
+#define CAN_RDL1R(can_base) CAN_RDLxR(can_base, CAN_FIFO1)
+
+/* CAN RX FIFO mailbox data high register (CAN_RDHxR) */
+#define CAN_RDHxR(can_base, fifo) MMIO32(can_base + fifo + 0xC)
+#define CAN_RDH0R(can_base) CAN_RDHxR(can_base, CAN_FIFO0)
+#define CAN_RDH1R(can_base) CAN_RDHxR(can_base, CAN_FIFO1)
+
+/* --- CAN filter registers ------------------------------------------------ */
+
+/* CAN filter master register (CAN_FMR) */
+#define CAN_FMR(can_base) MMIO32(can_base + 0x200)
+
+/* CAN filter mode register (CAN_FM1R) */
+#define CAN_FM1R(can_base) MMIO32(can_base + 0x204)
+
+/* Register offset 0x208 is reserved. */
+
+/* CAN filter scale register (CAN_FS1R) */
+#define CAN_FS1R(can_base) MMIO32(can_base + 0x20C)
+
+/* Register offset 0x210 is reserved. */
+
+/* CAN filter FIFO assignement register (CAN_FFA1R) */
+#define CAN_FFA1R(can_base) MMIO32(can_base + 0x214)
+
+/* Register offset 0x218 is reserved. */
+
+/* CAN filter activation register (CAN_FA1R) */
+#define CAN_FA1R(can_base) MMIO32(can_base + 0x21C)
+
+/* Register offset 0x220 is reserved. */
+
+/* Registers with offset 0x224 to 0x23F are reserved. */
+
+/* CAN filter bank registers (CAN_FiRx) */
+/*
+ * Connectivity line devices have 28 banks so the bank ID spans 0..27
+ * all other devices have 14 banks so the bank ID spans 0..13.
+ */
+#define CAN_FiR1(can_base, bank) MMIO32(can_base + 0x240 + (bank * 0x8) + 0x0)
+#define CAN_FiR2(can_base, bank) MMIO32(can_base + 0x240 + (bank * 0x8) + 0x4)
+
+/* --- CAN_MCR values ------------------------------------------------------ */
+
+/* 31:17 Reserved, forced by hardware to 0 */
+
+/* DBF: Debug freeze */
+#define CAN_MCR_DBF (1 << 16)
+
+/* RESET: bxCAN software master reset */
+#define CAN_MCR_RESET (1 << 15)
+
+/* 14:8 Reserved, forced by hardware to 0 */
+
+/* TTCM: Time triggered communication mode */
+#define CAN_MCR_TTCM (1 << 7)
+
+/* ABOM: Automatic bus-off management */
+#define CAN_MCR_ABOM (1 << 6)
+
+/* AWUM: Automatic wakeup mode */
+#define CAN_MCR_AWUM (1 << 5)
+
+/* NART: No automatic retransmission */
+#define CAN_MCR_NART (1 << 4)
+
+/* RFLM: Receive FIFO locked mode */
+#define CAN_MCR_RFLM (1 << 3)
+
+/* TXFP: Transmit FIFO priority */
+#define CAN_MCR_TXFP (1 << 2)
+
+/* SLEEP: Sleep mode request */
+#define CAN_MCR_SLEEP (1 << 1)
+
+/* INRQ: Initialization request */
+#define CAN_MCR_INRQ (1 << 0)
+
+/* --- CAN_MSR values ------------------------------------------------------ */
+
+/* 31:12 Reserved, forced by hardware to 0 */
+
+/* RX: CAN Rx signal */
+#define CAN_MSR_RX (1 << 11)
+
+/* SAMP: Last sample point */
+#define CAN_MSR_SAMP (1 << 10)
+
+/* RXM: Receive mode */
+#define CAN_MSR_RXM (1 << 9)
+
+/* TXM: Transmit mode */
+#define CAN_MSR_TXM (1 << 8)
+
+/* 7:5 Reserved, forced by hardware to 0 */
+
+/* SLAKI: Sleep acknowledge interrupt */
+#define CAN_MSR_SLAKI (1 << 4)
+
+/* WKUI: Wakeup interrupt */
+#define CAN_MSR_WKUI (1 << 3)
+
+/* ERRI: Error interrupt */
+#define CAN_MSR_ERRI (1 << 2)
+
+/* SLAK: Sleep acknowledge */
+#define CAN_MSR_SLAK (1 << 1)
+
+/* INAK: Initialization acknowledge */
+#define CAN_MSR_INAK (1 << 0)
+
+/* --- CAN_TSR values ------------------------------------------------------ */
+
+/* LOW2: Lowest priority flag for mailbox 2 */
+#define CAN_TSR_LOW2 (1 << 31)
+
+/* LOW1: Lowest priority flag for mailbox 1 */
+#define CAN_TSR_LOW1 (1 << 30)
+
+/* LOW0: Lowest priority flag for mailbox 0 */
+#define CAN_TSR_LOW0 (1 << 29)
+
+/* TME2: Transmit mailbox 2 empty */
+#define CAN_TSR_TME2 (1 << 28)
+
+/* TME1: Transmit mailbox 1 empty */
+#define CAN_TSR_TME1 (1 << 27)
+
+/* TME0: Transmit mailbox 0 empty */
+#define CAN_TSR_TME0 (1 << 26)
+
+/* CODE[1:0]: Mailbox code */
+#define CAN_TSR_CODE_MASK (0x3 << 24)
+
+/* ABRQ2: Abort request for mailbox 2 */
+#define CAN_TSR_TABRQ2 (1 << 23)
+
+/* 22:20 Reserved, forced by hardware to 0 */
+
+/* TERR2: Transmission error for mailbox 2 */
+#define CAN_TSR_TERR2 (1 << 19)
+
+/* ALST2: Arbitration lost for mailbox 2 */
+#define CAN_TSR_ALST2 (1 << 18)
+
+/* TXOK2: Transmission OK for mailbox 2 */
+#define CAN_TSR_TXOK2 (1 << 17)
+
+/* RQCP2: Request completed mailbox 2 */
+#define CAN_TSR_RQCP2 (1 << 16)
+
+/* ABRQ1: Abort request for mailbox 1 */
+#define CAN_TSR_ABRQ1 (1 << 15)
+
+/* 14:12 Reserved, forced by hardware to 0 */
+
+/* TERR1: Transmission error for mailbox 1 */
+#define CAN_TSR_TERR1 (1 << 11)
+
+/* ALST1: Arbitration lost for mailbox 1 */
+#define CAN_TSR_ALST1 (1 << 10)
+
+/* TXOK1: Transmission OK for mailbox 1 */
+#define CAN_TSR_TXOK1 (1 << 9)
+
+/* RQCP1: Request completed mailbox 1 */
+#define CAN_TSR_RQCP1 (1 << 8)
+
+/* ABRQ0: Abort request for mailbox 0 */
+#define CAN_TSR_ABRQ0 (1 << 7)
+
+/* 6:4 Reserved, forced by hardware to 0 */
+
+/* TERR0: Transmission error for mailbox 0 */
+#define CAN_TSR_TERR0 (1 << 3)
+
+/* ALST0: Arbitration lost for mailbox 0 */
+#define CAN_TSR_ALST0 (1 << 2)
+
+/* TXOK0: Transmission OK for mailbox 0 */
+#define CAN_TSR_TXOK0 (1 << 1)
+
+/* RQCP0: Request completed mailbox 0 */
+#define CAN_TSR_RQCP0 (1 << 0)
+
+/* --- CAN_RF0R values ----------------------------------------------------- */
+
+/* 31:6 Reserved, forced by hardware to 0 */
+
+/* RFOM0: Release FIFO 0 output mailbox */
+#define CAN_RF0R_RFOM0 (1 << 5)
+
+/* FOVR0: FIFO 0 overrun */
+#define CAN_RF0R_FAVR0 (1 << 4)
+
+/* FULL0: FIFO 0 full */
+#define CAN_RF0R_FULL0 (1 << 3)
+
+/* 2 Reserved, forced by hardware to 0 */
+
+/* FMP0[1:0]: FIFO 0 message pending */
+#define CAN_RF0R_FMP0_MASK (0x3 << 0)
+
+/* --- CAN_RF1R values ----------------------------------------------------- */
+
+/* 31:6 Reserved, forced by hardware to 0 */
+
+/* RFOM1: Release FIFO 1 output mailbox */
+#define CAN_RF1R_RFOM1 (1 << 5)
+
+/* FOVR1: FIFO 1 overrun */
+#define CAN_RF1R_FAVR1 (1 << 4)
+
+/* FULL1: FIFO 1 full */
+#define CAN_RF1R_FULL1 (1 << 3)
+
+/* 2 Reserved, forced by hardware to 0 */
+
+/* FMP1[1:0]: FIFO 1 message pending */
+#define CAN_RF1R_FMP1_MASK (0x3 << 0)
+
+/* --- CAN_IER values ------------------------------------------------------ */
+
+/* 32:18 Reserved, forced by hardware to 0 */
+
+/* SLKIE: Sleep interrupt enable */
+#define CAN_IER_SLKIE (1 << 17)
+
+/* WKUIE: Wakeup interrupt enable */
+#define CAN_IER_WKUIE (1 << 16)
+
+/* ERRIE: Error interrupt enable */
+#define CAN_IER_ERRIE (1 << 15)
+
+/* 14:12 Reserved, forced by hardware to 0 */
+
+/* LECIE: Last error code interrupt enable */
+#define CAN_IER_LECIE (1 << 11)
+
+/* BOFIE: Bus-off interrupt enable */
+#define CAN_IER_BOFIE (1 << 10)
+
+/* EPVIE: Error passive interrupt enable */
+#define CAN_IER_EPVIE (1 << 9)
+
+/* EWGIE: Error warning interrupt enable */
+#define CAN_IER_EWGIE (1 << 8)
+
+/* 7 Reserved, forced by hardware to 0 */
+
+/* FOVIE1: FIFO overrun interrupt enable */
+#define CAN_IER_FOVIE1 (1 << 6)
+
+/* FFIE1: FIFO full interrupt enable */
+#define CAN_IER_FFIE1 (1 << 5)
+
+/* FMPIE1: FIFO message pending interrupt enable */
+#define CAN_IER_FMPIE1 (1 << 4)
+
+/* FOVIE0: FIFO overrun interrupt enable */
+#define CAN_IER_FOVIE0 (1 << 3)
+
+/* FFIE0: FIFO full interrupt enable */
+#define CAN_IER_FFIE0 (1 << 2)
+
+/* FMPIE0: FIFO message pending interrupt enable */
+#define CAN_IER_FMPIE0 (1 << 1)
+
+/* TMEIE: Transmit mailbox empty interrupt enable */
+#define CAN_IER_TMEIE (1 << 0)
+
+/* --- CAN_ESR values ------------------------------------------------------ */
+
+/* REC[7:0]: Receive error counter */
+#define CAN_ESR_REC_MASK (0xF << 24)
+
+/* TEC[7:0]: Least significant byte of the 9-bit transmit error counter */
+#define CAN_ESR_TEC_MASK (0xF << 16)
+
+/* 15:7 Reserved, forced by hardware to 0 */
+
+/* LEC[2:0]: Last error code */
+#define CAN_ESR_LEC_NO_ERROR (0x0 << 4)
+#define CAN_ESR_LEC_STUFF_ERROR (0x1 << 4)
+#define CAN_ESR_LEC_FORM_ERROR (0x2 << 4)
+#define CAN_ESR_LEC_ACK_ERROR (0x3 << 4)
+#define CAN_ESR_LEC_REC_ERROR (0x4 << 4)
+#define CAN_ESR_LEC_DOM_ERROR (0x5 << 4)
+#define CAN_ESR_LEC_CRC_ERROR (0x6 << 4)
+#define CAN_ESR_LEC_SOFT_ERROR (0x7 << 4)
+#define CAN_ESR_LEC_MASK (0x7 << 4)
+
+/* 3 Reserved, forced by hardware to 0 */
+
+/* BOFF: Bus-off flag */
+#define CAN_ESR_BOFF (1 << 2)
+
+/* EPVF: Error passive flag */
+#define CAN_ESR_EPVF (1 << 1)
+
+/* EWGF: Error warning flag */
+#define CAN_ESR_EWGF (1 << 0)
+
+/* --- CAN_BTR values ------------------------------------------------------ */
+
+/* SILM: Silent mode (debug) */
+#define CAN_BTR_SILM (1 << 31)
+
+/* LBKM: Loop back mode (debug) */
+#define CAN_BTR_LBKM (1 << 30)
+
+/* 29:26 Reserved, forced by hardware to 0 */
+
+/* SJW[1:0]: Resynchronization jump width */
+#define CAN_BTR_SJW_1TQ (0x0 << 24)
+#define CAN_BTR_SJW_2TQ (0x1 << 24)
+#define CAN_BTR_SJW_3TQ (0x2 << 24)
+#define CAN_BTR_SJW_4TQ (0x3 << 24)
+#define CAN_BTR_SJW_MASK (0x3 << 24)
+
+/* 23 Reserved, forced by hardware to 0 */
+
+/* TS2[2:0]: Time segment 2 */
+#define CAN_BTR_TS2_1TQ (0x0 << 20)
+#define CAN_BTR_TS2_2TQ (0x1 << 20)
+#define CAN_BTR_TS2_3TQ (0x2 << 20)
+#define CAN_BTR_TS2_4TQ (0x3 << 20)
+#define CAN_BTR_TS2_5TQ (0x4 << 20)
+#define CAN_BTR_TS2_6TQ (0x5 << 20)
+#define CAN_BTR_TS2_7TQ (0x6 << 20)
+#define CAN_BTR_TS2_8TQ (0x7 << 20)
+#define CAN_BTR_TS2_MASK (0x7 << 20)
+
+/* TS1[3:0]: Time segment 1 */
+#define CAN_BTR_TS1_1TQ (0x0 << 16)
+#define CAN_BTR_TS1_2TQ (0x1 << 16)
+#define CAN_BTR_TS1_3TQ (0x2 << 16)
+#define CAN_BTR_TS1_4TQ (0x3 << 16)
+#define CAN_BTR_TS1_5TQ (0x4 << 16)
+#define CAN_BTR_TS1_6TQ (0x5 << 16)
+#define CAN_BTR_TS1_7TQ (0x6 << 16)
+#define CAN_BTR_TS1_8TQ (0x7 << 16)
+#define CAN_BTR_TS1_9TQ (0x8 << 16)
+#define CAN_BTR_TS1_10TQ (0x9 << 16)
+#define CAN_BTR_TS1_11TQ (0xA << 16)
+#define CAN_BTR_TS1_12TQ (0xB << 16)
+#define CAN_BTR_TS1_13TQ (0xC << 16)
+#define CAN_BTR_TS1_14TQ (0xD << 16)
+#define CAN_BTR_TS1_15TQ (0xE << 16)
+#define CAN_BTR_TS1_16TQ (0xF << 16)
+#define CAN_BTR_TS1_MASK (0xF << 16)
+
+/* 15:10 Reserved, forced by hardware to 0 */
+
+/* BRP[9:0]: Baud rate prescaler */
+#define CAN_BTR_BRP_MASK (0x1FF << 0)
+
+/* --- CAN_TIxR values ------------------------------------------------------ */
+
+/* STID[10:0]: Standard identifier */
+#define CAN_TIxR_STID_MASK (0x3FF << 21)
+#define CAN_TIxR_STID_SHIFT 21
+
+/* EXID[15:0]: Extended identifier */
+#define CAN_TIxR_EXID_MASK (0x1FFFFFF << 3)
+#define CAN_TIxR_EXID_SHIFT 3
+
+/* IDE: Identifier extension */
+#define CAN_TIxR_IDE (1 << 2)
+
+/* RTR: Remote transmission request */
+#define CAN_TIxR_RTR (1 << 1)
+
+/* TXRQ: Transmit mailbox request */
+#define CAN_TIxR_TXRQ (1 << 0)
+
+/* --- CAN_TDTxR values ----------------------------------------------------- */
+
+/* TIME[15:0]: Message time stamp */
+#define CAN_TDTxR_TIME_MASK (0xFFFF << 15)
+#define CAN_TDTxR_TIME_SHIFT 15
+
+/* 15:6 Reserved, forced by hardware to 0 */
+
+/* TGT: Transmit global time */
+#define CAN_TDTxR_TGT (1 << 5)
+
+/* 7:4 Reserved, forced by hardware to 0 */
+
+/* DLC[3:0]: Data length code */
+#define CAN_TDTxR_DLC_MASK (0xF << 0)
+#define CAN_TDTxR_DLC_SHIFT 0
+
+/* --- CAN_TDLxR values ----------------------------------------------------- */
+
+/* DATA3[7:0]: Data byte 3 */
+/* DATA2[7:0]: Data byte 2 */
+/* DATA1[7:0]: Data byte 1 */
+/* DATA0[7:0]: Data byte 0 */
+
+/* --- CAN_TDHxR values ----------------------------------------------------- */
+
+/* DATA7[7:0]: Data byte 7 */
+/* DATA6[7:0]: Data byte 6 */
+/* DATA5[7:0]: Data byte 5 */
+/* DATA4[7:0]: Data byte 4 */
+
+/* --- CAN_RIxR values ------------------------------------------------------ */
+
+/* STID[10:0]: Standard identifier */
+#define CAN_RIxR_STID_MASK (0x3FF << 21)
+#define CAN_RIxR_STID_SHIFT 21
+
+/* EXID[15:0]: Extended identifier */
+#define CAN_RIxR_EXID_MASK (0x1FFFFFF << 3)
+#define CAN_RIxR_EXID_SHIFT 3
+
+/* IDE: Identifier extension */
+#define CAN_RIxR_IDE (1 << 2)
+
+/* RTR: Remote transmission request */
+#define CAN_RIxR_RTR (1 << 1)
+
+/* 0 Reserved */
+
+/* --- CAN_RDTxR values ----------------------------------------------------- */
+
+/* TIME[15:0]: Message time stamp */
+#define CAN_RDTxR_TIME_MASK (0xFFFF << 15)
+#define CAN_RDTxR_TIME_SHIFT 15
+
+/* FMI[7:0]: Filter match index */
+#define CAN_RDTxR_FMI_MASK (0xFF << 8)
+#define CAN_RDTxR_FMI_SHIFT 8
+
+/* 7:4 Reserved, forced by hardware to 0 */
+
+/* DLC[3:0]: Data length code */
+#define CAN_RDTxR_DLC_MASK (0xF << 0)
+#define CAN_RDTxR_DLC_SHIFT 0
+
+/* --- CAN_RDLxR values ----------------------------------------------------- */
+
+/* DATA3[7:0]: Data byte 3 */
+/* DATA2[7:0]: Data byte 2 */
+/* DATA1[7:0]: Data byte 1 */
+/* DATA0[7:0]: Data byte 0 */
+
+/* --- CAN_RDHxR values ----------------------------------------------------- */
+
+/* DATA7[7:0]: Data byte 7 */
+/* DATA6[7:0]: Data byte 6 */
+/* DATA5[7:0]: Data byte 5 */
+/* DATA4[7:0]: Data byte 4 */
+
+/* --- CAN_FMR values ------------------------------------------------------- */
+
+/* 31:14 Reserved, forced to reset value */
+
+/*
+ * CAN2SB[5:0]: CAN2 start bank
+ * (only on connectivity line devices otherwise reserved)
+ */
+#define CAN_FMR_CAN2SB_MASK (0x3F << 8)
+#define CAN_FMR_CAN2SB_SHIFT 15
+
+/* 7:1 Reserved, forced to reset value */
+
+/* FINIT: Filter init mode */
+#define CAN_FMR_FINIT (1 << 0)
+
+/* --- CAN_FM1R values ------------------------------------------------------ */
+
+/* 31:28 Reserved, forced by hardware to 0 */
+
+/*
+ * FBMx: Filter mode
+ * x is 0..27 should be calculated by a helper function making so many macros
+ * seems like an overkill?
+ */
+
+/* --- CAN_FS1R values ------------------------------------------------------ */
+
+/* 31:28 Reserved, forced by hardware to 0 */
+
+/*
+ * FSCx: Filter scale configuration
+ * x is 0..27 should be calculated by a helper function making so many macros
+ * seems like an overkill?
+ */
+
+/* --- CAN_FFA1R values ----------------------------------------------------- */
+
+/* 31:28 Reserved, forced by hardware to 0 */
+
+/*
+ * FFAx: Filter scale configuration
+ * x is 0..27 should be calculated by a helper function making so many macros
+ * seems like an overkill?
+ */
+
+/* --- CAN_FA1R values ------------------------------------------------------ */
+
+/* 31:28 Reserved, forced by hardware to 0 */
+
+/*
+ * FACTx: Filter active
+ * x is 0..27 should be calculated by a helper function making so many macros
+ * seems like an overkill?
+ */
+
+/* --- CAN_FiRx values ------------------------------------------------------ */
+
+/* FB[31:0]: Filter bits */
+
+/* --- CAN functions -------------------------------------------------------- */
+
+void can_reset(u32 canport);
+int can_init(u32 canport, bool ttcm, bool abom, bool awum, bool nart,
+ bool rflm, bool txfp, u32 sjw, u32 ts1, u32 ts2, u32 brp);
+
+void can_filter_init(u32 canport, u32 nr, bool scale_32bit, bool id_list_mode,
+ u32 fr1, u32 fr2, u32 fifo, bool enable);
+void can_filter_id_mask_16bit_init(u32 canport, u32 nr, u16 id1, u16 mask1,
+ u16 id2, u16 mask2, u32 fifo, bool enable);
+void can_filter_id_mask_32bit_init(u32 canport, u32 nr, u32 id, u32 mask,
+ u32 fifo, bool enable);
+void can_filter_id_list_16bit_init(u32 canport, u32 nr, u16 id1, u16 id2,
+ u16 id3, u16 id4, u32 fifo, bool enable);
+void can_filter_id_list_32bit_init(u32 canport, u32 nr, u32 id1, u32 id2,
+ u32 fifo, bool enable);
+
+void can_enable_irq(u32 canport, u32 irq);
+void can_disable_irq(u32 canport, u32 irq);
+
+int can_transmit(u32 canport, u32 id, bool ext, bool rtr, u8 length, u8 *data);
+void can_receive(u32 canport, u8 fifo, bool release, u32 *id, bool *ext,
+ bool *rtr, u32 *fmi, u8 *length, u8 *data);
+
+void can_fifo_release(u32 canport, u8 fifo);
+
+#endif
diff --git a/include/libopenstm32/common.h b/include/libopenstm32/common.h
index fc06dd9..81b2f52 100644
--- a/include/libopenstm32/common.h
+++ b/include/libopenstm32/common.h
@@ -21,6 +21,7 @@
#define LIBOPENSTM32_COMMON_H
#include <stdint.h>
+#include <stdbool.h>
/* Type definitions for shorter and nicer code */
typedef int8_t s8;
diff --git a/include/libopenstm32/ethernet.h b/include/libopenstm32/ethernet.h
new file mode 100644
index 0000000..f611ce5
--- /dev/null
+++ b/include/libopenstm32/ethernet.h
@@ -0,0 +1,203 @@
+/*
+ * This file is part of the libopenstm32 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/>.
+ */
+
+#ifndef LIBOPENSTM32_ETHERNET_H
+#define LIBOPENSTM32_ETHERNET_H
+
+#include <libopenstm32/memorymap.h>
+#include <libopenstm32/common.h>
+
+/* Ethernet MAC registers */
+#define ETH_MACCR MMIO32(ETHERNET_BASE + 0x00)
+#define ETH_MACFFR MMIO32(ETHERNET_BASE + 0x04)
+#define ETH_MACHTHR MMIO32(ETHERNET_BASE + 0x08)
+#define ETH_MACHTLR MMIO32(ETHERNET_BASE + 0x0C)
+#define ETH_MACMIIAR MMIO32(ETHERNET_BASE + 0x10)
+#define ETH_MACMIIDR MMIO32(ETHERNET_BASE + 0x14)
+#define ETH_MACFCR MMIO32(ETHERNET_BASE + 0x18)
+#define ETH_MACVLANTR MMIO32(ETHERNET_BASE + 0x1C)
+#define ETH_MACRWUFFR MMIO32(ETHERNET_BASE + 0x28)
+#define ETH_MACPMTCSR MMIO32(ETHERNET_BASE + 0x2C)
+#define ETH_MACSR MMIO32(ETHERNET_BASE + 0x38)
+#define ETH_MACIMR MMIO32(ETHERNET_BASE + 0x3C)
+#define ETH_MACA0HR MMIO32(ETHERNET_BASE + 0x40)
+#define ETH_MACA0LR MMIO32(ETHERNET_BASE + 0x44)
+#define ETH_MACA1HR MMIO32(ETHERNET_BASE + 0x48)
+#define ETH_MACA1LR MMIO32(ETHERNET_BASE + 0x4C)
+#define ETH_MACA2HR MMIO32(ETHERNET_BASE + 0x50)
+#define ETH_MACA2LR MMIO32(ETHERNET_BASE + 0x54)
+#define ETH_MACA3HR MMIO32(ETHERNET_BASE + 0x58)
+#define ETH_MACA3LR MMIO32(ETHERNET_BASE + 0x5C)
+
+/* Ethernet MMC registers */
+#define ETH_MMCCR MMIO32(ETHERNET_BASE + 0x100)
+#define ETH_MMCRIR MMIO32(ETHERNET_BASE + 0x104)
+#define ETH_MMCTIR MMIO32(ETHERNET_BASE + 0x108)
+#define ETH_MMCRIMR MMIO32(ETHERNET_BASE + 0x10C)
+#define ETH_MMCTIMR MMIO32(ETHERNET_BASE + 0x110)
+#define ETH_MMCTGFSCCR MMIO32(ETHERNET_BASE + 0x14C)
+#define ETH_MMCTGFMSCCR MMIO32(ETHERNET_BASE + 0x150)
+#define ETH_MMCTGFCR MMIO32(ETHERNET_BASE + 0x168)
+#define ETH_MMCRFCECR MMIO32(ETHERNET_BASE + 0x194)
+#define ETH_MMCRFAECR MMIO32(ETHERNET_BASE + 0x198)
+#define ETH_MMCRGUFCR MMIO32(ETHERNET_BASE + 0x1C4)
+
+/* Ethrenet IEEE 1588 time stamp registers */
+#define ETH_PTPTSCR MMIO32(ETHERNET_BASE + 0x700)
+#define ETH_PTPSSIR MMIO32(ETHERNET_BASE + 0x704)
+#define ETH_PTPTSHR MMIO32(ETHERNET_BASE + 0x708)
+#define ETH_PTPTSLR MMIO32(ETHERNET_BASE + 0x70C)
+#define ETH_PTPTSHUR MMIO32(ETHERNET_BASE + 0x710)
+#define ETH_PTPTSLUR MMIO32(ETHERNET_BASE + 0x714)
+#define ETH_PTPTSAR MMIO32(ETHERNET_BASE + 0x718)
+#define ETH_PTPTTHR MMIO32(ETHERNET_BASE + 0x71C)
+#define ETH_PTPTTLR MMIO32(ETHERNET_BASE + 0x720)
+
+/* Ethernet DMA registers */
+#define ETH_DMABMR MMIO32(ETHERNET_BASE + 0x1000)
+#define ETH_DMATPDR MMIO32(ETHERNET_BASE + 0x1004)
+#define ETH_DMARPDR MMIO32(ETHERNET_BASE + 0x1008)
+#define ETH_DMARDLAR MMIO32(ETHERNET_BASE + 0x100C)
+#define ETH_DMATDLAR MMIO32(ETHERNET_BASE + 0x1010)
+#define ETH_DMATDLAR MMIO32(ETHERNET_BASE + 0x1010)
+#define ETH_DMASR MMIO32(ETHERNET_BASE + 0x1014)
+#define ETH_DMAOMR MMIO32(ETHERNET_BASE + 0x1018)
+#define ETH_DMAIER MMIO32(ETHERNET_BASE + 0x101C)
+#define ETH_DMAMFBOCR MMIO32(ETHERNET_BASE + 0x1020)
+#define ETH_DMACHTDR MMIO32(ETHERNET_BASE + 0x1048)
+#define ETH_DMACHRDR MMIO32(ETHERNET_BASE + 0x104C)
+#define ETH_DMACHTBAR MMIO32(ETHERNET_BASE + 0x1050)
+#define ETH_DMACHRBAR MMIO32(ETHERNET_BASE + 0x1054)
+
+/* Ethernet MAC Register bit definitions */
+/* Ethernet MAC configuration register ETH_MACCR bits */
+#define ETH_MACCR_RE 0x00000004
+#define ETH_MACCR_TE 0x00000008
+#define ETH_MACCR_DC 0x00000010
+#define ETH_MACCR_BL 0x00000060
+#define ETH_MACCR_APCS 0x00000080
+#define ETH_MACCR_RD 0x00000200
+#define ETH_MACCR_IPCO 0x00000400
+#define ETH_MACCR_DM 0x00000800
+#define ETH_MACCR_LM 0x00001000
+#define ETH_MACCR_ROD 0x00002000
+#define ETH_MACCR_FES 0x00004000
+#define ETH_MACCR_CSD 0x00010000
+#define ETH_MACCR_IFG 0x000E0000
+#define ETH_MACCR_JD 0x00400000
+#define ETH_MACCR_WD 0x00800000
+
+/* Ethernet MAC frame filter register ETH_MACFFR bits */
+#define ETH_MACFFR_PM 0x00000001
+#define ETH_MACFFR_HU 0x00000002
+#define ETH_MACFFR_HM 0x00000004
+#define ETH_MACFFR_DAIF 0x00000008
+#define ETH_MACFFR_PAM 0x00000010
+#define ETH_MACFFR_BFD 0x00000020
+#define ETH_MACFFR_PCF 0x000000C0
+#define ETH_MACFFR_SAIF 0x00000100
+#define ETH_MACFFR_SAF 0x00000200
+#define ETH_MACFFR_HPF 0x00000400
+#define ETH_MACFFR_PA 0x80000000
+
+/* Ethernet MAC MII address register ETH_MACMIIAR bits */
+#define ETH_MACMIIAR_MB 0x0001
+#define ETH_MACMIIAR_MW 0x0002
+/* Clock Range for MDC frequency */
+#define ETH_MACMIIAR_CR_MASK 0x001C
+#define ETH_MACMIIAR_CR_HCLK_DIV_42 0x0000 /* For HCLK 60-72 MHz */
+#define ETH_MACMIIAR_CR_HCLK_DIV_16 0x0008 /* For HCLK 20-35 MHz */
+#define ETH_MACMIIAR_CR_HCLK_DIV_24 0x000C /* For HCLK 35-60 MHz */
+#define ETH_MACMIIAR_MR 0x07C0
+#define ETH_MACMIIAR_PA 0xF800
+
+/* Ethernet MAC flow control register ETH_MACFCR bits */
+#define ETH_MACFCR_FCB 0x00000001
+#define ETH_MACFCR_BPA 0x00000001
+#define ETH_MACFCR_TFCE 0x00000002
+#define ETH_MACFCR_RFCE 0x00000004
+#define ETH_MACFCR_UPFD 0x00000008
+#define ETH_MACFCR_PLT 0x00000030
+#define ETH_MACFCR_ZQPD 0x00000080
+#define ETH_MACFCR_PT 0xFFFF0000
+
+/* Ethernet MAC interrupt status regster ETH_MACSR bits */
+#define ETH_MACSR_PMTS 0x0008
+#define ETH_MACSR_MMCS 0x0010
+#define ETH_MACSR_MMCRS 0x0020
+#define ETH_MACSR_MMCTS 0x0040
+#define ETH_MACSR_TSTS 0x0200
+
+/* Ethernet MAC interrupt mask regster ETH_MACIMR bits */
+#define ETH_MACIMR_PMTIM 0x0008
+#define ETH_MACIMR_TSTIM 0x0200
+
+/* Ethernet DMA Register bit definitions */
+/* Ethernet DMA bus mode register ETH_DMABMR bits */
+#define ETH_DMABMR_SR 0x00000001
+#define ETH_DMABMR_DA 0x00000002
+#define ETH_DMABMR_DSL_MASK 0x0000007C
+#define ETH_DMABMR_PBL_MASK 0x00003F00
+#define ETH_DMABMR_RTPR_MASK 0x0000C000
+#define ETH_DMABMR_RTPR_1TO1 0x00000000
+#define ETH_DMABMR_RTPR_2TO1 0x00004000
+#define ETH_DMABMR_RTPR_3TO1 0x00008000
+#define ETH_DMABMR_RTPR_4TO1 0x0000C000
+#define ETH_DMABMR_FB 0x00010000
+#define ETH_DMABMR_RDP_MASK 0x007E0000
+#define ETH_DMABMR_USP 0x00800000
+#define ETH_DMABMR_FPM 0x01000000
+#define ETH_DMABMR_AAB 0x02000000
+
+/* Ethernet DMA operation mode register ETH_DMAOMR bits */
+#define ETH_DMAOMR_SR 0x00000002
+#define ETH_DMAOMR_OSF 0x00000004
+#define ETH_DMAOMR_RTC_MASK 0x00000018
+#define ETH_DMAOMR_RTC_64 0x00000000
+#define ETH_DMAOMR_RTC_32 0x00000008
+#define ETH_DMAOMR_RTC_96 0x00000010
+#define ETH_DMAOMR_RTC_128 0x00000018
+#define ETH_DMAOMR_FUGF 0x00000040
+#define ETH_DMAOMR_FEF 0x00000080
+#define ETH_DMAOMR_ST 0x00002000
+#define ETH_DMAOMR_TTC_MASK 0x0001C000
+#define ETH_DMAOMR_FTF 0x00100000
+#define ETH_DMAOMR_TSF 0x00200000
+#define ETH_DMAOMR_DFRF 0x01000000
+#define ETH_DMAOMR_RSF 0x02000000
+#define ETH_DMAOMR_DTCEFD 0x04000000
+
+/* Ethernet DMA interrupt enable register ETH_DMAIER bits */
+#define ETH_DMAIER_TIE 0x00000001
+#define ETH_DMAIER_TPSIE 0x00000002
+#define ETH_DMAIER_TBUIE 0x00000004
+#define ETH_DMAIER_TJTIE 0x00000008
+#define ETH_DMAIER_ROIE 0x00000010
+#define ETH_DMAIER_TUIE 0x00000020
+#define ETH_DMAIER_RIE 0x00000040
+#define ETH_DMAIER_RBUIE 0x00000080
+#define ETH_DMAIER_RPSIE 0x00000100
+#define ETH_DMAIER_RWTIE 0x00000200
+#define ETH_DMAIER_ETIE 0x00000400
+#define ETH_DMAIER_FBEIE 0x00002000
+#define ETH_DMAIER_ERIE 0x00004000
+#define ETH_DMAIER_AISE 0x00008000
+#define ETH_DMAIER_NSIE 0x00010000
+
+#endif
diff --git a/include/libopenstm32/gpio.h b/include/libopenstm32/gpio.h
index a96c999..f1864a8 100644
--- a/include/libopenstm32/gpio.h
+++ b/include/libopenstm32/gpio.h
@@ -55,7 +55,7 @@
/* --- Alternate function GPIOs -------------------------------------------- */
-/* Default alternate functions of some pins (without remapping) */
+/* Default alternate functions of some pins (with and without remapping) */
/* CAN1 / CAN */
#define GPIO_CAN1_RX GPIO11 /* PA11 */
@@ -63,10 +63,23 @@
#define GPIO_CAN_RX GPIO_CAN1_RX /* Alias */
#define GPIO_CAN_TX GPIO_CAN1_TX /* Alias */
+#define GPIO_CAN_PB_RX GPIO8 /* PB8 */
+#define GPIO_CAN_PB_TX GPIO9 /* PB9 */
+#define GPIO_CAN1_PB_RX GPIO_CAN_PB_RX /* Alias */
+#define GPIO_CAN1_PB_TX GPIO_CAN_PB_TX /* Alias */
+
+#define GPIO_CAN_PD_RX GPIO0 /* PD0 */
+#define GPIO_CAN_PD_TX GPIO1 /* PD1 */
+#define GPIO_CAN1_PD_RX GPIO_CAN_PD_RX /* Alias */
+#define GPIO_CAN1_PD_TX GPIO_CAN_PD_TX /* Alias */
+
/* CAN2 */
#define GPIO_CAN2_RX GPIO12 /* PB12 */
#define GPIO_CAN2_TX GPIO13 /* PB13 */
+#define GPIO_CAN2_RE_RX GPIO5 /* PB5 */
+#define GPIO_CAN2_RE_TX GPIO6 /* PB6 */
+
/* JTAG/SWD */
#define GPIO_JTMS_SWDIO GPIO13 /* PA13 */
#define GPIO_JTCK_SWCLK GPIO14 /* PA14 */
@@ -79,20 +92,58 @@
#define GPIO_TRACED2 GPIO5 /* PE5 */
#define GPIO_TRACED3 GPIO6 /* PE6 */
-/* Timer */
+/* Timer5 */
#define GPIO_TIM5_CH4 GPIO3 /* PA3 */
+
+/* Timer4 */
#define GPIO_TIM4_CH1 GPIO6 /* PB6 */
#define GPIO_TIM4_CH2 GPIO7 /* PB7 */
#define GPIO_TIM4_CH3 GPIO8 /* PB8 */
#define GPIO_TIM4_CH4 GPIO9 /* PB9 */
+
+#define GPIO_TIM4_RE_CH1 GPIO12 /* PD12 */
+#define GPIO_TIM4_RE_CH2 GPIO13 /* PD13 */
+#define GPIO_TIM4_RE_CH3 GPIO14 /* PD14 */
+#define GPIO_TIM4_RE_CH4 GPIO15 /* PD15 */
+
+/* Timer3 */
#define GPIO_TIM3_CH1 GPIO6 /* PA6 */
#define GPIO_TIM3_CH2 GPIO7 /* PA7 */
#define GPIO_TIM3_CH3 GPIO0 /* PB0 */
#define GPIO_TIM3_CH4 GPIO1 /* PB1 */
+
+#define GPIO_TIM3_PR_CH1 GPIO4 /* PB4 */
+#define GPIO_TIM3_PR_CH2 GPIO5 /* PB5 */
+#define GPIO_TIM3_PR_CH3 GPIO0 /* PB0 */
+#define GPIO_TIM3_PR_CH4 GPIO1 /* PB1 */
+
+#define GPIO_TIM3_FR_CH1 GPIO6 /* PC6 */
+#define GPIO_TIM3_FR_CH2 GPIO7 /* PC7 */
+#define GPIO_TIM3_FR_CH3 GPIO8 /* PC8 */
+#define GPIO_TIM3_FR_CH4 GPIO9 /* PC9 */
+
+/* Timer2 */
#define GPIO_TIM2_CH1_ETR GPIO0 /* PA0 */
#define GPIO_TIM2_CH2 GPIO1 /* PA1 */
#define GPIO_TIM2_CH3 GPIO2 /* PA2 */
#define GPIO_TIM2_CH4 GPIO3 /* PA3 */
+
+#define GPIO_TIM2_PR1_CH1_ETR GPIO15 /* PA15 */
+#define GPIO_TIM2_PR1_CH2 GPIO3 /* PB3 */
+#define GPIO_TIM2_PR1_CH3 GPIO2 /* PA2 */
+#define GPIO_TIM2_PR1_CH4 GPIO3 /* PA3 */
+
+#define GPIO_TIM2_PR2_CH1_ETR GPIO0 /* PA0 */
+#define GPIO_TIM2_PR2_CH2 GPIO1 /* PA1 */
+#define GPIO_TIM2_PR2_CH3 GPIO10 /* PB10 */
+#define GPIO_TIM2_PR2_CH4 GPIO11 /* PB11 */
+
+#define GPIO_TIM2_FR_CH1_ETR GPIO15 /* PA15 */
+#define GPIO_TIM2_FR_CH2 GPIO3 /* PB3 */
+#define GPIO_TIM2_FR_CH3 GPIO10 /* PB10 */
+#define GPIO_TIM2_FR_CH4 GPIO11 /* PB11 */
+
+/* Timer1 */
#define GPIO_TIM1_ETR GPIO12 /* PA12 */
#define GPIO_TIM1_CH1 GPIO8 /* PA8 */
#define GPIO_TIM1_CH2 GPIO9 /* PA9 */
@@ -103,25 +154,74 @@
#define GPIO_TIM1_CH2N GPIO14 /* PB14 */
#define GPIO_TIM1_CH3N GPIO15 /* PB15 */
-/* USART */
+#define GPIO_TIM1_PR_ETR GPIO12 /* PA12 */
+#define GPIO_TIM1_PR_CH1 GPIO8 /* PA8 */
+#define GPIO_TIM1_PR_CH2 GPIO9 /* PA9 */
+#define GPIO_TIM1_PR_CH3 GPIO10 /* PA10 */
+#define GPIO_TIM1_PR_CH4 GPIO11 /* PA11 */
+#define GPIO_TIM1_PR_BKIN GPIO6 /* PA6 */
+#define GPIO_TIM1_PR_CH1N GPIO7 /* PA7 */
+#define GPIO_TIM1_PR_CH2N GPIO0 /* PB0 */
+#define GPIO_TIM1_PR_CH3N GPIO1 /* PB1 */
+
+#define GPIO_TIM1_FR_ETR GPIO7 /* PE7 */
+#define GPIO_TIM1_FR_CH1 GPIO9 /* PE9 */
+#define GPIO_TIM1_FR_CH2 GPIO11 /* PE11 */
+#define GPIO_TIM1_FR_CH3 GPIO13 /* PE13 */
+#define GPIO_TIM1_FR_CH4 GPIO14 /* PE14 */
+#define GPIO_TIM1_FR_BKIN GPIO15 /* PE15 */
+#define GPIO_TIM1_FR_CH1N GPIO8 /* PE8 */
+#define GPIO_TIM1_FR_CH2N GPIO10 /* PE10 */
+#define GPIO_TIM1_FR_CH3N GPIO12 /* PE12 */
+
+/* USART3 */
#define GPIO_USART3_TX GPIO10 /* PB10 */
#define GPIO_USART3_RX GPIO11 /* PB11 */
#define GPIO_USART3_CK GPIO12 /* PB12 */
#define GPIO_USART3_CTS GPIO13 /* PB13 */
#define GPIO_USART3_RTS GPIO14 /* PB14 */
+
+#define GPIO_USART3_PR_TX GPIO10 /* PC10 */
+#define GPIO_USART3_PR_RX GPIO11 /* PC11 */
+#define GPIO_USART3_PR_CK GPIO12 /* PC12 */
+#define GPIO_USART3_PR_CTS GPIO13 /* PB13 */
+#define GPIO_USART3_PR_RTS GPIO14 /* PB14 */
+
+#define GPIO_USART3_FR_TX GPIO8 /* PD8 */
+#define GPIO_USART3_FR_RX GPIO9 /* PD9 */
+#define GPIO_USART3_FR_CK GPIO10 /* PD10 */
+#define GPIO_USART3_FR_CTS GPIO11 /* PD11 */
+#define GPIO_USART3_FR_RTS GPIO12 /* PD12 */
+
+/* USART2 */
#define GPIO_USART2_CTS GPIO0 /* PA0 */
#define GPIO_USART2_RTS GPIO1 /* PA1 */
#define GPIO_USART2_TX GPIO2 /* PA2 */
#define GPIO_USART2_RX GPIO3 /* PA3 */
#define GPIO_USART2_CK GPIO4 /* PA4 */
+
+#define GPIO_USART2_RE_CTS GPIO3 /* PD3 */
+#define GPIO_USART2_RE_RTS GPIO4 /* PD4 */
+#define GPIO_USART2_RE_TX GPIO5 /* PD5 */
+#define GPIO_USART2_RE_RX GPIO6 /* PD6 */
+#define GPIO_USART2_RE_CK GPIO7 /* PD7 */
+
+/* USART1 */
#define GPIO_USART1_TX GPIO9 /* PA9 */
#define GPIO_USART1_RX GPIO10 /* PA10 */
+#define GPIO_USART1_RE_TX GPIO6 /* PB6 */
+#define GPIO_USART1_RE_RX GPIO7 /* PB7 */
+
/* I2C1 */
#define GPIO_I2C1_SMBAI GPIO5 /* PB5 */
#define GPIO_I2C1_SCL GPIO6 /* PB6 */
#define GPIO_I2C1_SDA GPIO7 /* PB7 */
+#define GPIO_I2C1_RE_SMBAI GPIO5 /* PB5 */
+#define GPIO_I2C1_RE_SCL GPIO8 /* PB8 */
+#define GPIO_I2C1_RE_SDA GPIO9 /* PB9 */
+
/* I2C2 */
#define GPIO_I2C2_SCL GPIO10 /* PB10 */
#define GPIO_I2C2_SDA GPIO11 /* PB11 */
@@ -133,6 +233,11 @@
#define GPIO_SPI1_MISO GPIO6 /* PA6 */
#define GPIO_SPI1_MOSI GPIO7 /* PA7 */
+#define GPIO_SPI1_RE_NSS GPIO15 /* PA15 */
+#define GPIO_SPI1_RE_SCK GPIO3 /* PB3 */
+#define GPIO_SPI1_RE_MISO GPIO4 /* PB4 */
+#define GPIO_SPI1_RE_MOSI GPIO5 /* PB5 */
+
/* SPI2 */
#define GPIO_SPI2_NSS GPIO12 /* PB12 */
#define GPIO_SPI2_SCK GPIO13 /* PB13 */
@@ -145,6 +250,11 @@
#define GPIO_SPI3_MISO GPIO4 /* PB4 */
#define GPIO_SPI3_MOSI GPIO5 /* PB5 */
+#define GPIO_SPI3_RE_NSS GPIO4 /* PA4 */
+#define GPIO_SPI3_RE_SCK GPIO10 /* PC10 */
+#define GPIO_SPI3_RE_MISO GPIO11 /* PC11 */
+#define GPIO_SPI3_RE_MOSI GPIO12 /* PC12 */
+
/* ETH */
#define GPIO_ETH_RX_DV_CRS_DV GPIO7 /* PA7 */
#define GPIO_ETH_RXD0 GPIO4 /* PC4 */
@@ -152,6 +262,12 @@
#define GPIO_ETH_RXD2 GPIO0 /* PB0 */
#define GPIO_ETH_RXD3 GPIO1 /* PB1 */
+#define GPIO_ETH_RE_RX_DV_CRS_DV GPIO8 /* PD8 */
+#define GPIO_ETH_RE_RXD0 GPIO9 /* PD9 */
+#define GPIO_ETH_RE_RXD1 GPIO10 /* PD10 */
+#define GPIO_ETH_RE_RXD2 GPIO11 /* PD11 */
+#define GPIO_ETH_RE_RXD3 GPIO12 /* PD12 */
+
/* --- GPIO registers ------------------------------------------------------ */
/* Port configuration register low (GPIOx_CRL) */
@@ -317,22 +433,54 @@
/* --- AFIO_MAPR values ---------------------------------------------------- */
+/* 31 reserved */
+
+/* PTP_PPS_REMAP: Ethernet PTP PPS remapping
+ * (only connectivity line devices) */
+#define AFIO_MAPR_PTP_PPS_REMAP (1 << 30)
+
+/* TIM2ITR1_IREMAP: TIM2 internal trigger 1 remapping
+ * (only connectivity line devices) */
+#define AFIO_MAPR_TIM2ITR1_IREMAP (1 << 29)
+
+/* SPI3_REMAP: SPI3/I2S3 remapping
+ * (only connectivity line devices) */
+#define AFIO_MAPR_SPI3_REMAP (1 << 28)
+
+/* 27 reserved */
+
/* SWJ_CFG[2:0]: Serial wire JTAG configuration */
#define AFIO_MAPR_SWJ_CFG_FULL_SWJ (0x0 << 24)
#define AFIO_MAPR_SWJ_CFG_FULL_SWJ_NO_JNTRST (0x1 << 24)
#define AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_ON (0x2 << 24)
#define AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_OFF (0x4 << 24)
-/* ADC2_ETRGREG_REMAP: ADC2 external trigger regulator conversion remapping */
+/* MII_REMAP: MII or RMII selection
+ * (only connectivity line devices) */
+#define AFIO_MAPR_MII_RMII_SEL (1 << 23)
+
+/* CAN2_REMAP: CAN2 I/O remapping
+ * (only connectivity line devices) */
+#define AFIO_MAPR_CAN2_REMAP (1 << 22)
+
+/* ETH_REMAP: Ethernet MAC I/O remapping
+ * (only connectivity line devices) */
+#define AFIO_MAPR_ETH_REMAP (1 << 21)
+
+/* ADC2_ETRGREG_REMAP: ADC2 external trigger regulator conversion remapping
+ * (only low-, medium-, high- and XL-densitiy devices) */
#define AFIO_MAPR_ADC2_ETRGREG_REMAP (1 << 20)
-/* ADC2_ETRGINJ_REMAP: ADC2 external trigger injected conversion remapping */
+/* ADC2_ETRGINJ_REMAP: ADC2 external trigger injected conversion remapping
+ * (only low-, medium-, high- and XL-densitiy devices) */
#define AFIO_MAPR_ADC2_ETRGINJ_REMAP (1 << 19)
-/* ADC1_ETRGREG_REMAP: ADC1 external trigger regulator conversion remapping */
+/* ADC1_ETRGREG_REMAP: ADC1 external trigger regulator conversion remapping
+ * (only low-, medium-, high- and XL-densitiy devices) */
#define AFIO_MAPR_ADC1_ETRGREG_REMAP (1 << 18)
-/* ADC1_ETRGINJ_REMAP: ADC1 external trigger injected conversion remapping */
+/* ADC1_ETRGINJ_REMAP: ADC1 external trigger injected conversion remapping
+ * (only low-, medium-, high- and XL-densitiy devices) */
#define AFIO_MAPR_ADC1_ETRGINJ_REMAP (1 << 17)
/* TIM5CH4_IREMAP: TIM5 channel4 internal remap */
@@ -341,10 +489,10 @@
/* PD01_REMAP: Port D0/Port D1 mapping on OSC_IN/OSC_OUT */
#define AFIO_MAPR_PD01_REMAP (1 << 15)
-/* CAN_REMAP[1:0]: CAN alternate function remapping */
-#define AFIO_MAPR_CAN_REMAP_PA11_PA12 (0x0 << 13)
-#define AFIO_MAPR_CAN_REMAP_PB8_PB9 (0x2 << 13) /* Not on 36pin pkg */
-#define AFIO_MAPR_CAN_REMAP_PD0_PD1 (0x3 << 13)
+/* CAN_REMAP[1:0]: CAN1 alternate function remapping */
+#define AFIO_MAPR_CAN1_REMAP_PORTA (0x0 << 13)
+#define AFIO_MAPR_CAN1_REMAP_PORTB (0x2 << 13) /* Not on 36pin pkg */
+#define AFIO_MAPR_CAN1_REMAP_PORTD (0x3 << 13)
/* TIM4_REMAP: TIM4 remapping */
#define AFIO_MAPR_TIM4_REMAP (1 << 12)
@@ -402,5 +550,6 @@ u16 gpio_get(u32 gpioport, u16 gpios);
void gpio_toggle(u32 gpioport, u16 gpios);
u16 gpio_port_read(u32 gpioport);
void gpio_port_write(u32 gpioport, u16 data);
+void gpio_port_config_lock(u32 gpioport, u16 gpios);
#endif
diff --git a/include/libopenstm32/usart.h b/include/libopenstm32/usart.h
index 0cf86d1..3f93d1b 100644
--- a/include/libopenstm32/usart.h
+++ b/include/libopenstm32/usart.h
@@ -125,7 +125,7 @@
/* --- USART_DR values ----------------------------------------------------- */
/* USART_DR[8:0]: DR[8:0]: Data value */
-#define USART_DR_MASK 0xFF
+#define USART_DR_MASK 0x1FF
/* --- USART_BRR values ---------------------------------------------------- */
@@ -178,26 +178,18 @@
/* SBK: Send break */
#define USART_CR1_SBK (1 << 0)
-/* CR1_PCE / CR1_PS combined values */
-#define USART_PARITY_NONE 0x00
-#define USART_PARITY_ODD 0x02
-#define USART_PARITY_EVEN 0x03
-
-/* CR1_TE/CR1_RE combined values */
-#define USART_MODE_RX 0x01
-#define USART_MODE_TX 0x02
-#define USART_MODE_TX_RX 0x03
-
/* --- USART_CR2 values ---------------------------------------------------- */
/* LINEN: LIN mode enable */
#define USART_CR2_LINEN (1 << 14)
/* STOP[13:12]: STOP bits */
-#define USART_STOPBITS_1 0x00 /* 1 stop bit */
-#define USART_STOPBITS_0_5 0x01 /* 0.5 stop bits */
-#define USART_STOPBITS_2 0x02 /* 2 stop bits */
-#define USART_STOPBITS_1_5 0x03 /* 1.5 stop bits */
+#define USART_CR2_STOPBITS_1 (0x00 << 12) /* 1 stop bit */
+#define USART_CR2_STOPBITS_0_5 (0x01 << 12) /* 0.5 stop bits */
+#define USART_CR2_STOPBITS_2 (0x02 << 12) /* 2 stop bits */
+#define USART_CR2_STOPBITS_1_5 (0x03 << 12) /* 1.5 stop bits */
+#define USART_CR2_STOPBITS_MASK (0x03 << 12)
+#define USART_CR2_STOPBITS_SHIFT 12
/* CLKEN: Clock enable */
#define USART_CR2_CLKEN (1 << 11)
@@ -262,12 +254,6 @@
/* EIE: Error interrupt enable */
#define USART_CR3_EIE (1 << 0)
-/* CR3_CTSE/CR3_RTSE combined values */
-#define USART_FLOWCONTROL_NONE 0x00
-#define USART_FLOWCONTROL_RTS 0x01
-#define USART_FLOWCONTROL_CTS 0x02
-#define USART_FLOWCONTROL_RTS_CTS 0x03
-
/* --- USART_GTPR values --------------------------------------------------- */
/* GT[7:0]: Guard time value */
@@ -280,6 +266,32 @@
/* TODO */ /* Note to Uwe: what needs to be done here? */
+/* --- Convenience defines ------------------------------------------------- */
+
+/* CR1_PCE / CR1_PS combined values */
+#define USART_PARITY_NONE 0x00
+#define USART_PARITY_ODD USART_CR1_PS
+#define USART_PARITY_EVEN (USART_CR1_PS | USART_CR1_PCE)
+#define USART_PARITY_MASK (USART_CR1_PS | USART_CR1_PCE)
+
+/* CR1_TE/CR1_RE combined values */
+#define USART_MODE_RX USART_CR1_RE
+#define USART_MODE_TX USART_CR1_TE
+#define USART_MODE_TX_RX (USART_CR1_RE | USART_CR1_TE)
+#define USART_MODE_MASK (USART_CR1_RE | USART_CR1_TE)
+
+#define USART_STOPBITS_1 USART_CR2_STOPBITS_1 /* 1 stop bit */
+#define USART_STOPBITS_0_5 USART_CR2_STOPBITS_0_5 /* 0.5 stop bits */
+#define USART_STOPBITS_2 USART_CR2_STOPBITS_2 /* 2 stop bits */
+#define USART_STOPBITS_1_5 USART_CR2_STOPBITS_1_5 /* 1.5 stop bits */
+
+/* CR3_CTSE/CR3_RTSE combined values */
+#define USART_FLOWCONTROL_NONE 0x00
+#define USART_FLOWCONTROL_RTS USART_CR3_RTSE
+#define USART_FLOWCONTROL_CTS USART_CR3_CTSE
+#define USART_FLOWCONTROL_RTS_CTS (USART_CR3_RTSE | USART_CR3_CTSE)
+#define USART_FLOWCONTROL_MASK (USART_CR3_RTSE | USART_CR3_CTSE)
+
/* --- Function prototypes ------------------------------------------------- */
void usart_set_baudrate(u32 usart, u32 baud);
@@ -292,5 +304,9 @@ void usart_enable(u32 usart);
void usart_disable(u32 usart);
void usart_send(u32 usart, u16 data);
u16 usart_recv(u32 usart);
+void usart_wait_send_ready(u32 usart);
+void usart_wait_recv_ready(u32 usart);
+void usart_send_blocking(u32 usart, u16 data);
+u16 usart_recv_blocking(u32 usart);
#endif
diff --git a/lib/Makefile b/lib/Makefile
index cb22b65..9003f5b 100644
--- a/lib/Makefile
+++ b/lib/Makefile
@@ -24,12 +24,13 @@ PREFIX ?= arm-elf
CC = $(PREFIX)-gcc
AR = $(PREFIX)-ar
CFLAGS = -Os -g -Wall -Wextra -I../include -fno-common \
- -mcpu=cortex-m3 -mthumb -Wstrict-prototypes
+ -mcpu=cortex-m3 -mthumb -Wstrict-prototypes \
+ -ffunction-sections -fdata-sections
# ARFLAGS = rcsv
ARFLAGS = rcs
OBJS = vector.o rcc.o gpio.o usart.o adc.o spi.o flash.o nvic.o \
- rtc.o i2c.o dma.o systick.o exti.o scb.o \
- usb_f103.o usb.o usb_control.o usb_standard.o
+ rtc.o i2c.o dma.o systick.o exti.o scb.o ethernet.o \
+ usb_f103.o usb.o usb_control.o usb_standard.o can.o
VPATH += usb
diff --git a/lib/can.c b/lib/can.c
new file mode 100644
index 0000000..baddab3
--- /dev/null
+++ b/lib/can.c
@@ -0,0 +1,305 @@
+/*
+ * This file is part of the libopenstm32 project.
+ *
+ * Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
+ *
+ * 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 <libopenstm32/can.h>
+#include <libopenstm32/rcc.h>
+
+void can_reset(u32 canport)
+{
+ if (canport == CAN1) {
+ rcc_peripheral_reset(&RCC_APB1RSTR, RCC_APB1RSTR_CAN1RST);
+ rcc_peripheral_clear_reset(&RCC_APB1RSTR, RCC_APB1RSTR_CAN1RST);
+ } else {
+ rcc_peripheral_reset(&RCC_APB1RSTR, RCC_APB1RSTR_CAN2RST);
+ rcc_peripheral_clear_reset(&RCC_APB1RSTR, RCC_APB1RSTR_CAN2RST);
+ }
+}
+
+int can_init(u32 canport, bool ttcm, bool abom, bool awum, bool nart,
+ bool rflm, bool txfp, u32 sjw, u32 ts1, u32 ts2, u32 brp)
+{
+ u32 wait_ack = 0x00000000;
+ u32 can_msr_inak_timeout = 0x0000FFFF;
+ int ret = 0;
+
+ /* Exit from sleep mode. */
+ CAN_MCR(canport) &= ~CAN_MCR_SLEEP;
+
+ /* Request initialization "enter". */
+ CAN_MCR(canport) |= CAN_MCR_INRQ;
+
+ /* Wait for acknowledge. */
+ while ((wait_ack != can_msr_inak_timeout) &&
+ ((CAN_MSR(canport) & CAN_MSR_INAK) != CAN_MSR_INAK)) {
+ wait_ack++;
+ }
+
+ /* Check the acknowledge. */
+ if ((CAN_MSR(canport) & CAN_MSR_INAK) != CAN_MSR_INAK)
+ return 1;
+
+ /* Set the automatic bus-off management. */
+ if (ttcm)
+ CAN_MCR(canport) |= CAN_MCR_TTCM;
+ else
+ CAN_MCR(canport) &= ~CAN_MCR_TTCM;
+
+ if (abom)
+ CAN_MCR(canport) |= CAN_MCR_ABOM;
+ else
+ CAN_MCR(canport) &= ~CAN_MCR_ABOM;
+
+ if (awum)
+ CAN_MCR(canport) |= CAN_MCR_AWUM;
+ else
+ CAN_MCR(canport) &= ~CAN_MCR_AWUM;
+
+ if (nart)
+ CAN_MCR(canport) |= CAN_MCR_NART;
+ else
+ CAN_MCR(canport) &= ~CAN_MCR_NART;
+
+ if (rflm)
+ CAN_MCR(canport) |= CAN_MCR_RFLM;
+ else
+ CAN_MCR(canport) &= ~CAN_MCR_RFLM;
+
+ if (txfp)
+ CAN_MCR(canport) |= CAN_MCR_TXFP;
+ else
+ CAN_MCR(canport) &= ~CAN_MCR_TXFP;
+
+ /* Set bit timings. */
+ CAN_BTR(canport) = sjw | ts2 | ts1 |
+ (u32)(CAN_BTR_BRP_MASK & (brp - 1));
+
+ /* Request initialization "leave". */
+ CAN_MCR(canport) &= ~CAN_MCR_INRQ;
+
+ /* Wait for acknowledge. */
+ wait_ack = 0x00000000;
+ while ((wait_ack != can_msr_inak_timeout) &&
+ ((CAN_MSR(canport) & CAN_MSR_INAK) == CAN_MSR_INAK)) {
+ wait_ack++;
+ }
+
+ if ((CAN_MSR(canport) & CAN_MSR_INAK) == CAN_MSR_INAK)
+ ret = 1;
+
+ return ret;
+}
+
+void can_filter_init(u32 canport, u32 nr, bool scale_32bit, bool id_list_mode,
+ u32 fr1, u32 fr2, u32 fifo, bool enable)
+{
+ u32 filter_select_bit = 0x00000001 << nr;
+
+ /* Request initialization "enter". */
+ CAN_FMR(canport) |= CAN_FMR_FINIT;
+
+ /* Deactivate the filter. */
+ CAN_FA1R(canport) &= ~filter_select_bit;
+
+ if (scale_32bit) {
+ /* Set 32-bit scale for the filter. */
+ CAN_FS1R(canport) |= filter_select_bit;
+ } else {
+ /* Set 16-bit scale for the filter. */
+ CAN_FS1R(canport) &= ~filter_select_bit;
+ }
+
+ if (id_list_mode) {
+ /* Set filter mode to ID list mode. */
+ CAN_FM1R(canport) |= filter_select_bit;
+ } else {
+ /* Set filter mode to id/mask mode. */
+ CAN_FM1R(canport) &= ~filter_select_bit;
+ }
+
+ /* Set the first filter register. */
+ CAN_FiR1(canport, nr) = fr1;
+
+ /* Set the second filter register. */
+ CAN_FiR2(canport, nr) = fr2;
+
+ /* Select FIFO0 or FIFO1 as filter assignement. */
+ if (fifo)
+ CAN_FFA1R(canport) |= filter_select_bit; /* FIFO1 */
+ else
+ CAN_FFA1R(canport) &= ~filter_select_bit; /* FIFO0 */
+
+ if (enable)
+ CAN_FA1R(canport) |= filter_select_bit; /* Activate filter. */
+
+ /* Request initialization "leave". */
+ CAN_FMR(canport) &= ~CAN_FMR_FINIT;
+}
+
+void can_filter_id_mask_16bit_init(u32 canport, u32 nr, u16 id1, u16 mask1,
+ u16 id2, u16 mask2, u32 fifo, bool enable)
+{
+ can_filter_init(canport, nr, false, false,
+ ((u32)id1 << 16) | (u32)mask1,
+ ((u32)id2 << 16) | (u32)mask2, fifo, enable);
+}
+
+void can_filter_id_mask_32bit_init(u32 canport, u32 nr, u32 id, u32 mask,
+ u32 fifo, bool enable)
+{
+ can_filter_init(canport, nr, true, false, id, mask, fifo, enable);
+}
+
+void can_filter_id_list_16bit_init(u32 canport, u32 nr, u16 id1, u16 id2,
+ u16 id3, u16 id4, u32 fifo, bool enable)
+{
+ can_filter_init(canport, nr, false, true,
+ ((u32)id1 << 16) | (u32)id2,
+ ((u32)id3 << 16) | (u32)id4, fifo, enable);
+}
+
+void can_filter_id_list_32bit_init(u32 canport, u32 nr, u32 id1, u32 id2,
+ u32 fifo, bool enable)
+{
+ can_filter_init(canport, nr, true, true, id1, id2, fifo, enable);
+}
+
+void can_enable_irq(u32 canport, u32 irq)
+{
+ CAN_IER(canport) |= irq;
+}
+
+void can_disable_irq(u32 canport, u32 irq)
+{
+ CAN_IER(canport) &= ~irq;
+}
+
+int can_transmit(u32 canport, u32 id, bool ext, bool rtr, u8 length, u8 *data)
+{
+ int ret = 0, i;
+ u32 mailbox = 0;
+
+ if ((CAN_TSR(canport) & CAN_TSR_TME0) == CAN_TSR_TME0) {
+ ret = 0;
+ mailbox = CAN_MBOX0;
+ } else if ((CAN_TSR(canport) & CAN_TSR_TME1) == CAN_TSR_TME1) {
+ ret = 1;
+ mailbox = CAN_MBOX1;
+ } else if ((CAN_TSR(canport) & CAN_TSR_TME2) == CAN_TSR_TME2) {
+ ret = 2;
+ mailbox = CAN_MBOX2;
+ } else {
+ ret = -1;
+ }
+
+ /* Check if we have an empty mailbox. */
+ if (ret == -1)
+ return ret;
+
+ if (ext) {
+ /* Set extended ID. */
+ CAN_TIxR(canport, mailbox) |= id << CAN_TIxR_EXID_SHIFT;
+ /* Set extended ID indicator bit. */
+ CAN_TIxR(canport, mailbox) |= CAN_TIxR_IDE;
+ } else {
+ /* Set standard ID. */
+ CAN_TIxR(canport, mailbox) |= id << CAN_TIxR_STID_SHIFT;
+ /* Unset extended ID indicator bit. */
+ CAN_TIxR(canport, mailbox) &= ~CAN_TIxR_IDE;
+ }
+
+ /* Set/clear remote transmission request bit. */
+ if (rtr)
+ CAN_TIxR(canport, mailbox) |= CAN_TIxR_RTR; /* Set */
+ else
+ CAN_TIxR(canport, mailbox) &= ~CAN_TIxR_RTR; /* Clear */
+
+ /* Set the DLC. */
+ CAN_TDTxR(canport, mailbox) &= 0xFFFFFFFF0;
+ CAN_TDTxR(canport, mailbox) |= length & CAN_TDTxR_DLC_MASK;
+
+ /* Set the data. */
+ CAN_TDLxR(canport, mailbox) = 0;
+ CAN_TDHxR(canport, mailbox) = 0;
+ for (i = 0; (i < 4) && (i < length); i++)
+ CAN_TDLxR(canport, mailbox) |= (u32)data[i] << (8 * i);
+ for (i = 4; (i < 8) && (i < length); i++)
+ CAN_TDHxR(canport, mailbox) |= (u32)data[i] << (8 * (i - 4));
+
+ /* Request transmission. */
+ CAN_TIxR(canport, mailbox) |= CAN_TIxR_TXRQ;
+
+ return ret;
+}
+
+void can_fifo_release(u32 canport, u8 fifo)
+{
+ if (fifo == 0)
+ CAN_RF0R(canport) |= CAN_RF1R_RFOM1;
+ else
+ CAN_RF1R(canport) |= CAN_RF1R_RFOM1;
+}
+
+void can_receive(u32 canport, u8 fifo, bool release, u32 *id, bool *ext,
+ bool *rtr, u32 *fmi, u8 *length, u8 *data)
+{
+ u32 fifo_id = 0;
+ int i;
+
+ if (fifo == 0)
+ fifo_id = CAN_FIFO0;
+ else
+ fifo_id = CAN_FIFO1;
+
+ /* Get type of CAN ID and CAN ID. */
+ if (CAN_RIxR(canport, fifo_id) & CAN_RIxR_IDE) {
+ *ext = true;
+ /* Get extended CAN ID. */
+ *id = ((CAN_RIxR(canport, fifo_id) & CAN_RIxR_EXID_MASK) >
+ CAN_RIxR_EXID_SHIFT);
+ } else {
+ *ext = false;
+ /* Get standard CAN ID. */
+ *id = ((CAN_RIxR(canport, fifo_id) & CAN_RIxR_STID_MASK) >
+ CAN_RIxR_STID_SHIFT);
+ }
+
+ /* Get request transmit flag. */
+ if (CAN_RIxR(canport, fifo_id) & CAN_RIxR_RTR)
+ *rtr = true;
+ else
+ *rtr = false;
+
+ /* Get filter match ID. */
+ *fmi = ((CAN_RDTxR(canport, fifo_id) & CAN_RDTxR_FMI_MASK) >
+ CAN_RDTxR_FMI_SHIFT);
+
+ /* Get data length. */
+ *length = CAN_RDTxR(canport, fifo_id) & CAN_RDTxR_DLC_MASK;
+
+ /* Get data. */
+ for (i = 0; (i < 4) && (i < *length); i++)
+ data[i] = (CAN_RDLxR(canport, fifo_id) >> (8 * i)) & 0xFF;
+
+ for (i = 4; (i < 8) && (i < *length); i++)
+ data[i] = (CAN_RDHxR(canport, fifo_id) >> (8 * (i - 4))) & 0xFF;
+
+ /* Release the FIFO. */
+ if (release)
+ can_fifo_release(CAN1, 0);
+}
diff --git a/lib/ethernet.c b/lib/ethernet.c
new file mode 100644
index 0000000..c1abd03
--- /dev/null
+++ b/lib/ethernet.c
@@ -0,0 +1,53 @@
+/*
+ * This file is part of the libopenstm32 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 <libopenstm32/ethernet.h>
+
+void eth_smi_write(u8 phy, u8 reg, u16 data)
+{
+ /* Set PHY and register addresses for write access. */
+ ETH_MACMIIAR &= ~(ETH_MACMIIAR_MR | ETH_MACMIIAR_PA);
+ ETH_MACMIIAR |= (phy << 11) | (reg << 6) | ETH_MACMIIAR_MW;
+
+ /* Set register value. */
+ ETH_MACMIIDR = data;
+
+ /* Begin transaction. */
+ ETH_MACMIIAR |= ETH_MACMIIAR_MB;
+
+ /* Wait for not busy. */
+ while (ETH_MACMIIAR & ETH_MACMIIAR_MB);
+}
+
+u16 eth_smi_read(u8 phy, u8 reg)
+{
+ /* Set PHY and register addresses for write access. */
+ ETH_MACMIIAR &= ~(ETH_MACMIIAR_MR | ETH_MACMIIAR_PA |
+ ETH_MACMIIAR_MW);
+ ETH_MACMIIAR |= (phy << 11) | (reg << 6);
+
+ /* Begin transaction. */
+ ETH_MACMIIAR |= ETH_MACMIIAR_MB;
+
+ /* Wait for not busy. */
+ while (ETH_MACMIIAR & ETH_MACMIIAR_MB);
+
+ /* Set register value. */
+ return (u16)(ETH_MACMIIDR);
+}
diff --git a/lib/gpio.c b/lib/gpio.c
index abf47cf..747977d 100644
--- a/lib/gpio.c
+++ b/lib/gpio.c
@@ -106,3 +106,17 @@ void gpio_port_write(u32 gpioport, u16 data)
{
GPIO_ODR(gpioport) = data;
}
+
+void gpio_port_config_lock(u32 gpioport, u16 gpios)
+{
+ u32 reg32;
+
+ /* Special "Lock Key Writing Sequence", see datasheet. */
+ GPIO_LCKR(gpioport) = GPIO_LCKK | gpios; /* Set LCKK. */
+ GPIO_LCKR(gpioport) = ~GPIO_LCKK & gpios; /* Clear LCKK. */
+ GPIO_LCKR(gpioport) = GPIO_LCKK | gpios; /* Set LCKK. */
+ reg32 = GPIO_LCKR(gpioport); /* Read LCKK. */
+ reg32 = GPIO_LCKR(gpioport); /* Read LCKK again. */
+
+ /* If (reg32 & GPIO_LCKK) is true, the lock is now active. */
+}
diff --git a/lib/libopenstm32.ld b/lib/libopenstm32.ld
index 13efe44..75b7103 100644
--- a/lib/libopenstm32.ld
+++ b/lib/libopenstm32.ld
@@ -31,8 +31,8 @@ SECTIONS
.text : {
*(.vectors) /* Vector table */
- *(.text) /* Program code */
- *(.rodata) /* Read-only data */
+ *(.text*) /* Program code */
+ *(.rodata*) /* Read-only data */
_etext = .;
} >rom
@@ -40,16 +40,22 @@ SECTIONS
.data : {
_data = .;
- *(.data) /* Read-write initialized data */
+ *(.data*) /* Read-write initialized data */
_edata = .;
} >ram AT >rom
.bss : {
- *(.bss) /* Read-write zero initialized data */
+ *(.bss*) /* Read-write zero initialized data */
*(COMMON)
_ebss = .;
} >ram AT >rom
+ /*
+ * The .eh_frame section appears to be used for C++ exception handling.
+ * You may need to fix this if you're using C++.
+ */
+ /DISCARD/ : { *(.eh_frame) }
+
end = .;
}
diff --git a/lib/rcc.c b/lib/rcc.c
index 3da85d3..dc4dca1 100644
--- a/lib/rcc.c
+++ b/lib/rcc.c
@@ -243,7 +243,7 @@ void rcc_peripheral_reset(volatile u32 *reg, u32 reset)
void rcc_peripheral_clear_reset(volatile u32 *reg, u32 clear_reset)
{
- *reg |= clear_reset;
+ *reg &= ~clear_reset;
}
void rcc_set_sysclk_source(u32 clk)
diff --git a/lib/usart.c b/lib/usart.c
index 57b3ed5..6f3905f 100644
--- a/lib/usart.c
+++ b/lib/usart.c
@@ -40,7 +40,7 @@ void usart_set_stopbits(u32 usart, u32 stopbits)
u32 reg32;
reg32 = USART_CR2(usart);
- reg32 = (reg32 & ~((1 << 13) | (1 << 12))) | (stopbits << 12);
+ reg32 = (reg32 & ~USART_CR2_STOPBITS_MASK) | stopbits;
USART_CR2(usart) = reg32;
}
@@ -49,7 +49,7 @@ void usart_set_parity(u32 usart, u32 parity)
u32 reg32;
reg32 = USART_CR1(usart);
- reg32 = (reg32 & ~((1 << 10) | (1 << 9))) | (parity << 9);
+ reg32 = (reg32 & ~USART_PARITY_MASK) | parity;
USART_CR1(usart) = reg32;
}
@@ -58,7 +58,7 @@ void usart_set_mode(u32 usart, u32 mode)
u32 reg32;
reg32 = USART_CR1(usart);
- reg32 = (reg32 & ~((1 << 3) | (1 << 2))) | (mode << 2);
+ reg32 = (reg32 & ~USART_MODE_MASK) | mode;
USART_CR1(usart) = reg32;
}
@@ -67,7 +67,7 @@ void usart_set_flow_control(u32 usart, u32 flowcontrol)
u32 reg32;
reg32 = USART_CR3(usart);
- reg32 = (reg32 & ~((1 << 9) | (1 << 8))) | (flowcontrol << 2);
+ reg32 = (reg32 & ~USART_FLOWCONTROL_MASK) | flowcontrol;
USART_CR3(usart) = reg32;
}
@@ -84,17 +84,37 @@ void usart_disable(u32 usart)
void usart_send(u32 usart, u16 data)
{
/* Send data. */
- USART_DR(usart) = (data & 0x1ff);
+ USART_DR(usart) = (data & USART_DR_MASK);
+}
+
+u16 usart_recv(u32 usart)
+{
+ /* Receive data. */
+ return USART_DR(usart) & USART_DR_MASK;
+}
+void usart_wait_send_ready(u32 usart)
+{
/* Wait until the data has been transferred into the shift register. */
while ((USART_SR(usart) & USART_SR_TXE) == 0);
}
-u16 usart_recv(u32 usart)
+void usart_wait_recv_ready(u32 usart)
{
/* Wait until the data is ready to be received. */
while ((USART_SR(usart) & USART_SR_RXNE) == 0);
+}
- /* Receive data. */
- return USART_DR(usart) & 0x1ff;
+void usart_send_blocking(u32 usart, u16 data)
+{
+ usart_send(usart, data);
+
+ usart_wait_send_ready(usart);
+}
+
+u16 usart_recv_blocking(u32 usart)
+{
+ usart_wait_recv_ready(usart);
+
+ return usart_recv(usart);
}