aboutsummaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2013-01-25 19:29:29 -0800
committerpx4dev <px4@purgatory.org>2013-01-25 19:29:29 -0800
commit24f6c6b121ea87b26a2c5cac933089be496a28b6 (patch)
treec3b8fdab88b12c72197348873caa03d22eb46b60 /nuttx/arch
parent0bc836ae1d90b1805940ec8ae271639f0074a792 (diff)
parentbeb45222985f1eb9fbe21b22b95c30ab8ca5bbac (diff)
downloadpx4-firmware-24f6c6b121ea87b26a2c5cac933089be496a28b6.tar.gz
px4-firmware-24f6c6b121ea87b26a2c5cac933089be496a28b6.tar.bz2
px4-firmware-24f6c6b121ea87b26a2c5cac933089be496a28b6.zip
Merge branch 'master' into px4io-i2c
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/Kconfig125
-rw-r--r--nuttx/arch/arm/Kconfig19
-rw-r--r--nuttx/arch/arm/include/armv7-m/irq.h146
-rw-r--r--nuttx/arch/arm/include/armv7-m/irq_cmnvector.h6
-rw-r--r--nuttx/arch/arm/include/armv7-m/irq_lazyfpu.h6
-rw-r--r--nuttx/arch/arm/include/stm32/chip.h48
-rw-r--r--nuttx/arch/arm/include/types.h6
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_assert.c7
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_exception.S11
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_hardfault.c24
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_initialstate.c12
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_schedulesigaction.c18
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_sigdeliver.c10
-rw-r--r--nuttx/arch/arm/src/stm32/Kconfig19
-rw-r--r--nuttx/arch/arm/src/stm32/chip.h2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32.h6
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_irq.c48
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_serial.c27
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_vectors.S17
19 files changed, 456 insertions, 101 deletions
diff --git a/nuttx/arch/Kconfig b/nuttx/arch/Kconfig
index d43137adb..c0f235c5d 100644
--- a/nuttx/arch/Kconfig
+++ b/nuttx/arch/Kconfig
@@ -103,6 +103,131 @@ source arch/x86/Kconfig
source arch/z16/Kconfig
source arch/z80/Kconfig
+comment "External Memory Configuration"
+
+config ARCH_HAVE_EXTNAND
+ bool
+
+config ARCH_HAVE_EXTNOR
+ bool
+
+config ARCH_HAVE_EXTDRAM
+ bool
+
+config ARCH_HAVE_EXTSRAM0
+ bool
+
+config ARCH_HAVE_EXTSRAM1
+ bool
+
+config ARCH_EXTNAND
+ bool "Configure external NAND"
+ default n
+ depends on ARCH_HAVE_EXTNAND
+ ---help---
+ Configure external NAND memory and, if applicable, map then external
+ NAND into the memory map.
+
+if ARCH_EXTNAND
+
+config ARCH_EXTNANDSIZE
+ int "External NAND size"
+ default 0
+ ---help---
+ Size of the external NAND in bytes.
+
+endif
+
+config ARCH_EXTNOR
+ bool "Configure external NOR memory"
+ default n
+ depends on ARCH_HAVE_EXTNOR
+ ---help---
+ Configure external NOR memory and, if applicable, map then external
+ NOR into the memory map.
+
+if ARCH_EXTNOR
+
+config ARCH_EXTNORSIZE
+ int "External NOR size"
+ default 0
+ ---help---
+ Size of the external NOR in bytes.
+
+endif
+
+config ARCH_EXTDRAM
+ bool "Configure external DRAM"
+ default n
+ depends on ARCH_HAVE_EXTDRAM
+ ---help---
+ Configure external DRAM memory and, if applicable, map then external
+ DRAM into the memory map.
+
+if ARCH_EXTDRAM
+
+config ARCH_EXTDRAMSIZE
+ int "External SDRAM size"
+ default 0
+ ---help---
+ Size of the external SDRAM in bytes.
+
+config ARCH_EXTDRAMHEAP
+ bool "Add external SDRAM to the heap"
+ default y
+ ---help---
+ Add the external SDRAM into the heap.
+
+endif
+
+config ARCH_EXTSRAM0
+ bool "Configure external SRAM (Bank 0)"
+ default n
+ depends on ARCH_HAVE_EXTSRAM0
+ ---help---
+ Configure external SRAM Bank 0 memory and, if applicable, map then
+ external SRAM Bank 0 into the memory map.
+
+if ARCH_EXTSRAM0
+
+config ARCH_EXTSRAM0SIZE
+ int "External SRAM size"
+ default 0
+ ---help---
+ Size of the external SRAM Bank 0 in bytes.
+
+config ARCH_EXTSRAM0HEAP
+ bool "Add external SRAM (Bank 0) to the heap"
+ default y
+ ---help---
+ Add external SRAM Bank 0 into the heap.
+
+endif
+
+config ARCH_EXTSRAM1
+ bool "Configure external SRAM (Bank 1)"
+ default n
+ depends on ARCH_HAVE_EXTSRAM1
+ ---help---
+ Configure external SRAM Bank 1 memory and, if applicable, map then
+ external SRAM Bank 1 into the memory map.
+
+if ARCH_EXTSRAM1
+
+config ARCH_EXTSRAM1SIZE
+ int "External SRAM1 size"
+ default 0
+ ---help---
+ Size of the external SRAM Bank 1 in bytes.
+
+config ARCH_EXTSRAM1HEAP
+ bool "Add external SRAM (Bank 1) to the heap"
+ default y
+ ---help---
+ Add external SRAM Bank 1 into the heap.
+
+endif
+
comment "Architecture Options"
config ARCH_NOINTC
diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig
index 36343e319..5709f890f 100644
--- a/nuttx/arch/arm/Kconfig
+++ b/nuttx/arch/arm/Kconfig
@@ -46,7 +46,6 @@ config ARCH_CHIP_KINETIS
bool "Freescale Kinetis"
select ARCH_CORTEXM4
select ARCH_HAVE_MPU
- select ARCH_IRQPRIO
select ARCH_HAVE_RAMFUNCS
select ARCH_RAMFUNCS
---help---
@@ -55,7 +54,6 @@ config ARCH_CHIP_KINETIS
config ARCH_CHIP_LM
bool "TI Stellaris"
select ARCH_HAVE_MPU
- select ARCH_IRQPRIO
---help---
TI Stellaris LMS3 architecutres (ARM Cortex-M3)
@@ -63,7 +61,6 @@ config ARCH_CHIP_LPC17XX
bool "NXP LPC17xx"
select ARCH_CORTEXM3
select ARCH_HAVE_MPU
- select ARCH_IRQPRIO
---help---
NXP LPC17xx architectures (ARM Cortex-M3)
@@ -95,7 +92,6 @@ config ARCH_CHIP_LPC43XX
select ARCH_HAVE_CMNVECTOR
select ARMV7M_CMNVECTOR
select ARCH_HAVE_MPU
- select ARCH_IRQPRIO
---help---
NPX LPC43XX architectures (ARM Cortex-M4).
@@ -103,7 +99,6 @@ config ARCH_CHIP_SAM3U
bool "Atmel AT91SAM3U"
select ARCH_CORTEXM3
select ARCH_HAVE_MPU
- select ARCH_IRQPRIO
---help---
Atmel AT91SAM3U architectures (ARM Cortex-M3)
@@ -112,7 +107,6 @@ config ARCH_CHIP_STM32
select ARCH_HAVE_CMNVECTOR
select ARCH_HAVE_MPU
select ARCH_HAVE_I2CRESET
- select ARCH_IRQPRIO
---help---
STMicro STM32 architectures (ARM Cortex-M3/4).
@@ -136,9 +130,11 @@ config ARCH_ARM920T
config ARCH_CORTEXM3
bool
+ select ARCH_IRQPRIO
config ARCH_CORTEXM4
bool
+ select ARCH_IRQPRIO
config ARCH_FAMILY
string
@@ -162,6 +158,17 @@ config ARCH_CHIP
default "stm32" if ARCH_CHIP_STM32
default "str71x" if ARCH_CHIP_STR71X
+config ARMV7M_USEBASEPRI
+ bool "Use BASEPRI Register"
+ default n
+ depends on ARCH_CORTEXM3 || ARCH_CORTEXM4
+ ---help---
+ Use the BASEPRI register to enable and disable able interrupts. By
+ default, the PRIMASK register is used for this purpose. This
+ usually results in hardfaults that are properly handling by the
+ RTOS. Using the BASEPRI register will avoid these hardfault.
+ That is needed primarily for integration with some toolchains.
+
config ARCH_HAVE_CMNVECTOR
bool
diff --git a/nuttx/arch/arm/include/armv7-m/irq.h b/nuttx/arch/arm/include/armv7-m/irq.h
index 606b3988f..8acec4c07 100644
--- a/nuttx/arch/arm/include/armv7-m/irq.h
+++ b/nuttx/arch/arm/include/armv7-m/irq.h
@@ -60,6 +60,10 @@
# include <arch/armv7-m/irq_lazyfpu.h>
#endif
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+# include <arch/chip/chip.h>
+#endif
+
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
@@ -114,7 +118,11 @@ struct xcptcontext
*/
uint32_t saved_pc;
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ uint32_t saved_basepri;
+#else
uint32_t saved_primask;
+#endif
uint32_t saved_xpsr;
#endif
@@ -130,12 +138,75 @@ struct xcptcontext
#ifndef __ASSEMBLY__
+/* Get/set the PRIMASK register */
+
+static inline uint8_t getprimask(void) inline_function;
+static inline uint8_t getprimask(void)
+{
+ uint32_t primask;
+ __asm__ __volatile__
+ (
+ "\tmrs %0, primask\n"
+ : "=r" (primask)
+ :
+ : "memory");
+
+ return (uint8_t)primask;
+}
+
+static inline void setprimask(uint32_t primask) inline_function;
+static inline void setprimask(uint32_t primask)
+{
+ __asm__ __volatile__
+ (
+ "\tmsr primask, %0\n"
+ :
+ : "r" (primask)
+ : "memory");
+}
+
+/* Get/set the BASEPRI register. The BASEPRI register defines the minimum
+ * priority for exception processing. When BASEPRI is set to a nonzero
+ * value, it prevents the activation of all exceptions with the same or
+ * lower priority level as the BASEPRI value.
+ */
+
+static inline uint8_t getbasepri(void) inline_function;
+static inline uint8_t getbasepri(void)
+{
+ uint32_t basepri;
+
+ __asm__ __volatile__
+ (
+ "\tmrs %0, basepri\n"
+ : "=r" (basepri)
+ :
+ : "memory");
+
+ return (uint8_t)basepri;
+}
+
+static inline void setbasepri(uint32_t basepri) inline_function;
+static inline void setbasepri(uint32_t basepri)
+{
+ __asm__ __volatile__
+ (
+ "\tmsr basepri, %0\n"
+ :
+ : "r" (basepri)
+ : "memory");
+}
+
/* Disable IRQs */
static inline void irqdisable(void) inline_function;
static inline void irqdisable(void)
{
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ setbasepri(NVIC_SYSH_DISABLE_PRIORITY);
+#else
__asm__ __volatile__ ("\tcpsid i\n");
+#endif
}
/* Save the current primask state & disable IRQs */
@@ -143,6 +214,14 @@ static inline void irqdisable(void)
static inline irqstate_t irqsave(void) inline_function;
static inline irqstate_t irqsave(void)
{
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+
+ uint8_t basepri = getbasepri();
+ setbasepri(NVIC_SYSH_DISABLE_PRIORITY);
+ return (irqstate_t)basepri;
+
+#else
+
unsigned short primask;
/* Return the current value of primask register and set
@@ -158,6 +237,7 @@ static inline irqstate_t irqsave(void)
: "memory");
return primask;
+#endif
}
/* Enable IRQs */
@@ -165,14 +245,18 @@ static inline irqstate_t irqsave(void)
static inline void irqenable(void) inline_function;
static inline void irqenable(void)
{
+ setbasepri(0);
__asm__ __volatile__ ("\tcpsie i\n");
}
/* Restore saved primask state */
-static inline void irqrestore(irqstate_t primask) inline_function;
-static inline void irqrestore(irqstate_t primask)
+static inline void irqrestore(irqstate_t flags) inline_function;
+static inline void irqrestore(irqstate_t flags)
{
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ setbasepri((uint32_t)flags);
+#else
/* If bit 0 of the primask is 0, then we need to restore
* interupts.
*/
@@ -184,63 +268,9 @@ static inline void irqrestore(irqstate_t primask)
"\tcpsie i\n"
"1:\n"
:
- : "r" (primask)
- : "memory");
-}
-
-/* Get/set the primask register */
-
-static inline uint8_t getprimask(void) inline_function;
-static inline uint8_t getprimask(void)
-{
- uint32_t primask;
- __asm__ __volatile__
- (
- "\tmrs %0, primask\n"
- : "=r" (primask)
- :
- : "memory");
-
- return (uint8_t)primask;
-}
-
-static inline void setprimask(uint32_t primask) inline_function;
-static inline void setprimask(uint32_t primask)
-{
- __asm__ __volatile__
- (
- "\tmsr primask, %0\n"
- :
- : "r" (primask)
- : "memory");
-}
-
-/* Get/set the basepri register */
-
-static inline uint8_t getbasepri(void) inline_function;
-static inline uint8_t getbasepri(void)
-{
- uint32_t basepri;
-
- __asm__ __volatile__
- (
- "\tmrs %0, basepri\n"
- : "=r" (basepri)
- :
- : "memory");
-
- return (uint8_t)basepri;
-}
-
-static inline void setbasepri(uint32_t basepri) inline_function;
-static inline void setbasepri(uint32_t basepri)
-{
- __asm__ __volatile__
- (
- "\tmsr basepri, %0\n"
- :
- : "r" (basepri)
+ : "r" (flags)
: "memory");
+#endif
}
/* Get/set IPSR */
diff --git a/nuttx/arch/arm/include/armv7-m/irq_cmnvector.h b/nuttx/arch/arm/include/armv7-m/irq_cmnvector.h
index e646731eb..bc67004ed 100644
--- a/nuttx/arch/arm/include/armv7-m/irq_cmnvector.h
+++ b/nuttx/arch/arm/include/armv7-m/irq_cmnvector.h
@@ -51,7 +51,11 @@
*/
#define REG_R13 (0) /* R13 = SP at time of interrupt */
-#define REG_PRIMASK (1) /* PRIMASK */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+# define REG_BASEPRI (1) /* BASEPRI */
+#else
+# define REG_PRIMASK (1) /* PRIMASK */
+#endif
#define REG_R4 (2) /* R4 */
#define REG_R5 (3) /* R5 */
#define REG_R6 (4) /* R6 */
diff --git a/nuttx/arch/arm/include/armv7-m/irq_lazyfpu.h b/nuttx/arch/arm/include/armv7-m/irq_lazyfpu.h
index 2c3600b7f..f2380cbb6 100644
--- a/nuttx/arch/arm/include/armv7-m/irq_lazyfpu.h
+++ b/nuttx/arch/arm/include/armv7-m/irq_lazyfpu.h
@@ -51,7 +51,11 @@
*/
#define REG_R13 (0) /* R13 = SP at time of interrupt */
-#define REG_PRIMASK (1) /* PRIMASK */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+# define REG_BASEPRI (1) /* BASEPRI */
+#else
+# define REG_PRIMASK (1) /* PRIMASK */
+#endif
#define REG_R4 (2) /* R4 */
#define REG_R5 (3) /* R5 */
#define REG_R6 (4) /* R6 */
diff --git a/nuttx/arch/arm/include/stm32/chip.h b/nuttx/arch/arm/include/stm32/chip.h
index d34c2eb4f..14d92ea3d 100644
--- a/nuttx/arch/arm/include/stm32/chip.h
+++ b/nuttx/arch/arm/include/stm32/chip.h
@@ -183,9 +183,43 @@
# define STM32_NRNG 0 /* No random number generator (RNG) */
# define STM32_NDCMI 0 /* No digital camera interface (DCMI) */
+/* STM32 F103 Medium Density Family *************************************************/
+/* STM32F103RB is in the Medium-density performance line and is provided in 64 pin
+ * packages with 128K Flash, USB, CAN, 7 timers, 2 ADCs, 9 com. interfaces
+ */
+
+#elif defined(CONFIG_ARCH_CHIP_STM32F103RBT6)
+# define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# define CONFIG_STM32_MEDIUMDENSITY 1 /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
+# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_VALUELINE /* STM32F100x */
+# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */
+# undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */
+# undef CONFIG_STM32_STM32F40XX /* STM32F405xx and STM32407xx families */
+# define STM32_NFSMC 0 /* FSMC */
+# define STM32_NATIM 1 /* One advanced timer TIM1 */
+# define STM32_NGTIM 3 /* General timers TIM2,3,4 */
+# define STM32_NBTIM 0 /* Two basic timers TIM6 and TIM7 */
+# define STM32_NDMA 1 /* DMA1 */
+# define STM32_NSPI 2 /* SPI1-2 */
+# define STM32_NI2S 0 /* No I2S (?) */
+# define STM32_NUSART 3 /* USART1-3 */
+# define STM32_NI2C 2 /* I2C1-2 */
+# define STM32_NCAN 1 /* bxCAN1 */
+# define STM32_NSDIO 0 /* No SDIO */
+# define STM32_NUSBOTG 0 /* No USB OTG FS/HS */
+# define STM32_NGPIO 51 /* GPIOA-E */
+# define STM32_NADC 2 /* ADC1-2 */
+# define STM32_NDAC 0 /* No DAC */
+# define STM32_NCRC 1 /* CRC */
+# define STM32_NTHERNET 0 /* No ethernet */
+# define STM32_NRNG 0 /* No random number generator (RNG) */
+# define STM32_NDCMI 0 /* No digital camera interface (DCMI) */
+
/* STM32 F103 High Density Family ***************************************************/
-/* STM32F103RC, STM32F103RD, and STM32F103RE are all provided in 64 pin packages and differ
- * only in the available FLASH and SRAM.
+/* STM32F103RC, STM32F103RD, and STM32F103RE are all provided in 64 pin packages and
+ * differ only in the available FLASH and SRAM.
*/
#elif defined(CONFIG_ARCH_CHIP_STM32F103RET6)
@@ -658,5 +692,15 @@
# error "Unsupported STM32 chip"
#endif
+/* NVIC priority levels *************************************************************/
+
+#define NVIC_SYSH_PRIORITY_MIN 0xf0 /* All bits set in minimum priority */
+#define NVIC_SYSH_PRIORITY_DEFAULT 0x80 /* Midpoint is the default */
+#define NVIC_SYSH_PRIORITY_MAX 0x00 /* Zero is maximum priority */
+#define NVIC_SYSH_PRIORITY_STEP 0x10 /* Four bits of interrupt priority used */
+
+#define NVIC_SYSH_DISABLE_PRIORITY (NVIC_SYSH_PRIORITY_MAX + NVIC_SYSH_PRIORITY_STEP)
+#define NVIC_SYSH_SVCALL_PRIORITY NVIC_SYSH_PRIORITY_MAX
+
#endif /* __ARCH_ARM_INCLUDE_STM32_CHIP_H */
diff --git a/nuttx/arch/arm/include/types.h b/nuttx/arch/arm/include/types.h
index c06b28950..1d2ea4cfe 100644
--- a/nuttx/arch/arm/include/types.h
+++ b/nuttx/arch/arm/include/types.h
@@ -44,6 +44,8 @@
* Included Files
****************************************************************************/
+#include <nuttx/config.h>
+
/****************************************************************************
* Definitions
****************************************************************************/
@@ -87,7 +89,11 @@ typedef unsigned int _uintptr_t;
*/
#ifdef __thumb2__
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+typedef unsigned char irqstate_t;
+#else
typedef unsigned short irqstate_t;
+#endif
#else /* __thumb2__ */
typedef unsigned int irqstate_t;
#endif /* __thumb2__ */
diff --git a/nuttx/arch/arm/src/armv7-m/up_assert.c b/nuttx/arch/arm/src/armv7-m/up_assert.c
index 282ff6a57..ab30b09f3 100644
--- a/nuttx/arch/arm/src/armv7-m/up_assert.c
+++ b/nuttx/arch/arm/src/armv7-m/up_assert.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_assert.c
*
- * Copyright (C) 2009-2010, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -147,8 +147,13 @@ static inline void up_registerdump(void)
current_regs[REG_R10], current_regs[REG_R11],
current_regs[REG_R12], current_regs[REG_R13],
current_regs[REG_R14], current_regs[REG_R15]);
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ lldbg("xPSR: %08x BASEPRI: %08x\n",
+ current_regs[REG_XPSR], current_regs[REG_BASEPRI]);
+#else
lldbg("xPSR: %08x PRIMASK: %08x\n",
current_regs[REG_XPSR], current_regs[REG_PRIMASK]);
+#endif
}
}
#else
diff --git a/nuttx/arch/arm/src/armv7-m/up_exception.S b/nuttx/arch/arm/src/armv7-m/up_exception.S
index c9f216027..17344db41 100644
--- a/nuttx/arch/arm/src/armv7-m/up_exception.S
+++ b/nuttx/arch/arm/src/armv7-m/up_exception.S
@@ -2,7 +2,7 @@
* arch/arm/src/stm32/up_exception.S
* arch/arm/src/chip/up_exception.S
*
- * Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2013 Gregory Nutt. All rights reserved.
* Copyright (C) 2012 Michael Smith. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
@@ -100,7 +100,11 @@ exception_common:
mov r2, r1 /* R2=Copy of the main/process stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */
/* (ignoring the xPSR[9] alignment bit) */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ mrs r3, basepri /* R3=Current BASEPRI setting */
+#else
mrs r3, primask /* R3=Current PRIMASK setting */
+#endif
#ifdef CONFIG_ARCH_FPU
@@ -205,7 +209,12 @@ exception_common:
/* Restore the interrupt state */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ msr basepri, r3 /* Restore interrupts priority masking*/
+ cpsie i /* Re-enable interrupts */
+#else
msr primask, r3 /* Restore interrupts */
+#endif
/* Always return with R14 containing the special value that will: (1)
* return to thread mode, and (2) select the correct stack.
diff --git a/nuttx/arch/arm/src/armv7-m/up_hardfault.c b/nuttx/arch/arm/src/armv7-m/up_hardfault.c
index c30015ad2..fa750b525 100644
--- a/nuttx/arch/arm/src/armv7-m/up_hardfault.c
+++ b/nuttx/arch/arm/src/armv7-m/up_hardfault.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_hardfault.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -55,7 +55,9 @@
* Pre-processor Definitions
****************************************************************************/
-/* Debug output from this file may interfere with context switching! */
+/* If CONFIG_ARMV7M_USEBASEPRI=n, then debug output from this file may
+ * interfere with context switching!
+ */
#ifdef CONFIG_DEBUG_HARDFAULT
# define hfdbg(format, arg...) lldbg(format, ##arg)
@@ -92,18 +94,19 @@
int up_hardfault(int irq, FAR void *context)
{
+#if defined(CONFIG_DEBUG_HARDFAULT) || !defined(CONFIG_ARMV7M_USEBASEPRI)
uint32_t *regs = (uint32_t*)context;
- uint16_t *pc;
- uint16_t insn;
+#endif
/* Get the value of the program counter where the fault occurred */
- pc = (uint16_t*)regs[REG_PC] - 1;
+#ifndef CONFIG_ARMV7M_USEBASEPRI
+ uint16_t *pc = (uint16_t*)regs[REG_PC] - 1;
if ((void*)pc >= (void*)&_stext && (void*)pc < (void*)&_etext)
{
/* Fetch the instruction that caused the Hard fault */
- insn = *pc;
+ uint16_t insn = *pc;
hfdbg(" PC: %p INSN: %04x\n", pc, insn);
/* If this was the instruction 'svc 0', then forward processing
@@ -116,6 +119,7 @@ int up_hardfault(int irq, FAR void *context)
return up_svcall(irq, context);
}
}
+#endif
/* Dump some hard fault info */
@@ -133,7 +137,13 @@ int up_hardfault(int irq, FAR void *context)
hfdbg(" R8: %08x %08x %08x %08x %08x %08x %08x %08x\n",
regs[REG_R8], regs[REG_R9], regs[REG_R10], regs[REG_R11],
regs[REG_R12], regs[REG_R13], regs[REG_R14], regs[REG_R15]);
- hfdbg(" PSR=%08x\n", regs[REG_XPSR]);
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ hfdbg(" xPSR: %08x BASEPRI: %08x (saved)\n",
+ current_regs[REG_XPSR], current_regs[REG_BASEPRI]);
+#else
+ hfdbg(" xPSR: %08x PRIMASK: %08x (saved)\n",
+ current_regs[REG_XPSR], current_regs[REG_PRIMASK]);
+#endif
(void)irqsave();
lldbg("PANIC!!! Hard fault: %08x\n", getreg32(NVIC_HFAULTS));
diff --git a/nuttx/arch/arm/src/armv7-m/up_initialstate.c b/nuttx/arch/arm/src/armv7-m/up_initialstate.c
index 52a2682a0..4af553f25 100644
--- a/nuttx/arch/arm/src/armv7-m/up_initialstate.c
+++ b/nuttx/arch/arm/src/armv7-m/up_initialstate.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_initialstate.c
*
- * Copyright (C) 2009, 2011-2 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -156,7 +156,7 @@ void up_initial_state(_TCB *tcb)
xcp->regs[REG_FPSCR] = 0; // XXX initial FPSCR should be configurable
xcp->regs[REG_FPReserved] = 0;
-#endif
+#endif /* CONFIG_ARCH_FPU */
#ifdef CONFIG_NUTTX_KERNEL
if ((tcb->flags & TCB_FLAG_TTYPE_MASK) != TCB_FLAG_TTYPE_KERNEL)
@@ -165,7 +165,7 @@ void up_initial_state(_TCB *tcb)
xcp->regs[REG_EXC_RETURN] = EXC_RETURN_PROCESS_STACK;
}
-#endif
+#endif /* CONFIG_NUTTX_KERNEL */
#else /* CONFIG_ARMV7M_CMNVECTOR */
@@ -189,12 +189,16 @@ void up_initial_state(_TCB *tcb)
xcp->regs[REG_EXC_RETURN] = EXC_RETURN_UNPRIVTHR;
}
-#endif
+#endif /* CONFIG_NUTTX_KERNEL */
#endif /* CONFIG_ARMV7M_CMNVECTOR */
/* Enable or disable interrupts, based on user configuration */
#ifdef CONFIG_SUPPRESS_INTERRUPTS
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ xcp->regs[REG_BASEPRI] = NVIC_SYSH_DISABLE_PRIORITY;
+#else
xcp->regs[REG_PRIMASK] = 1;
#endif
+#endif /* CONFIG_SUPPRESS_INTERRUPTS */
}
diff --git a/nuttx/arch/arm/src/armv7-m/up_schedulesigaction.c b/nuttx/arch/arm/src/armv7-m/up_schedulesigaction.c
index 9e6dbd14b..9221a69a2 100644
--- a/nuttx/arch/arm/src/armv7-m/up_schedulesigaction.c
+++ b/nuttx/arch/arm/src/armv7-m/up_schedulesigaction.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_schedulesigaction.c
*
- * Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -155,7 +155,11 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
tcb->xcp.sigdeliver = sigdeliver;
tcb->xcp.saved_pc = current_regs[REG_PC];
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ tcb->xcp.saved_basepri = current_regs[REG_BASEPRI];
+#else
tcb->xcp.saved_primask = current_regs[REG_PRIMASK];
+#endif
tcb->xcp.saved_xpsr = current_regs[REG_XPSR];
/* Then set up to vector to the trampoline with interrupts
@@ -163,7 +167,11 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
*/
current_regs[REG_PC] = (uint32_t)up_sigdeliver;
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ current_regs[REG_BASEPRI] = NVIC_SYSH_DISABLE_PRIORITY;
+#else
current_regs[REG_PRIMASK] = 1;
+#endif
current_regs[REG_XPSR] = ARMV7M_XPSR_T;
/* And make sure that the saved context in the TCB
@@ -189,7 +197,11 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
tcb->xcp.sigdeliver = sigdeliver;
tcb->xcp.saved_pc = tcb->xcp.regs[REG_PC];
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ tcb->xcp.saved_basepri = tcb->xcp.regs[REG_BASEPRI];
+#else
tcb->xcp.saved_primask = tcb->xcp.regs[REG_PRIMASK];
+#endif
tcb->xcp.saved_xpsr = tcb->xcp.regs[REG_XPSR];
/* Then set up to vector to the trampoline with interrupts
@@ -197,7 +209,11 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
*/
tcb->xcp.regs[REG_PC] = (uint32_t)up_sigdeliver;
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ tcb->xcp.regs[REG_BASEPRI] = NVIC_SYSH_DISABLE_PRIORITY;
+#else
tcb->xcp.regs[REG_PRIMASK] = 1;
+#endif
tcb->xcp.regs[REG_XPSR] = ARMV7M_XPSR_T;
}
diff --git a/nuttx/arch/arm/src/armv7-m/up_sigdeliver.c b/nuttx/arch/arm/src/armv7-m/up_sigdeliver.c
index 38673c41d..654214b39 100644
--- a/nuttx/arch/arm/src/armv7-m/up_sigdeliver.c
+++ b/nuttx/arch/arm/src/armv7-m/up_sigdeliver.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_sigdeliver.c
*
- * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -102,7 +102,11 @@ void up_sigdeliver(void)
up_copystate(regs, rtcb->xcp.regs);
regs[REG_PC] = rtcb->xcp.saved_pc;
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ regs[REG_BASEPRI] = rtcb->xcp.saved_basepri;
+#else
regs[REG_PRIMASK] = rtcb->xcp.saved_primask;
+#endif
regs[REG_XPSR] = rtcb->xcp.saved_xpsr;
/* Get a local copy of the sigdeliver function pointer. We do this so that
@@ -115,7 +119,11 @@ void up_sigdeliver(void)
/* Then restore the task interrupt state */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ irqrestore((uint8_t)regs[REG_BASEPRI]);
+#else
irqrestore((uint16_t)regs[REG_PRIMASK]);
+#endif
/* Deliver the signals */
diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig
index 99dde3209..41724be2d 100644
--- a/nuttx/arch/arm/src/stm32/Kconfig
+++ b/nuttx/arch/arm/src/stm32/Kconfig
@@ -457,32 +457,38 @@ config STM32_USART1
bool "USART1"
default n
select ARCH_HAVE_USART1
+ select STM32_USART
config STM32_USART2
bool "USART2"
default n
select ARCH_HAVE_USART2
+ select STM32_USART
config STM32_USART3
bool "USART3"
default n
select ARCH_HAVE_USART3
+ select STM32_USART
config STM32_UART4
bool "UART4"
default n
select ARCH_HAVE_UART4
+ select STM32_USART
config STM32_UART5
bool "UART5"
default n
select ARCH_HAVE_UART5
+ select STM32_USART
config STM32_USART6
bool "USART6"
default n
depends on STM32_STM32F20XX || STM32_STM32F40XX
select ARCH_HAVE_USART6
+ select STM32_USART
config STM32_USB
bool "USB Device"
@@ -1804,8 +1810,11 @@ config STM32_TIM14_DAC2
endchoice
+config STM32_USART
+ bool
+
menu "U[S]ART Configuration"
- depends on STM32_USART1 || STM32_USART2 || STM32_USART3 || STM32_USART4 || STM32_USART5 || STM32_USART6
+ depends on STM32_USART
config USART1_RS485
bool "RS-485 on USART1"
@@ -1968,6 +1977,14 @@ config SERIAL_TERMIOS
endmenu
+config STM32_USART_SINGLEWIRE
+ bool "Single Wire Support"
+ default n
+ depends on STM32_USART
+ ---help---
+ Enable single wire UART support. The option enables support for the
+ TIOCSSINGLEWIRE ioctl in the STM32 serial driver.
+
menu "SPI Configuration"
depends on STM32_SPI
diff --git a/nuttx/arch/arm/src/stm32/chip.h b/nuttx/arch/arm/src/stm32/chip.h
index 3fac597ef..41a87feae 100644
--- a/nuttx/arch/arm/src/stm32/chip.h
+++ b/nuttx/arch/arm/src/stm32/chip.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/stm32/chip.h
*
- * Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/arch/arm/src/stm32/stm32.h b/nuttx/arch/arm/src/stm32/stm32.h
index 44a23aece..95fd19779 100644
--- a/nuttx/arch/arm/src/stm32/stm32.h
+++ b/nuttx/arch/arm/src/stm32/stm32.h
@@ -68,12 +68,6 @@
# undef CONFIG_DEBUG_QENCODER
#endif
-/* NVIC priority levels *************************************************************/
-
-#define NVIC_SYSH_PRIORITY_MIN 0xff /* All bits set in minimum priority */
-#define NVIC_SYSH_PRIORITY_DEFAULT 0x80 /* Midpoint is the default */
-#define NVIC_SYSH_PRIORITY_MAX 0x00 /* Zero is maximum priority */
-
/* Peripherals **********************************************************************/
#include "chip.h"
diff --git a/nuttx/arch/arm/src/stm32/stm32_irq.c b/nuttx/arch/arm/src/stm32/stm32_irq.c
index 36a5cf5fa..a952c2486 100644
--- a/nuttx/arch/arm/src/stm32/stm32_irq.c
+++ b/nuttx/arch/arm/src/stm32/stm32_irq.c
@@ -2,7 +2,7 @@
* arch/arm/src/stm32/stm32_irq.c
* arch/arm/src/chip/stm32_irq.c
*
- * Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -195,6 +195,29 @@ static int stm32_reserved(int irq, FAR void *context)
#endif
/****************************************************************************
+ * Name: stm32_prioritize_syscall
+ *
+ * Description:
+ * Set the priority of an exception. This function may be needed
+ * internally even if support for prioritized interrupts is not enabled.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+static inline void stm32_prioritize_syscall(int priority)
+{
+ uint32_t regval;
+
+ /* SVCALL is system handler 11 */
+
+ regval = getreg32(NVIC_SYSH8_11_PRIORITY);
+ regval &= ~NVIC_SYSH_PRIORITY_PR11_MASK;
+ regval |= (priority << NVIC_SYSH_PRIORITY_PR11_SHIFT);
+ putreg32(regval, NVIC_SYSH8_11_PRIORITY);
+}
+#endif
+
+/****************************************************************************
* Name: stm32_irqinfo
*
* Description:
@@ -335,6 +358,9 @@ void up_irqinitialize(void)
#ifdef CONFIG_ARCH_IRQPRIO
/* up_prioritize_irq(STM32_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN); */
#endif
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ stm32_prioritize_syscall(NVIC_SYSH_SVCALL_PRIORITY);
+#endif
/* If the MPU is enabled, then attach and enable the Memory Management
* Fault handler.
@@ -365,8 +391,7 @@ void up_irqinitialize(void)
/* And finally, enable interrupts */
- setbasepri(NVIC_SYSH_PRIORITY_MAX);
- irqrestore(0);
+ irqenable();
#endif
}
@@ -451,15 +476,28 @@ int up_prioritize_irq(int irq, int priority)
uint32_t regval;
int shift;
- DEBUGASSERT(irq >= STM32_IRQ_MEMFAULT && irq < NR_IRQS && (unsigned)priority <= NVIC_SYSH_PRIORITY_MIN);
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ DEBUGASSERT(irq >= STM32_IRQ_MEMFAULT && irq < NR_IRQS &&
+ priority >= NVIC_SYSH_DISABLE_PRIORITY &&
+ priority <= NVIC_SYSH_PRIORITY_MIN);
+#else
+ DEBUGASSERT(irq >= STM32_IRQ_MEMFAULT && irq < NR_IRQS &&
+ (unsigned)priority <= NVIC_SYSH_PRIORITY_MIN);
+#endif
if (irq < STM32_IRQ_INTERRUPTS)
{
- irq -= 4;
+ /* NVIC_SYSH_PRIORITY() maps {0..15} to one of three priority
+ * registers (0-3 are invalid)
+ */
+
regaddr = NVIC_SYSH_PRIORITY(irq);
+ irq -= 4;
}
else
{
+ /* NVIC_IRQ_PRIORITY() maps {0..} to one of many priority registers */
+
irq -= STM32_IRQ_INTERRUPTS;
regaddr = NVIC_IRQ_PRIORITY(irq);
}
diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c
index bfb64b26a..6aaecb2d9 100644
--- a/nuttx/arch/arm/src/stm32/stm32_serial.c
+++ b/nuttx/arch/arm/src/stm32/stm32_serial.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/stm32/stm32_serial.c
*
- * Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -1439,6 +1439,31 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
}
break;
+#ifdef CONFIG_STM32_USART_SINGLEWIRE
+ case TIOCSSINGLEWIRE:
+ {
+ /* Change the TX port to be open-drain/push-pull and enable/disable
+ * half-duplex mode.
+ */
+
+ uint32_t cr = up_serialin(priv, STM32_USART_CR3_OFFSET);
+
+ if (arg == SER_SINGLEWIRE_ENABLED)
+ {
+ stm32_configgpio(priv->tx_gpio | GPIO_OPENDRAIN);
+ cr |= USART_CR3_HDSEL;
+ }
+ else
+ {
+ stm32_configgpio(priv->tx_gpio | GPIO_PUSHPULL);
+ cr &= ~USART_CR3_HDSEL;
+ }
+
+ up_serialout(priv, STM32_USART_CR3_OFFSET, cr);
+ }
+ break;
+#endif
+
#ifdef CONFIG_SERIAL_TERMIOS
case TCGETS:
{
diff --git a/nuttx/arch/arm/src/stm32/stm32_vectors.S b/nuttx/arch/arm/src/stm32/stm32_vectors.S
index ab4dadb77..c9b62d762 100644
--- a/nuttx/arch/arm/src/stm32/stm32_vectors.S
+++ b/nuttx/arch/arm/src/stm32/stm32_vectors.S
@@ -2,7 +2,7 @@
* arch/arm/src/stm32/stm32_vectors.S
* arch/arm/src/chip/stm32_vectors.S
*
- * Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -235,7 +235,11 @@ stm32_common:
mov r2, r1 /* R2=Copy of the main/process stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ mrs r3, basepri /* R3=Current BASEPRI setting */
+#else
mrs r3, primask /* R3=Current PRIMASK setting */
+#endif
#ifdef CONFIG_ARCH_FPU
/* Skip over the block of memory reserved for floating pointer register save.
@@ -248,8 +252,8 @@ stm32_common:
#endif
/* Save the the remaining registers on the stack after the registers pushed
- * by the exception handling logic. r2=SP and r3=primask, r4-r11,r14=register
- * values.
+ * by the exception handling logic. r2=SP and r3=primask or basepri, r4-r11,
+ * r14=register values.
*/
#ifdef CONFIG_NUTTX_KERNEL
@@ -349,7 +353,7 @@ stm32_common:
* Here:
* r1 = Address on the target thread's stack position at the start of
* the registers saved by hardware
- * r3 = primask
+ * r3 = primask or basepri
* r4-r11 = restored register values
*/
2:
@@ -375,7 +379,12 @@ stm32_common:
/* Restore the interrupt state */
+#ifdef CONFIG_ARMV7M_USEBASEPRI
+ msr basepri, r3 /* Restore interrupts priority masking*/
+ cpsie i /* Re-enable interrupts */
+#else
msr primask, r3 /* Restore interrupts */
+#endif
/* Always return with R14 containing the special value that will: (1)
* return to thread mode, and (2) continue to use the MSP