summaryrefslogtreecommitdiff
path: root/src/stm
diff options
context:
space:
mode:
Diffstat (limited to 'src/stm')
-rw-r--r--src/stm/Makefile.defs4
-rw-r--r--src/stm/altos-512.ld98
-rw-r--r--src/stm/ao_arch.h23
-rw-r--r--src/stm/ao_arch_funcs.h174
-rw-r--r--src/stm/ao_dma_stm.c41
-rw-r--r--src/stm/ao_exti_stm.c2
-rw-r--r--src/stm/ao_flash_stm.c10
-rw-r--r--src/stm/ao_i2c_stm.c3
-rw-r--r--src/stm/ao_serial_stm.c6
-rw-r--r--src/stm/ao_timer.c1
-rw-r--r--src/stm/ao_usb_stm.c18
-rw-r--r--src/stm/stm32l.h82
12 files changed, 393 insertions, 69 deletions
diff --git a/src/stm/Makefile.defs b/src/stm/Makefile.defs
index 0ba86f5a..66ed4be8 100644
--- a/src/stm/Makefile.defs
+++ b/src/stm/Makefile.defs
@@ -1,4 +1,4 @@
-vpath % ../stm:../product:../drivers:../kernel:../util:../kalman:../aes:../math:..
+vpath % ../stm:../product:../drivers:../kernel:../util:../kalman:../aes:../math:../draw:../lisp:..
vpath make-altitude ../util
vpath make-kalman ../util
vpath kalman.5c ../kalman
@@ -26,7 +26,7 @@ LIBS=$(PDCLIB_LIBS_M3) -lgcc
WARN_FLAGS=-Wall -Wextra -Werror
-AO_CFLAGS=-I. -I../stm -I../kernel -I../drivers -I../math -I.. $(PDCLIB_INCLUDES)
+AO_CFLAGS=-I. -I../stm -I../kernel -I../drivers -I../math -I../draw -I../lisp -I.. $(PDCLIB_INCLUDES)
STM_CFLAGS=-std=gnu99 -mlittle-endian -mcpu=cortex-m3 -mthumb -Wcast-align \
-ffreestanding -nostdlib $(AO_CFLAGS) $(WARN_FLAGS)
diff --git a/src/stm/altos-512.ld b/src/stm/altos-512.ld
new file mode 100644
index 00000000..78c41685
--- /dev/null
+++ b/src/stm/altos-512.ld
@@ -0,0 +1,98 @@
+/*
+ * Copyright © 2017 Keith Packard <keithp@keithp.com>
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 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, write to the Free Software Foundation, Inc.,
+ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA.
+ */
+
+MEMORY {
+ rom (rx) : ORIGIN = 0x08001000, LENGTH = 508K
+ ram (!w) : ORIGIN = 0x20000000, LENGTH = 81408
+ stack (!w) : ORIGIN = 0x20013e00, LENGTH = 512
+}
+
+INCLUDE registers.ld
+
+EXTERN (stm_interrupt_vector)
+
+SECTIONS {
+ /*
+ * Rom contents
+ */
+
+ .text ORIGIN(rom) : {
+ __text_start__ = .;
+ *(.interrupt) /* Interrupt vectors */
+
+ . = ORIGIN(rom) + 0x100;
+
+
+ /* Ick. What I want is to specify the
+ * addresses of some global constants so
+ * that I can find them across versions
+ * of the application. I can't figure out
+ * how to make gnu ld do that, so instead
+ * we just load the two files that include
+ * these defines in the right order here and
+ * expect things to 'just work'. Don't change
+ * the contents of those files, ok?
+ */
+ ao_romconfig.o(.romconfig*)
+ ao_product.o(.romconfig*)
+ *(.text*) /* Executable code */
+ *(.rodata*) /* Constants */
+
+ } > rom
+
+ .ARM.exidx : {
+ *(.ARM.exidx* .gnu.linkonce.armexidx.*)
+ } > rom
+ __text_end__ = .;
+
+ /* Boot data which must live at the start of ram so that
+ * the application and bootloader share the same addresses.
+ * This must be all uninitialized data
+ */
+ .boot (NOLOAD) : {
+ __boot_start__ = .;
+ *(.boot)
+ . = ALIGN(4);
+ __boot_end__ = .;
+ } >ram
+
+ /* Data -- relocated to RAM, but written to ROM
+ */
+ .data : {
+ __data_start__ = .;
+ *(.data) /* initialized data */
+ . = ALIGN(4);
+ __data_end__ = .;
+ } >ram AT>rom
+
+ .bss : {
+ __bss_start__ = .;
+ *(.bss)
+ *(COMMON)
+ . = ALIGN(4);
+ __bss_end__ = .;
+ } >ram
+
+ PROVIDE(end = .);
+
+ PROVIDE(__stack__ = ORIGIN(stack) + LENGTH(stack));
+}
+
+ENTRY(start);
+
+
diff --git a/src/stm/ao_arch.h b/src/stm/ao_arch.h
index 0cc29376..5f033b66 100644
--- a/src/stm/ao_arch.h
+++ b/src/stm/ao_arch.h
@@ -85,10 +85,6 @@ extern const uint32_t ao_radio_cal;
#define ao_arch_task_members\
uint32_t *sp; /* saved stack pointer */
-#define ao_arch_block_interrupts() asm("cpsid i")
-#define ao_arch_release_interrupts() asm("cpsie i")
-
-
/*
* For now, we're running at a weird frequency
*/
@@ -122,10 +118,21 @@ extern const uint32_t ao_radio_cal;
#define AO_TIM91011_CLK (2 * AO_PCLK2)
#endif
-#define AO_STM_NVIC_HIGH_PRIORITY 4
-#define AO_STM_NVIC_CLOCK_PRIORITY 6
-#define AO_STM_NVIC_MED_PRIORITY 8
-#define AO_STM_NVIC_LOW_PRIORITY 10
+/* The stm32l implements only 4 bits of the priority fields */
+
+#if AO_NONMASK_INTERRUPT
+#define AO_STM_NVIC_NONMASK_PRIORITY 0x00
+
+/* Set the basepri register to this value to mask all
+ * non-maskable priorities
+ */
+#define AO_STM_NVIC_BASEPRI_MASK 0x10
+#endif
+
+#define AO_STM_NVIC_HIGH_PRIORITY 0x40
+#define AO_STM_NVIC_MED_PRIORITY 0x80
+#define AO_STM_NVIC_LOW_PRIORITY 0xC0
+#define AO_STM_NVIC_CLOCK_PRIORITY 0xf0
void ao_lcd_stm_init(void);
diff --git a/src/stm/ao_arch_funcs.h b/src/stm/ao_arch_funcs.h
index a9d0fa34..522059bc 100644
--- a/src/stm/ao_arch_funcs.h
+++ b/src/stm/ao_arch_funcs.h
@@ -202,8 +202,11 @@ ao_spi_try_get_mask(struct stm_gpio *reg, uint16_t mask, uint8_t bus, uint32_t s
#define ao_gpio_set_bits(port, bits) stm_gpio_set_bits(port, bits)
+#define ao_gpio_set_mask(port, bits, mask) stm_gpio_set_mask(port, bits, mask)
+
#define ao_gpio_clr_bits(port, bits) stm_gpio_clr_bits(port, bits);
+#define ao_gpio_get_all(port) stm_gpio_get_all(port)
#define ao_enable_output(port,bit,pin,v) do { \
ao_enable_port(port); \
@@ -211,6 +214,18 @@ ao_spi_try_get_mask(struct stm_gpio *reg, uint16_t mask, uint8_t bus, uint32_t s
stm_moder_set(port, bit, STM_MODER_OUTPUT);\
} while (0)
+#define ao_enable_output_mask(port,bits,mask) do { \
+ ao_enable_port(port); \
+ ao_gpio_set_mask(port, bits, mask); \
+ ao_set_output_mask(port, mask); \
+ } while (0)
+
+#define AO_OUTPUT_PUSH_PULL STM_OTYPER_PUSH_PULL
+#define AO_OUTPUT_OPEN_DRAIN STM_OTYPER_OPEN_DRAIN
+
+#define ao_gpio_set_output_mode(port,bit,pin,mode) \
+ stm_otyper_set(port, pin, mode)
+
#define ao_gpio_set_mode(port,bit,mode) do { \
if (mode == AO_EXTI_MODE_PULL_UP) \
stm_pupdr_set(port, bit, STM_PUPDR_PULL_UP); \
@@ -219,36 +234,73 @@ ao_spi_try_get_mask(struct stm_gpio *reg, uint16_t mask, uint8_t bus, uint32_t s
else \
stm_pupdr_set(port, bit, STM_PUPDR_NONE); \
} while (0)
-
+
+#define ao_gpio_set_mode_mask(port,mask,mode) do { \
+ if (mode == AO_EXTI_MODE_PULL_UP) \
+ stm_pupdr_set_mask(port, mask, STM_PUPDR_PULL_UP); \
+ else if (mode == AO_EXTI_MODE_PULL_DOWN) \
+ stm_pupdr_set_mask(port, mask, STM_PUPDR_PULL_DOWN); \
+ else \
+ stm_pupdr_set_mask(port, mask, STM_PUPDR_NONE); \
+ } while (0)
+
+#define ao_set_input(port, bit) do { \
+ stm_moder_set(port, bit, STM_MODER_INPUT); \
+ } while (0)
+
+#define ao_set_output(port, bit, pin, v) do { \
+ ao_gpio_set(port, bit, pin, v); \
+ stm_moder_set(port, bit, STM_MODER_OUTPUT); \
+ } while (0)
+
+#define ao_set_output_mask(port, mask) do { \
+ stm_moder_set_mask(port, mask, STM_MODER_OUTPUT); \
+ } while (0)
+
+#define ao_set_input_mask(port, mask) do { \
+ stm_moder_set_mask(port, mask, STM_MODER_INPUT); \
+ } while (0)
+
#define ao_enable_input(port,bit,mode) do { \
ao_enable_port(port); \
- stm_moder_set(port, bit, STM_MODER_INPUT); \
+ ao_set_input(port, bit); \
ao_gpio_set_mode(port, bit, mode); \
} while (0)
-#define ao_enable_cs(port,bit) do { \
+#define ao_enable_input_mask(port,mask,mode) do { \
+ ao_enable_port(port); \
+ ao_gpio_set_mode_mask(port, mask, mode); \
+ ao_set_input_mask(port, mask); \
+ } while (0)
+
+#define _ao_enable_cs(port, bit) do { \
stm_gpio_set((port), bit, 1); \
stm_moder_set((port), bit, STM_MODER_OUTPUT); \
} while (0)
+#define ao_enable_cs(port,bit) do { \
+ ao_enable_port(port); \
+ _ao_enable_cs(port, bit); \
+ } while (0)
+
#define ao_spi_init_cs(port, mask) do { \
ao_enable_port(port); \
- if ((mask) & 0x0001) ao_enable_cs(port, 0); \
- if ((mask) & 0x0002) ao_enable_cs(port, 1); \
- if ((mask) & 0x0004) ao_enable_cs(port, 2); \
- if ((mask) & 0x0008) ao_enable_cs(port, 3); \
- if ((mask) & 0x0010) ao_enable_cs(port, 4); \
- if ((mask) & 0x0020) ao_enable_cs(port, 5); \
- if ((mask) & 0x0040) ao_enable_cs(port, 6); \
- if ((mask) & 0x0080) ao_enable_cs(port, 7); \
- if ((mask) & 0x0100) ao_enable_cs(port, 8); \
- if ((mask) & 0x0200) ao_enable_cs(port, 9); \
- if ((mask) & 0x0400) ao_enable_cs(port, 10);\
- if ((mask) & 0x0800) ao_enable_cs(port, 11);\
- if ((mask) & 0x1000) ao_enable_cs(port, 12);\
- if ((mask) & 0x2000) ao_enable_cs(port, 13);\
- if ((mask) & 0x4000) ao_enable_cs(port, 14);\
- if ((mask) & 0x8000) ao_enable_cs(port, 15);\
+ if ((mask) & 0x0001) _ao_enable_cs(port, 0); \
+ if ((mask) & 0x0002) _ao_enable_cs(port, 1); \
+ if ((mask) & 0x0004) _ao_enable_cs(port, 2); \
+ if ((mask) & 0x0008) _ao_enable_cs(port, 3); \
+ if ((mask) & 0x0010) _ao_enable_cs(port, 4); \
+ if ((mask) & 0x0020) _ao_enable_cs(port, 5); \
+ if ((mask) & 0x0040) _ao_enable_cs(port, 6); \
+ if ((mask) & 0x0080) _ao_enable_cs(port, 7); \
+ if ((mask) & 0x0100) _ao_enable_cs(port, 8); \
+ if ((mask) & 0x0200) _ao_enable_cs(port, 9); \
+ if ((mask) & 0x0400) _ao_enable_cs(port, 10);\
+ if ((mask) & 0x0800) _ao_enable_cs(port, 11);\
+ if ((mask) & 0x1000) _ao_enable_cs(port, 12);\
+ if ((mask) & 0x2000) _ao_enable_cs(port, 13);\
+ if ((mask) & 0x4000) _ao_enable_cs(port, 14);\
+ if ((mask) & 0x8000) _ao_enable_cs(port, 15);\
} while (0)
/* ao_dma_stm.c
@@ -345,17 +397,43 @@ extern struct ao_stm_usart ao_stm_usart3;
typedef uint32_t ao_arch_irq_t;
+static inline void
+ao_arch_block_interrupts(void) {
+#ifdef AO_NONMASK_INTERRUPTS
+ asm("msr basepri,%0" : : "r" (AO_STM_NVIC_BASEPRI_MASK));
+#else
+ asm("cpsid i");
+#endif
+}
+
+static inline void
+ao_arch_release_interrupts(void) {
+#ifdef AO_NONMASK_INTERRUPTS
+ asm("msr basepri,%0" : : "r" (0x0));
+#else
+ asm("cpsie i");
+#endif
+}
+
static inline uint32_t
ao_arch_irqsave(void) {
- uint32_t primask;
- asm("mrs %0,primask" : "=&r" (primask));
+ uint32_t val;
+#ifdef AO_NONMASK_INTERRUPTS
+ asm("mrs %0,basepri" : "=r" (val));
+#else
+ asm("mrs %0,primask" : "=r" (val));
+#endif
ao_arch_block_interrupts();
- return primask;
+ return val;
}
static inline void
-ao_arch_irqrestore(uint32_t primask) {
- asm("msr primask,%0" : : "r" (primask));
+ao_arch_irqrestore(uint32_t basepri) {
+#ifdef AO_NONMASK_INTERRUPTS
+ asm("msr basepri,%0" : : "r" (basepri));
+#else
+ asm("msr primask,%0" : : "r" (basepri));
+#endif
}
static inline void
@@ -365,10 +443,17 @@ ao_arch_memory_barrier() {
static inline void
ao_arch_irq_check(void) {
+#ifdef AO_NONMASK_INTERRUPTS
+ uint32_t basepri;
+ asm("mrs %0,basepri" : "=r" (basepri));
+ if (basepri == 0)
+ ao_panic(AO_PANIC_IRQ);
+#else
uint32_t primask;
- asm("mrs %0,primask" : "=&r" (primask));
+ asm("mrs %0,primask" : "=r" (primask));
if ((primask & 1) == 0)
ao_panic(AO_PANIC_IRQ);
+#endif
}
#if HAS_TASK
@@ -390,7 +475,7 @@ ao_arch_init_stack(struct ao_task *task, void *start)
/* APSR */
ARM_PUSH32(sp, 0);
- /* PRIMASK with interrupts enabled */
+ /* BASEPRI with interrupts enabled */
ARM_PUSH32(sp, 0);
task->sp = sp;
@@ -404,8 +489,13 @@ static inline void ao_arch_save_regs(void) {
asm("mrs r0,apsr");
asm("push {r0}");
+#ifdef AO_NONMASK_INTERRUPTS
+ /* Save BASEPRI */
+ asm("mrs r0,basepri");
+#else
/* Save PRIMASK */
asm("mrs r0,primask");
+#endif
asm("push {r0}");
}
@@ -419,9 +509,15 @@ static inline void ao_arch_restore_stack(void) {
/* Switch stacks */
asm("mov sp, %0" : : "r" (ao_cur_task->sp) );
+#ifdef AO_NONMASK_INTERRUPTS
+ /* Restore BASEPRI */
+ asm("pop {r0}");
+ asm("msr basepri,r0");
+#else
/* Restore PRIMASK */
asm("pop {r0}");
asm("msr primask,r0");
+#endif
/* Restore APSR */
asm("pop {r0}");
@@ -463,7 +559,7 @@ static inline void ao_arch_start_scheduler(void) {
asm("mrs %0,msp" : "=&r" (sp));
asm("msr psp,%0" : : "r" (sp));
- asm("mrs %0,control" : "=&r" (control));
+ asm("mrs %0,control" : "=r" (control));
control |= (1 << 1);
asm("msr control,%0" : : "r" (control));
asm("isb");
@@ -474,12 +570,24 @@ static inline void ao_arch_start_scheduler(void) {
#endif
-#define ao_arch_wait_interrupt() do { \
- asm("\twfi\n"); \
- ao_arch_release_interrupts(); \
- asm(".global ao_idle_loc\nao_idle_loc:"); \
- ao_arch_block_interrupts(); \
- } while (0)
+static inline void
+ao_arch_wait_interrupt(void) {
+#ifdef AO_NONMASK_INTERRUPTS
+ asm(
+ "dsb\n" /* Serialize data */
+ "isb\n" /* Serialize instructions */
+ "cpsid i\n" /* Block all interrupts */
+ "msr basepri,%0\n" /* Allow all interrupts through basepri */
+ "wfi\n" /* Wait for an interrupt */
+ "cpsie i\n" /* Allow all interrupts */
+ "msr basepri,%1\n" /* Block interrupts through basepri */
+ : : "r" (0), "r" (AO_STM_NVIC_BASEPRI_MASK));
+#else
+ asm("\twfi\n");
+ ao_arch_release_interrupts();
+ ao_arch_block_interrupts();
+#endif
+}
#define ao_arch_critical(b) do { \
uint32_t __mask = ao_arch_irqsave(); \
diff --git a/src/stm/ao_dma_stm.c b/src/stm/ao_dma_stm.c
index 6d779660..962b3acc 100644
--- a/src/stm/ao_dma_stm.c
+++ b/src/stm/ao_dma_stm.c
@@ -29,7 +29,6 @@ uint8_t ao_dma_done[NUM_DMA];
static struct ao_dma_config ao_dma_config[NUM_DMA];
static uint8_t ao_dma_allocated[NUM_DMA];
static uint8_t ao_dma_mutex[NUM_DMA];
-static uint8_t ao_dma_active;
static void
ao_dma_isr(uint8_t index) {
@@ -49,12 +48,24 @@ ao_dma_isr(uint8_t index) {
void stm_dma1_channel1_isr(void) { ao_dma_isr(STM_DMA_INDEX(1)); }
void stm_dma1_channel2_isr(void) { ao_dma_isr(STM_DMA_INDEX(2)); }
+#ifdef STM_DMA1_3_STOLEN
+#define LEAVE_DMA_ON
+#else
void stm_dma1_channel3_isr(void) { ao_dma_isr(STM_DMA_INDEX(3)); }
+#endif
void stm_dma1_channel4_isr(void) { ao_dma_isr(STM_DMA_INDEX(4)); }
+#ifdef STM_DMA1_5_STOLEN
+#define LEAVE_DMA_ON
+#else
void stm_dma1_channel5_isr(void) { ao_dma_isr(STM_DMA_INDEX(5)); }
+#endif
void stm_dma1_channel6_isr(void) { ao_dma_isr(STM_DMA_INDEX(6)); }
void stm_dma1_channel7_isr(void) { ao_dma_isr(STM_DMA_INDEX(7)); }
+#ifndef LEAVE_DMA_ON
+static uint8_t ao_dma_active;
+#endif
+
void
ao_dma_set_transfer(uint8_t index,
volatile void *peripheral,
@@ -68,10 +79,12 @@ ao_dma_set_transfer(uint8_t index,
ao_dma_mutex[index] = 0xff;
} else
ao_mutex_get(&ao_dma_mutex[index]);
+#ifndef LEAVE_DMA_ON
ao_arch_critical(
if (ao_dma_active++ == 0)
stm_rcc.ahbenr |= (1 << STM_RCC_AHBENR_DMA1EN);
);
+#endif
stm_dma.channel[index].ccr = ccr | (1 << STM_DMA_CCR_TCIE);
stm_dma.channel[index].cndtr = count;
stm_dma.channel[index].cpar = peripheral;
@@ -96,10 +109,12 @@ void
ao_dma_done_transfer(uint8_t index)
{
stm_dma.channel[index].ccr &= ~(1 << STM_DMA_CCR_EN);
+#ifndef LEAVE_DMA_ON
ao_arch_critical(
if (--ao_dma_active == 0)
stm_rcc.ahbenr &= ~(1 << STM_RCC_AHBENR_DMA1EN);
);
+#endif
if (ao_dma_allocated[index])
ao_dma_mutex[index] = 0;
else
@@ -120,10 +135,12 @@ ao_dma_dump_cmd(void)
{
int i;
+#ifndef LEAVE_DMA_ON
ao_arch_critical(
if (ao_dma_active++ == 0)
stm_rcc.ahbenr |= (1 << STM_RCC_AHBENR_DMA1EN);
);
+#endif
printf ("isr %08x ifcr%08x\n", stm_dma.isr, stm_dma.ifcr);
for (i = 0; i < NUM_DMA; i++)
printf("%d: done %d allocated %d mutex %2d ccr %04x cndtr %04x cpar %08x cmar %08x isr %08x\n",
@@ -136,10 +153,12 @@ ao_dma_dump_cmd(void)
stm_dma.channel[i].cpar,
stm_dma.channel[i].cmar,
ao_dma_config[i].isr);
+#ifndef LEAVE_DMA_ON
ao_arch_critical(
if (--ao_dma_active == 0)
stm_rcc.ahbenr &= ~(1 << STM_RCC_AHBENR_DMA1EN);
);
+#endif
}
static const struct ao_cmds ao_dma_cmds[] = {
@@ -153,9 +172,27 @@ ao_dma_init(void)
{
int index;
+#ifdef LEAVE_DMA_ON
+ stm_rcc.ahbenr |= (1 << STM_RCC_AHBENR_DMA1EN);
+#endif
for (index = 0; index < STM_NUM_DMA; index++) {
+#if STM_DMA1_5_STOLEN
+ if (index == STM_DMA_INDEX(5)) {
+ ao_dma_allocated[index] = 1;
+ ao_dma_mutex[index] = 0xff;
+ continue;
+ }
+#endif
+#if STM_DMA1_3_STOLEN
+ if (index == STM_DMA_INDEX(3)) {
+ ao_dma_allocated[index] = 1;
+ ao_dma_mutex[index] = 0xff;
+ continue;
+ }
+#endif
stm_nvic_set_enable(STM_ISR_DMA1_CHANNEL1_POS + index);
- stm_nvic_set_priority(STM_ISR_DMA1_CHANNEL1_POS + index, 4);
+ stm_nvic_set_priority(STM_ISR_DMA1_CHANNEL1_POS + index,
+ AO_STM_NVIC_MED_PRIORITY);
ao_dma_allocated[index] = 0;
ao_dma_mutex[index] = 0;
}
diff --git a/src/stm/ao_exti_stm.c b/src/stm/ao_exti_stm.c
index 3e0b3e5c..2491b609 100644
--- a/src/stm/ao_exti_stm.c
+++ b/src/stm/ao_exti_stm.c
@@ -123,7 +123,7 @@ ao_exti_set_mode(struct stm_gpio *gpio, uint8_t pin, uint8_t mode) {
(void) gpio;
uint32_t mask = 1 << pin;
-
+
if (mode & AO_EXTI_MODE_RISING)
stm_exti.rtsr |= mask;
else
diff --git a/src/stm/ao_flash_stm.c b/src/stm/ao_flash_stm.c
index c1648421..38618bbe 100644
--- a/src/stm/ao_flash_stm.c
+++ b/src/stm/ao_flash_stm.c
@@ -74,11 +74,10 @@ static void __attribute__ ((section(".ramtext"),noinline))
_ao_flash_erase_page(uint32_t *page)
{
stm_flash.pecr |= (1 << STM_FLASH_PECR_ERASE) | (1 << STM_FLASH_PECR_PROG);
-
+
*page = 0x00000000;
- while (stm_flash.sr & (1 << STM_FLASH_SR_BSY))
- ;
+ ao_flash_wait_bsy();
}
void
@@ -101,9 +100,8 @@ _ao_flash_half_page(uint32_t *dst, uint32_t *src)
stm_flash.pecr |= (1 << STM_FLASH_PECR_FPRG);
stm_flash.pecr |= (1 << STM_FLASH_PECR_PROG);
-
- while (stm_flash.sr & (1 << STM_FLASH_SR_BSY))
- ;
+
+ ao_flash_wait_bsy();
for (i = 0; i < 32; i++) {
*dst++ = *src++;
diff --git a/src/stm/ao_i2c_stm.c b/src/stm/ao_i2c_stm.c
index 29a8f173..59cad495 100644
--- a/src/stm/ao_i2c_stm.c
+++ b/src/stm/ao_i2c_stm.c
@@ -75,6 +75,9 @@ uint8_t ao_i2c_mutex[STM_NUM_I2C];
#if AO_PCLK1 == 16000000
# define AO_STM_I2C_CR2_FREQ STM_I2C_CR2_FREQ_16_MHZ
#endif
+#if AO_PCLK1 == 24000000
+# define AO_STM_I2C_CR2_FREQ STM_I2C_CR2_FREQ_24_MHZ
+#endif
#if AO_PCLK1 == 32000000
# define AO_STM_I2C_CR2_FREQ STM_I2C_CR2_FREQ_32_MHZ
#endif
diff --git a/src/stm/ao_serial_stm.c b/src/stm/ao_serial_stm.c
index db0be992..c625471e 100644
--- a/src/stm/ao_serial_stm.c
+++ b/src/stm/ao_serial_stm.c
@@ -444,7 +444,7 @@ ao_serial_init(void)
ao_usart_init(&ao_stm_usart1);
stm_nvic_set_enable(STM_ISR_USART1_POS);
- stm_nvic_set_priority(STM_ISR_USART1_POS, 4);
+ stm_nvic_set_priority(STM_ISR_USART1_POS, AO_STM_NVIC_MED_PRIORITY);
#if USE_SERIAL_1_STDIN && !DELAY_SERIAL_1_STDIN
ao_add_stdio(_ao_serial1_pollchar,
ao_serial1_putchar,
@@ -500,7 +500,7 @@ ao_serial_init(void)
#endif
stm_nvic_set_enable(STM_ISR_USART2_POS);
- stm_nvic_set_priority(STM_ISR_USART2_POS, 4);
+ stm_nvic_set_priority(STM_ISR_USART2_POS, AO_STM_NVIC_MED_PRIORITY);
#if USE_SERIAL_2_STDIN && !DELAY_SERIAL_2_STDIN
ao_add_stdio(_ao_serial2_pollchar,
ao_serial2_putchar,
@@ -544,7 +544,7 @@ ao_serial_init(void)
ao_usart_init(&ao_stm_usart3);
stm_nvic_set_enable(STM_ISR_USART3_POS);
- stm_nvic_set_priority(STM_ISR_USART3_POS, 4);
+ stm_nvic_set_priority(STM_ISR_USART3_POS, AO_STM_NVIC_MED_PRIORITY);
#if USE_SERIAL_3_STDIN && !DELAY_SERIAL_3_STDIN
ao_add_stdio(_ao_serial3_pollchar,
ao_serial3_putchar,
diff --git a/src/stm/ao_timer.c b/src/stm/ao_timer.c
index f86a5116..1576a6c9 100644
--- a/src/stm/ao_timer.c
+++ b/src/stm/ao_timer.c
@@ -90,6 +90,7 @@ ao_timer_init(void)
stm_systick.csr = ((1 << STM_SYSTICK_CSR_ENABLE) |
(1 << STM_SYSTICK_CSR_TICKINT) |
(STM_SYSTICK_CSR_CLKSOURCE_HCLK_8 << STM_SYSTICK_CSR_CLKSOURCE));
+ stm_nvic.shpr15_12 |= AO_STM_NVIC_CLOCK_PRIORITY << 24;
}
#endif
diff --git a/src/stm/ao_usb_stm.c b/src/stm/ao_usb_stm.c
index 9d72844e..33e0617c 100644
--- a/src/stm/ao_usb_stm.c
+++ b/src/stm/ao_usb_stm.c
@@ -1015,7 +1015,7 @@ ao_usb_enable(void)
ao_arch_block_interrupts();
/* Route interrupts */
- stm_nvic_set_priority(STM_ISR_USB_LP_POS, 3);
+ stm_nvic_set_priority(STM_ISR_USB_LP_POS, AO_STM_NVIC_LOW_PRIORITY);
stm_nvic_set_enable(STM_ISR_USB_LP_POS);
ao_usb_configuration = 0;
@@ -1109,7 +1109,7 @@ struct ao_usb_dbg {
int line;
char *msg;
uint32_t value;
- uint32_t primask;
+ uint32_t prival;
#if TX_DBG
uint16_t in_count;
uint32_t in_epr;
@@ -1125,19 +1125,23 @@ struct ao_usb_dbg {
#endif
};
-#define NUM_USB_DBG 128
+#define NUM_USB_DBG 16
-static struct ao_usb_dbg dbg[128];
+static struct ao_usb_dbg dbg[NUM_USB_DBG];
static int dbg_i;
static void _dbg(int line, char *msg, uint32_t value)
{
- uint32_t primask;
+ uint32_t prival;
dbg[dbg_i].line = line;
dbg[dbg_i].msg = msg;
dbg[dbg_i].value = value;
- asm("mrs %0,primask" : "=&r" (primask));
- dbg[dbg_i].primask = primask;
+#if AO_NONMASK_INTERRUPT
+ asm("mrs %0,basepri" : "=&r" (prival));
+#else
+ asm("mrs %0,primask" : "=&r" (prival));
+#endif
+ dbg[dbg_i].prival = prival;
#if TX_DBG
dbg[dbg_i].in_count = in_count;
dbg[dbg_i].in_epr = stm_usb.epr[AO_USB_IN_EPR];
diff --git a/src/stm/stm32l.h b/src/stm/stm32l.h
index be1e1d65..201f4f36 100644
--- a/src/stm/stm32l.h
+++ b/src/stm/stm32l.h
@@ -52,7 +52,32 @@ stm_moder_set(struct stm_gpio *gpio, int pin, vuint32_t value) {
~(STM_MODER_MASK << STM_MODER_SHIFT(pin))) |
value << STM_MODER_SHIFT(pin));
}
-
+
+static inline uint32_t
+stm_spread_mask(uint16_t mask) {
+ uint32_t m = mask;
+
+ /* 0000000000000000mmmmmmmmmmmmmmmm */
+ m = (m & 0xff) | ((m & 0xff00) << 8);
+ /* 00000000mmmmmmmm00000000mmmmmmmm */
+ m = (m & 0x000f000f) | ((m & 0x00f000f0) << 4);
+ /* 0000mmmm0000mmmm0000mmmm0000mmmm */
+ m = (m & 0x03030303) | ((m & 0x0c0c0c0c) << 2);
+ /* 00mm00mm00mm00mm00mm00mm00mm00mm */
+ m = (m & 0x11111111) | ((m & 0x22222222) << 2);
+ /* 0m0m0m0m0m0m0m0m0m0m0m0m0m0m0m0m */
+ return m;
+}
+
+static inline void
+stm_moder_set_mask(struct stm_gpio *gpio, uint16_t mask, uint32_t value) {
+ uint32_t bits32 = stm_spread_mask(mask);
+ uint32_t mask32 = 3 * bits32;
+ uint32_t value32 = (value & 3) * bits32;
+
+ gpio->moder = ((gpio->moder & ~mask32) | value32);
+}
+
static inline uint32_t
stm_moder_get(struct stm_gpio *gpio, int pin) {
return (gpio->moder >> STM_MODER_SHIFT(pin)) & STM_MODER_MASK;
@@ -69,7 +94,7 @@ stm_otyper_set(struct stm_gpio *gpio, int pin, vuint32_t value) {
~(STM_OTYPER_MASK << STM_OTYPER_SHIFT(pin))) |
value << STM_OTYPER_SHIFT(pin));
}
-
+
static inline uint32_t
stm_otyper_get(struct stm_gpio *gpio, int pin) {
return (gpio->otyper >> STM_OTYPER_SHIFT(pin)) & STM_OTYPER_MASK;
@@ -83,12 +108,21 @@ stm_otyper_get(struct stm_gpio *gpio, int pin) {
#define STM_OSPEEDR_40MHz 3
static inline void
-stm_ospeedr_set(struct stm_gpio *gpio, int pin, vuint32_t value) {
+stm_ospeedr_set(struct stm_gpio *gpio, int pin, uint32_t value) {
gpio->ospeedr = ((gpio->ospeedr &
~(STM_OSPEEDR_MASK << STM_OSPEEDR_SHIFT(pin))) |
value << STM_OSPEEDR_SHIFT(pin));
}
-
+
+static inline void
+stm_ospeedr_set_mask(struct stm_gpio *gpio, uint16_t mask, uint32_t value) {
+ uint32_t bits32 = stm_spread_mask(mask);
+ uint32_t mask32 = 3 * bits32;
+ uint32_t value32 = (value & 3) * bits32;
+
+ gpio->ospeedr = ((gpio->ospeedr & ~mask32) | value32);
+}
+
static inline uint32_t
stm_ospeedr_get(struct stm_gpio *gpio, int pin) {
return (gpio->ospeedr >> STM_OSPEEDR_SHIFT(pin)) & STM_OSPEEDR_MASK;
@@ -107,7 +141,16 @@ stm_pupdr_set(struct stm_gpio *gpio, int pin, uint32_t value) {
~(STM_PUPDR_MASK << STM_PUPDR_SHIFT(pin))) |
value << STM_PUPDR_SHIFT(pin));
}
-
+
+static inline void
+stm_pupdr_set_mask(struct stm_gpio *gpio, uint16_t mask, uint32_t value) {
+ uint32_t bits32 = stm_spread_mask(mask);
+ uint32_t mask32 = 3 * bits32;
+ uint32_t value32 = (value & 3) * bits32;
+
+ gpio->pupdr = (gpio->pupdr & ~mask32) | value32;
+}
+
static inline uint32_t
stm_pupdr_get(struct stm_gpio *gpio, int pin) {
return (gpio->pupdr >> STM_PUPDR_SHIFT(pin)) & STM_PUPDR_MASK;
@@ -168,6 +211,12 @@ stm_gpio_set(struct stm_gpio *gpio, int pin, uint8_t value) {
}
static inline void
+stm_gpio_set_mask(struct stm_gpio *gpio, uint16_t bits, uint16_t mask) {
+ /* Use the bit set/reset register to do this atomically */
+ gpio->bsrr = ((uint32_t) (~bits & mask) << 16) | ((uint32_t) (bits & mask));
+}
+
+static inline void
stm_gpio_set_bits(struct stm_gpio *gpio, uint16_t bits) {
gpio->bsrr = bits;
}
@@ -518,7 +567,7 @@ extern struct stm_rcc stm_rcc;
#define STM_RCC_CFGR_MCOPRE_DIV_4 2
#define STM_RCC_CFGR_MCOPRE_DIV_8 3
#define STM_RCC_CFGR_MCOPRE_DIV_16 4
-#define STM_RCC_CFGR_MCOPRE_DIV_MASK 7
+#define STM_RCC_CFGR_MCOPRE_MASK 7
#define STM_RCC_CFGR_MCOSEL (24)
#define STM_RCC_CFGR_MCOSEL_DISABLE 0
@@ -897,7 +946,11 @@ struct stm_nvic {
vuint32_t sc; /* 0xc10 0xe000ed10 System Control Register */
vuint32_t cc; /* 0xc14 0xe000ed14 Configuration Control Register */
- uint8_t _unusedc18[0xe00 - 0xc18];
+ vuint32_t shpr7_4; /* 0xc18 0xe000ed18 System Hander Priority Registers */
+ vuint32_t shpr11_8; /* 0xc1c */
+ vuint32_t shpr15_12; /* 0xc20 */
+
+ uint8_t _unusedc18[0xe00 - 0xc24];
vuint32_t stir; /* 0xe00 */
};
@@ -1594,6 +1647,7 @@ extern struct stm_i2c stm_i2c1, stm_i2c2;
#define STM_I2C_CR2_FREQ_4_MHZ 4
#define STM_I2C_CR2_FREQ_8_MHZ 8
#define STM_I2C_CR2_FREQ_16_MHZ 16
+#define STM_I2C_CR2_FREQ_24_MHZ 24
#define STM_I2C_CR2_FREQ_32_MHZ 32
#define STM_I2C_CR2_FREQ_MASK 0x3f
@@ -1740,6 +1794,12 @@ extern struct stm_tim234 stm_tim2, stm_tim3, stm_tim4;
#define STM_TIM234_SMCR_SMS_EXTERNAL_CLOCK 7
#define STM_TIM234_SMCR_SMS_MASK 7
+#define STM_TIM234_DIER_CC4IE 4
+#define STM_TIM234_DIER_CC3IE 3
+#define STM_TIM234_DIER_CC2IE 2
+#define STM_TIM234_DIER_CC1IE 1
+#define STM_TIM234_DIER_UIE 0
+
#define STM_TIM234_SR_CC4OF 12
#define STM_TIM234_SR_CC3OF 11
#define STM_TIM234_SR_CC2OF 10
@@ -1840,15 +1900,23 @@ extern struct stm_tim234 stm_tim2, stm_tim3, stm_tim4;
#define STM_TIM234_CCER_CC4NP 15
#define STM_TIM234_CCER_CC4P 13
+#define STM_TIM234_CCER_CC4P_ACTIVE_HIGH 0
+#define STM_TIM234_CCER_CC4P_ACTIVE_LOW 1
#define STM_TIM234_CCER_CC4E 12
#define STM_TIM234_CCER_CC3NP 11
#define STM_TIM234_CCER_CC3P 9
+#define STM_TIM234_CCER_CC3P_ACTIVE_HIGH 0
+#define STM_TIM234_CCER_CC3P_ACTIVE_LOW 1
#define STM_TIM234_CCER_CC3E 8
#define STM_TIM234_CCER_CC2NP 7
#define STM_TIM234_CCER_CC2P 5
+#define STM_TIM234_CCER_CC2P_ACTIVE_HIGH 0
+#define STM_TIM234_CCER_CC2P_ACTIVE_LOW 1
#define STM_TIM234_CCER_CC2E 4
#define STM_TIM234_CCER_CC1NP 3
#define STM_TIM234_CCER_CC1P 1
+#define STM_TIM234_CCER_CC1P_ACTIVE_HIGH 0
+#define STM_TIM234_CCER_CC1P_ACTIVE_LOW 1
#define STM_TIM234_CCER_CC1E 0
struct stm_usb {