From 522380097ea768e7474c0de8195cc0ced03904e8 Mon Sep 17 00:00:00 2001
From: NIIBE Yutaka <gniibe@fsij.org>
Date: Wed, 30 Jul 2014 12:52:48 +0900
Subject: Support Cortex-M0.

---
 example-led/sys.c | 131 +++++++++++++++++++++++++++++++++++++++++++++++++++++-
 1 file changed, 129 insertions(+), 2 deletions(-)

(limited to 'example-led')

diff --git a/example-led/sys.c b/example-led/sys.c
index 264df5e..c86a08e 100644
--- a/example-led/sys.c
+++ b/example-led/sys.c
@@ -1,5 +1,5 @@
 /*
- * sys.c - system routines for the initial page for STM32F103.
+ * sys.c - system routines for the initial page for STM32F030 / STM32F103.
  *
  * Copyright (C) 2013, 2014 Flying Stone Technology
  * Author: NIIBE Yutaka <gniibe@fsij.org>
@@ -23,7 +23,6 @@
 #define USB_LP_CAN1_RX0_IRQn	 20
 #define STM32_USB_IRQ_PRIORITY   11
 
-
 #define STM32_SW_HSI		(0 << 0)
 #define STM32_SW_PLL		(2 << 0)
 #define STM32_PLLSRC_HSI	(0 << 16)
@@ -47,10 +46,17 @@
 
 #define STM32_MCO_NOCLOCK	(0 << 24)
 
+#if MCU_STM32F0
+#define STM32_PPRE1		STM32_PPRE1_DIV1
+#define STM32_PLLSRC		STM32_PLLSRC_HSI
+#define STM32_FLASHBITS		0x00000011
+#define STM32_PLLCLKIN		(STM32_HSICLK / 2)
+#else
 #define STM32_PPRE1		STM32_PPRE1_DIV2
 #define STM32_PLLSRC		STM32_PLLSRC_HSE
 #define STM32_FLASHBITS		0x00000012
 #define STM32_PLLCLKIN		(STM32_HSECLK / 1)
+#endif
 
 #define STM32_SW		STM32_SW_PLL
 #define STM32_HPRE		STM32_HPRE_DIV1
@@ -111,6 +117,12 @@ struct RCC {
   volatile uint32_t APB1ENR;
   volatile uint32_t BDCR;
   volatile uint32_t CSR;
+#if MCU_STM32F0
+  volatile uint32_t AHBRSTR;
+  volatile uint32_t CFGR2;
+  volatile uint32_t CFGR3;
+  volatile uint32_t CR2;
+#endif
 };
 
 #define RCC_BASE		(AHBPERIPH_BASE + 0x1000)
@@ -132,6 +144,22 @@ static struct RCC *const RCC = ((struct RCC *const)RCC_BASE);
 
 #define RCC_AHBENR_CRCEN        0x0040
 
+#if MCU_STM32F0
+#define RCC_AHBRSTR_IOPARST	0x00020000
+#define RCC_AHBRSTR_IOPBRST	0x00040000
+#define RCC_AHBRSTR_IOPCRST	0x00080000
+#define RCC_AHBRSTR_IOPDRST	0x00100000
+#define RCC_AHBRSTR_IOPFRST	0x00400000
+
+#define RCC_AHBENR_IOPAEN	0x00020000
+#define RCC_AHBENR_IOPBEN	0x00040000
+#define RCC_AHBENR_IOPCEN	0x00080000
+#define RCC_AHBENR_IOPDEN	0x00100000
+#define RCC_AHBENR_IOPFEN	0x00400000
+
+#define RCC_APB2RSTR_SYSCFGRST	0x00000001
+#define RCC_APB2ENR_SYSCFGEN	0x00000001
+#else
 #define RCC_APB2RSTR_AFIORST	0x00000001
 #define RCC_APB2RSTR_IOPARST	0x00000004
 #define RCC_APB2RSTR_IOPBRST	0x00000008
@@ -143,6 +171,20 @@ static struct RCC *const RCC = ((struct RCC *const)RCC_BASE);
 #define RCC_APB2ENR_IOPBEN	0x00000008
 #define RCC_APB2ENR_IOPCEN	0x00000010
 #define RCC_APB2ENR_IOPDEN	0x00000020
+#endif
+
+#if MCU_STM32F0
+struct SYSCFG {
+  volatile uint32_t CFGR1;
+  uint32_t dummy0;
+  volatile uint32_t EXTICR[4];
+  volatile uint32_t CFGR2;
+};
+#define SYSCFG_CFGR1_MEM_MODE 0x03
+
+#define SYSCFG_BASE	(APBPERIPH_BASE + 0x00010000)
+static struct SYSCFG *const SYSCFG = ((struct SYSCFG *const) SYSCFG_BASE);
+#endif
 
 struct FLASH {
   volatile uint32_t ACR;
@@ -172,10 +214,12 @@ clock_init (void)
   while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_HSI)
     ;
 
+#if !MCU_STM32F0
   /* HSE setup */
   RCC->CR |= RCC_CR_HSEON;
   while (!(RCC->CR & RCC_CR_HSERDY))
     ;
+#endif
 
   /* PLL setup */
   RCC->CFGR |= STM32_PLLMUL | STM32_PLLXTPRE | STM32_PLLSRC;
@@ -201,9 +245,48 @@ clock_init (void)
   RCC->CFGR |= STM32_SW;
   while ((RCC->CFGR & RCC_CFGR_SWS) != (STM32_SW << 2))
     ;
+
+#if MCU_STM32F0
+  RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN;
+  RCC->APB2RSTR = RCC_APB2RSTR_SYSCFGRST;
+  RCC->APB2RSTR = 0;
+  
+  /* Use vectors on RAM */
+  SYSCFG->CFGR1 = (SYSCFG->CFGR1 & ~SYSCFG_CFGR1_MEM_MODE) | 3;
+#endif
 }
 
 
+#if MCU_STM32F0
+struct GPIO {
+  volatile uint32_t MODER;
+  volatile uint16_t OTYPER;
+  uint16_t dummy0;
+  volatile uint32_t OSPEEDR;
+  volatile uint32_t PUPDR;
+  volatile uint16_t IDR;
+  uint16_t dummy1;
+  volatile uint16_t ODR;
+  uint16_t dummy2;
+  volatile uint16_t BSRR;
+  uint16_t dummy3;
+  volatile uint32_t LCKR;
+  volatile uint32_t AFR[2];
+  volatile uint16_t BRR;
+  uint16_t dummy4;
+};
+
+#define GPIOA_BASE	(AHB2PERIPH_BASE + 0x0000)
+#define GPIOA		((struct GPIO *) GPIOA_BASE)
+#define GPIOB_BASE	(AHB2PERIPH_BASE + 0x0400)
+#define GPIOB		((struct GPIO *) GPIOB_BASE)
+#define GPIOC_BASE	(AHB2PERIPH_BASE + 0x0800)
+#define GPIOC		((struct GPIO *) GPIOC_BASE)
+#define GPIOD_BASE	(AHB2PERIPH_BASE + 0x0C00)
+#define GPIOD		((struct GPIO *) GPIOD_BASE)
+#define GPIOF_BASE	(AHB2PERIPH_BASE + 0x1400)
+#define GPIOF		((struct GPIO *) GPIOF_BASE)
+#else
 struct AFIO
 {
   volatile uint32_t EVCR;
@@ -240,6 +323,7 @@ struct GPIO {
 #define GPIOD		((struct GPIO *) GPIOD_BASE)
 #define GPIOE_BASE	(APB2PERIPH_BASE + 0x1800)
 #define GPIOE		((struct GPIO *) GPIOE_BASE)
+#endif
 
 static struct GPIO *const GPIO_LED = ((struct GPIO *const) GPIO_LED_BASE);
 #ifdef GPIO_USB_BASE
@@ -253,10 +337,29 @@ static void
 gpio_init (void)
 {
   /* Enable GPIO clock. */
+#if MCU_STM32F0
+  RCC->AHBENR |= RCC_ENR_IOP_EN;
+  RCC->AHBRSTR = RCC_RSTR_IOP_RST;
+  RCC->AHBRSTR = 0;
+#else
   RCC->APB2ENR |= RCC_ENR_IOP_EN;
   RCC->APB2RSTR = RCC_RSTR_IOP_RST;
   RCC->APB2RSTR = 0;
+#endif
+
+#if MCU_STM32F0
+  GPIO_LED->OSPEEDR = VAL_GPIO_OSPEEDR;
+  GPIO_LED->OTYPER  = VAL_GPIO_OTYPER;
+  GPIO_LED->MODER   = VAL_GPIO_MODER;
+  GPIO_LED->PUPDR   = VAL_GPIO_PUPDR;
 
+#ifdef GPIO_OTHER_BASE
+  GPIO_OTHER->OSPEEDR = VAL_GPIO_OTHER_OSPEEDR;
+  GPIO_OTHER->OTYPER  = VAL_GPIO_OTHER_OTYPER;
+  GPIO_OTHER->MODER   = VAL_GPIO_OTHER_MODER;
+  GPIO_OTHER->PUPDR   = VAL_GPIO_OTHER_PUPDR;
+#endif
+#else
 #ifdef AFIO_MAPR_SOMETHING
   AFIO->MAPR |= AFIO_MAPR_SOMETHING;
 #endif
@@ -276,6 +379,7 @@ gpio_init (void)
   GPIO_OTHER->CRH = VAL_GPIO_OTHER_CRH;
   GPIO_OTHER->CRL = VAL_GPIO_OTHER_CRL;
 #endif
+#endif
 }
 
 static void
@@ -594,6 +698,28 @@ reset (void)
    * This code may not be at the start of flash ROM, because of DFU.
    * So, we take the address from PC.
    */
+#if __ARM_ARCH_6M__
+  asm volatile ("cpsid	i\n\t"		/* Mask all interrupts. */
+		"ldr	r0, 1f\n\t"     /* r0 = RAM start */
+		"mov	r1, pc\n\t"	/* r1 = (PC + 0x0400) & ~0x03ff */
+		"mov	r2, #0x04\n\t"
+		"lsl	r2, #8\n\t"
+		"add	r1, r1, r2\n\t"
+		"sub	r2, r2, #1\n\t"
+		"bic	r1, r1, r2\n\t"
+		"mov	r2, #188\n"
+	"2:\n\t" /* Copy vectors.  It will be enabled later by clock_init.  */
+		"ldr	r3, [r1, r2]\n\t"
+		"str	r3, [r0, r2]\n\t"
+		"sub	r2, #4\n\t"
+		"bcs	2b\n\t"
+		"msr	MSP, r3\n\t"	/* Main (exception handler) stack. */
+		"ldr	r0, [r1, #4]\n\t" /* Reset handler.                */
+		"bx	r0\n\t"
+		".align	2\n"
+	"1:	.word	0x20000000"
+		: /* no output */ : /* no input */ : "memory");
+#else
   asm volatile ("cpsid	i\n\t"		/* Mask all interrupts. */
 		"ldr	r0, 1f\n\t"     /* r0 = SCR */
 		"mov	r1, pc\n\t"	/* r1 = (PC + 0x1000) & ~0x0fff */
@@ -609,6 +735,7 @@ reset (void)
 		".align	2\n"
 	"1:	.word	0xe000ed00"
 		: /* no output */ : /* no input */ : "memory");
+#endif
 
   /* Never reach here. */
   /* Artificial entry to refer FT0, FT1, and FT2.  */
-- 
cgit v1.2.3


From 5137db82902ded4cabb4667ade17d1732f73c736 Mon Sep 17 00:00:00 2001
From: NIIBE Yutaka <gniibe@fsij.org>
Date: Wed, 30 Jul 2014 16:09:39 +0900
Subject: Cortex-M0 works.

---
 chopstx.c             | 78 ++++++++++++++++++++++++++++++++++++++++++++++++---
 entry.c               | 16 +++++++++++
 example-led/Makefile  |  5 ++--
 example-led/sample.ld | 13 +++++++++
 4 files changed, 106 insertions(+), 6 deletions(-)

(limited to 'example-led')

diff --git a/chopstx.c b/chopstx.c
index 29bea71..3f27832 100644
--- a/chopstx.c
+++ b/chopstx.c
@@ -61,6 +61,7 @@
 
 #define CPU_EXCEPTION_PRIORITY_CLEAR         0
 
+#if 0
 #define CPU_EXCEPTION_PRIORITY_SVC           0x30
 
 #define CPU_EXCEPTION_PRIORITY_INHIBIT_SCHED 0x40
@@ -68,6 +69,15 @@
 #define CPU_EXCEPTION_PRIORITY_SYSTICK       CPU_EXCEPTION_PRIORITY_INTERRUPT
 #define CPU_EXCEPTION_PRIORITY_INTERRUPT     0xb0
 #define CPU_EXCEPTION_PRIORITY_PENDSV        0xc0
+#else
+#define CPU_EXCEPTION_PRIORITY_SVC           0x00
+
+#define CPU_EXCEPTION_PRIORITY_INHIBIT_SCHED 0x40
+/* ... */
+#define CPU_EXCEPTION_PRIORITY_SYSTICK       CPU_EXCEPTION_PRIORITY_INTERRUPT
+#define CPU_EXCEPTION_PRIORITY_INTERRUPT     0x80
+#define CPU_EXCEPTION_PRIORITY_PENDSV        0xc0
+#endif
 
 /**
  * chx_fatal - Fatal error point.
@@ -184,7 +194,9 @@ static volatile uint32_t *const SYST_CSR = (uint32_t *const)0xE000E010;
 static volatile uint32_t *const SYST_RVR = (uint32_t *const)0xE000E014;
 static volatile uint32_t *const SYST_CVR = (uint32_t *const)0xE000E018;
 
+#ifndef MHZ 
 #define MHZ 72
+#endif
 
 static uint32_t usec_to_ticks (uint32_t usec)
 {
@@ -214,8 +226,12 @@ chx_cpu_sched_lock (void)
 {
   if (running->prio < CHOPSTX_PRIO_INHIBIT_PREEMPTION)
     {
+#if __ARM_ARCH_6M__
+      asm volatile ("cpsid	i" : : : "memory");
+#else
       register uint32_t tmp = CPU_EXCEPTION_PRIORITY_INHIBIT_SCHED;
       asm volatile ("msr	BASEPRI, %0" : : "r" (tmp) : "memory");
+#endif
     }
 }
 
@@ -224,8 +240,12 @@ chx_cpu_sched_unlock (void)
 {
   if (running->prio < CHOPSTX_PRIO_INHIBIT_PREEMPTION)
     {
+#if __ARM_ARCH_6M__
+      asm volatile ("cpsie	i" : : : "memory");
+#else
       register uint32_t tmp = CPU_EXCEPTION_PRIORITY_CLEAR;
       asm volatile ("msr	BASEPRI, %0" : : "r" (tmp) : "memory");
+#endif
     }
 }
 
@@ -383,22 +403,42 @@ sched (void)
 		"ldr	r1, =running\n\t"
 		/* Update running.  */
 		"str	r0, [r1]\n\t"
+#if __ARM_ARCH_6M__
+		"cmp	r0, #0\n\t"
+		"beq	1f\n\t"
+#else
 		"cbz	r0, 1f\n\t"
+#endif
 		/**/
 		"add	r0, #8\n\t"
 		"ldm	r0!, {r4, r5, r6, r7}\n\t"
+#if __ARM_ARCH_6M__
+		"ldm	r0!, {r1, r2, r3}\n\t"
+		"mov	r8, r1\n\t"
+		"mov	r9, r2\n\t"
+		"mov	r10, r3\n\t"
+		"ldm	r0!, {r1, r2}\n\t"
+		"mov	r11, r1\n\t"
+		"msr	PSP, r2\n\t"
+#else
 		"ldr	r8, [r0], #4\n\t"
 		"ldr	r9, [r0], #4\n\t"
 		"ldr	r10, [r0], #4\n\t"
 		"ldr	r11, [r0], #4\n\t"
 		"ldr	r1, [r0], #4\n\t"
 		"msr	PSP, r1\n\t"
+#endif
 		"ldrb	r1, [r0, #3]\n\t" /* ->PRIO field.  */
 		"cmp	r1, #247\n\t"
 		"bhi	0f\n\t"	/* Leave interrupt disabled if >= 248 */
 		/**/
+		/* Unmask interrupts.  */
 		"mov	r0, #0\n\t"
-		"msr	BASEPRI, r0\n"	      /* Unmask interrupts.  */
+#if __ARM_ARCH_6M__
+		"cpsie	i\n"
+#else
+		"msr	BASEPRI, r0\n"
+#endif
 		/**/
 	"0:\n\t"
 		"sub	r0, #3\n\t" /* EXC_RETURN to a thread with PSP */
@@ -410,7 +450,12 @@ sched (void)
 		"mov	r0, #0\n\t"
 		"mov	r1, #0\n\t"
 		"ldr	r2, =idle\n\t"	     /* PC = idle */
+#if __ARM_ARCH_6M__
+		"mov	r3, #0x010\n\t"
+		"lsl	r3, r3, #20\n\t" /* xPSR = T-flag set (Thumb) */
+#else
 		"mov	r3, #0x01000000\n\t" /* xPSR = T-flag set (Thumb) */
+#endif
 		"push	{r0, r1, r2, r3}\n\t"
 		"mov	r0, #0\n\t"
 		"mov	r1, #0\n\t"
@@ -418,8 +463,13 @@ sched (void)
 		"mov	r3, #0\n\t"
 		"push	{r0, r1, r2, r3}\n"
 		/**/
+		/* Unmask interrupts.  */
 		"mov	r0, #0\n\t"
-		"msr	BASEPRI, r0\n\t"	      /* Unmask interrupts.  */
+#if __ARM_ARCH_6M__
+		"cpsie	i\n\t"
+#else
+		"msr	BASEPRI, r0\n\t"
+#endif
 		/**/
 		"sub	r0, #7\n\t" /* EXC_RETURN to a thread with MSP */
 		"bx	r0\n"
@@ -430,18 +480,33 @@ void __attribute__ ((naked))
 preempt (void)
 {
   register struct chx_thread *tp asm ("r0");
-
   tp = (struct chx_thread *)CPU_EXCEPTION_PRIORITY_INHIBIT_SCHED;
-  asm ("msr	BASEPRI, r0\n\t"
+
+  asm (
+#if __ARM_ARCH_6M__
+       "cpsid	i\n\t"
+#else
+       "msr	BASEPRI, r0\n\t"
+#endif
        "ldr	r1, =running\n\t"
        "ldr	r0, [r1]\n\t"
+#if __ARM_ARCH_6M__
+       "cmp	r0, #0\n\t"
+       "bne	0f\n\t"
+#else
        "cbnz	r0, 0f\n\t"
+#endif
        /* It's idle which was preempted.  Discard saved registers on stack.  */
        "ldr	r1, =__main_stack_end__\n\t"
        "msr	MSP, r1\n\t"
        "b	sched\n"
   "0:\n\t"
+#if __ARM_ARCH_6M__
+       "add	r1, r0, #4\n\t"
+       "add	r1, #4\n\t"
+#else
        "add	r1, r0, #8\n\t"
+#endif
        /* Save registers onto CHX_THREAD struct.  */
        "stm	r1!, {r4, r5, r6, r7}\n\t"
        "mov	r2, r8\n\t"
@@ -494,7 +559,12 @@ svc (void)
 
   asm ("ldr	r1, =running\n\t"
        "ldr	r0, [r1]\n\t"
+#if __ARM_ARCH_6M__
+       "add	r1, r0, #4\n\t"
+       "add	r1, #4\n\t"
+#else
        "add	r1, r0, #8\n\t"
+#endif
        /* Save registers onto CHX_THREAD struct.  */
        "stm	r1!, {r4, r5, r6, r7}\n\t"
        "mov	r2, r8\n\t"
diff --git a/entry.c b/entry.c
index 1a8e944..0036a3a 100644
--- a/entry.c
+++ b/entry.c
@@ -379,9 +379,22 @@ static void nmi (void)
   for (;;);
 }
 
+extern void svc (void);
+
 static void hard_fault (void)
 {
+#if 1
+  register uint32_t primask;
+
+  asm ("mrs	%0, PRIMASK" : "=r" (primask));
+
+  if (primask)
+    asm volatile ("b	svc");
+  else
+    for (;;);
+#else
   for (;;);
+#endif
 }
 
 static void mem_manage (void)
@@ -462,8 +475,11 @@ void entry (void)
 		"bl	chx_systick_init\n\t"
 		"bl	gpio_init\n\t"
 		/* Enable interrupts.  */
+#if __ARM_ARCH_6M__
+#else
 		"mov	r0, #0\n\t"
 		"msr	BASEPRI, r0\n\t"
+#endif
 		"cpsie	i\n\t"
 		/* Call main.  */
 		"mov	r1, r0\n\t"
diff --git a/example-led/Makefile b/example-led/Makefile
index 43c131a..14ff7ff 100644
--- a/example-led/Makefile
+++ b/example-led/Makefile
@@ -12,9 +12,10 @@ CC   = $(CROSS)gcc
 LD   = $(CROSS)gcc
 OBJCOPY   = $(CROSS)objcopy
 
-MCU   = cortex-m3
+# MCU   = cortex-m3
+MCU   = cortex-m0 # -save-temps
 CWARN = -Wall -Wextra -Wstrict-prototypes
-DEFS  = -DHAVE_SYS_H -DFREE_STANDING
+DEFS  = -DHAVE_SYS_H -DFREE_STANDING -DMHZ=48
 # DEFS  = -DFREE_STANDING -DHAVE_SYS_H -DBUSY_LOOP -DCHX_FLAGS_MAIN=CHOPSTX_SCHED_RR
 OPT   = -O3 -Os -g
 LIBS  =
diff --git a/example-led/sample.ld b/example-led/sample.ld
index f98d789..07761e0 100644
--- a/example-led/sample.ld
+++ b/example-led/sample.ld
@@ -9,8 +9,12 @@ __process3_stack_size__  = 0x0100; /* third thread program */
 
 MEMORY
 {
+/*
     flash0 : org = 0x08000000, len = 4k
     flash  : org = 0x08000000+0x1000, len = 60k
+*/
+    flash0 : org = 0x08000000, len = 1k
+    flash  : org = 0x08000000+0x0400, len = 60k
     ram : org = 0x20000000, len = 20k
 }
 
@@ -36,9 +40,11 @@ SECTIONS
         build/sys.o(.rodata)
 	build/sys.o(.rodata.*)
 	. = ALIGN(1024);
+/*
 	*(.sys.0)
 	*(.sys.1)
 	*(.sys.2)
+*/
     } > flash0
 
     _text = .;
@@ -78,6 +84,13 @@ SECTIONS
     _etext = .;
     _textdata = _etext;
 
+    .vectors_in_ram :
+    {
+        . = ALIGN(8);
+        __vector_ram_addr__ = .;
+	KEEP(*(.data.startup.*))
+    } > ram
+
     .process_stack :
     {
         . = ALIGN(8);
-- 
cgit v1.2.3