aboutsummaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-14 22:06:19 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-14 22:06:19 +0000
commit87b33d354695294b519f7f6f1275592faf4fee46 (patch)
tree22cb9614a4995864efa52299408283473e5388e7 /nuttx/arch
parentcc3614dfe8f67033dca8c7c1f40c3367a0d3ca06 (diff)
downloadpx4-firmware-87b33d354695294b519f7f6f1275592faf4fee46.tar.gz
px4-firmware-87b33d354695294b519f7f6f1275592faf4fee46.tar.bz2
px4-firmware-87b33d354695294b519f7f6f1275592faf4fee46.zip
Configre configs/ubw32/ostest to use kconfig-frontends
git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5518 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/Kconfig18
-rw-r--r--nuttx/arch/arm/Kconfig2
-rw-r--r--nuttx/arch/arm/src/common/up_internal.h4
-rw-r--r--nuttx/arch/arm/src/kinetis/kinetis_clockconfig.c4
-rw-r--r--nuttx/arch/arm/src/kinetis/kinetis_start.c2
-rw-r--r--nuttx/arch/mips/Kconfig2
-rw-r--r--nuttx/arch/mips/src/common/up_internal.h4
-rw-r--r--nuttx/arch/mips/src/pic32mx/Kconfig6
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-head.S21
9 files changed, 53 insertions, 10 deletions
diff --git a/nuttx/arch/Kconfig b/nuttx/arch/Kconfig
index 7d34b56f4..d43137adb 100644
--- a/nuttx/arch/Kconfig
+++ b/nuttx/arch/Kconfig
@@ -109,6 +109,10 @@ config ARCH_NOINTC
bool
default n
+config ARCH_VECNOTIRQ
+ bool
+ default n
+
config ARCH_DMA
bool
default n
@@ -141,6 +145,20 @@ config ENDIAN_BIG
---help---
Select if architecture operates using big-endian byte ordering.
+config ARCH_HAVE_RAMFUNCS
+ bool
+ default n
+
+config ARCH_RAMFUNCS
+ bool "Copy functions to RAM on startup"
+ default n
+ depends on ARCH_HAVE_RAMFUNCS
+ ---help---
+ Copy some functions to RAM at boot time. This is done in some
+ architectures to improve performance. In other cases, it is done
+ so that FLASH can be reconfigured while the MCU executes out of
+ SRAM.
+
comment "Board Settings"
config BOARD_LOOPSPERMSEC
diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig
index bc7634695..36343e319 100644
--- a/nuttx/arch/arm/Kconfig
+++ b/nuttx/arch/arm/Kconfig
@@ -47,6 +47,8 @@ config ARCH_CHIP_KINETIS
select ARCH_CORTEXM4
select ARCH_HAVE_MPU
select ARCH_IRQPRIO
+ select ARCH_HAVE_RAMFUNCS
+ select ARCH_RAMFUNCS
---help---
Freescale Kinetis Architectures (ARM Cortex-M4)
diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h
index 0d3c5b1f2..55071345f 100644
--- a/nuttx/arch/arm/src/common/up_internal.h
+++ b/nuttx/arch/arm/src/common/up_internal.h
@@ -188,7 +188,7 @@ extern uint32_t _ebss; /* End+1 of .bss */
* will create a function named foo that will execute from RAM.
*/
-#ifdef CONFIG_BOOT_RAMFUNCS
+#ifdef CONFIG_ARCH_RAMFUNCS
# define __ramfunc__ __attribute__ ((section(".ramfunc")))
@@ -204,7 +204,7 @@ extern const uint32_t _framfuncs; /* Copy source address in FLASH */
extern uint32_t _sramfuncs; /* Copy destination start address in RAM */
extern uint32_t _eramfuncs; /* Copy destination start address in RAM */
-#endif /* CONFIG_BOOT_RAMFUNCS */
+#endif /* CONFIG_ARCH_RAMFUNCS */
#endif /* __ASSEMBLY__ */
/****************************************************************************
diff --git a/nuttx/arch/arm/src/kinetis/kinetis_clockconfig.c b/nuttx/arch/arm/src/kinetis/kinetis_clockconfig.c
index 31ea235d2..ad6e42884 100644
--- a/nuttx/arch/arm/src/kinetis/kinetis_clockconfig.c
+++ b/nuttx/arch/arm/src/kinetis/kinetis_clockconfig.c
@@ -55,8 +55,8 @@
* Private Definitions
****************************************************************************/
-#ifndef CONFIG_BOOT_RAMFUNCS
-# error "CONFIG_BOOT_RAMFUNCS must be defined for this logic"
+#ifndef CONFIG_ARCH_RAMFUNCS
+# error "CONFIG_ARCH_RAMFUNCS must be defined for this logic"
#endif
/****************************************************************************
diff --git a/nuttx/arch/arm/src/kinetis/kinetis_start.c b/nuttx/arch/arm/src/kinetis/kinetis_start.c
index c8f20fbdd..2f73cb2e6 100644
--- a/nuttx/arch/arm/src/kinetis/kinetis_start.c
+++ b/nuttx/arch/arm/src/kinetis/kinetis_start.c
@@ -116,7 +116,7 @@ void __start(void)
* at _framfuncs
*/
-#ifdef CONFIG_BOOT_RAMFUNCS
+#ifdef CONFIG_ARCH_RAMFUNCS
for (src = &_framfuncs, dest = &_sramfuncs; dest < &_eramfuncs; )
{
*dest++ = *src++;
diff --git a/nuttx/arch/mips/Kconfig b/nuttx/arch/mips/Kconfig
index 772b6f663..1b10e26ae 100644
--- a/nuttx/arch/mips/Kconfig
+++ b/nuttx/arch/mips/Kconfig
@@ -12,6 +12,8 @@ config ARCH_CHIP_PIC32MX
bool "PIC32MX"
select ARCH_MIPS32
select ARCH_IRQPRIO
+ select ARCH_VECNOTIRQ
+ select ARCH_HAVE_RAMFUNCS
---help---
Microchip PIC32MX320F032H (MIPS32)
diff --git a/nuttx/arch/mips/src/common/up_internal.h b/nuttx/arch/mips/src/common/up_internal.h
index 0eb1ed6a0..b284961b0 100644
--- a/nuttx/arch/mips/src/common/up_internal.h
+++ b/nuttx/arch/mips/src/common/up_internal.h
@@ -152,7 +152,7 @@ extern uint32_t _sdata; /* Start of .data */
extern uint32_t _edata; /* End+1 of .data */
extern uint32_t _sbss; /* Start of .bss */
extern uint32_t _ebss; /* End+1 of .bss */
-#ifdef CONFIG_PIC32MX_RAMFUNCS
+#ifdef CONFIG_ARCH_RAMFUNCS
extern uint32_t _sramfunc; /* Start of ramfuncs */
extern uint32_t _eramfunc; /* End+1 of ramfuncs */
extern uint32_t _ramfunc_loadaddr; /* Start of ramfuncs in FLASH */
@@ -160,7 +160,7 @@ extern uint32_t _ramfunc_sizeof; /* Size of ramfuncs */
extern uint32_t _bmxdkpba_address; /* BMX register setting */
extern uint32_t _bmxdudba_address; /* BMX register setting */
extern uint32_t _bmxdupba_address; /* BMX register setting */
-#endif /* CONFIG_PIC32MX_RAMFUNCS */
+#endif /* CONFIG_ARCH_RAMFUNCS */
#endif /* __ASSEMBLY__ */
/****************************************************************************
diff --git a/nuttx/arch/mips/src/pic32mx/Kconfig b/nuttx/arch/mips/src/pic32mx/Kconfig
index bcb99cf6d..6ac10608b 100644
--- a/nuttx/arch/mips/src/pic32mx/Kconfig
+++ b/nuttx/arch/mips/src/pic32mx/Kconfig
@@ -533,10 +533,14 @@ config PIC32MX_CM1
bool "Comparator 1 (CM1)"
default n
-config PIC32MX_CM2
+config PIC32MX_CM2
bool "Comparator 2 (CM2)"
default n
+config PIC32MX_CM3
+ bool "Comparator 3 (CM3)"
+ default n
+
config PIC32MX_RTCC
bool "Real-Time Clock and Calendar (RTCC)"
default n
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-head.S b/nuttx/arch/mips/src/pic32mx/pic32mx-head.S
index 7224ee122..2e1a34080 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-head.S
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-head.S
@@ -367,7 +367,7 @@ __start:
* initializing bus matrix registers.
*/
-#ifdef CONFIG_PIC32MX_RAMFUNCS
+#ifdef CONFIG_ARCH_RAMFUNCS
la t1, _ramfunc_sizeof
beqz t1, .Lnoramfuncs
nop
@@ -598,17 +598,26 @@ halt:
devconfig:
devconfig3:
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
+
.long CONFIG_PIC32MX_USERID << DEVCFG3_USERID_SHIFT | \
CONFIG_PIC32MX_PMDL1WAY << 28 | CONFIG_PIC32MX_IOL1WAY << 29 | \
CONFIG_PIC32MX_USBIDO << 30 | CONFIG_PIC32MX_VBUSIO << 31 | \
DEVCFG3_UNUSED
-#else
+
+#elif defined(CHIP_PIC32MX3) || defined(CHIP_PIC32MX4)
+
+ .long CONFIG_PIC32MX_USERID << DEVCFG3_USERID_SHIFT | \
+ DEVCFG3_UNUSED
+
+#elif defined(CHIP_PIC32MX5) || defined(CHIP_PIC32MX6) || defined(CHIP_PIC32MX7)
+
.long CONFIG_PIC32MX_USERID << DEVCFG3_USERID_SHIFT | \
CONFIG_PIC32MX_SRSSEL << DEVCFG3_FSRSSEL_SHIFT | \
CONFIG_PIC32MX_FMIIEN << 24 | CONFIG_PIC32MX_FETHIO << 25 | \
CONFIG_PIC32MX_FCANIO << 26 | CONFIG_PIC32MX_FSCM1IO << 29 | \
CONFIG_PIC32MX_USBIDO << 30 | CONFIG_PIC32MX_VBUSIO << 31 | \
DEVCFG3_UNUSED
+
#endif
devconfig2:
@@ -618,22 +627,27 @@ devconfig2:
devconfig1:
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
+
.long CONFIG_PIC32MX_FNOSC | CONFIG_PIC32MX_FSOSCEN | \
CONFIG_PIC32MX_IESO | CONFIG_PIC32MX_POSCMOD | \
CONFIG_PIC32MX_OSCOUT << 10 | \
CONFIG_PIC32MX_PBDIV | CONFIG_PIC32MX_FCKSM | \
DEVCFG1_WINDIS | CONFIG_PIC32MX_WDENABLE | \
DEVCFG1_FWDTWINSZ_75 | DEVCFG1_UNUSED
+
#else
+
.long CONFIG_PIC32MX_FNOSC | CONFIG_PIC32MX_FSOSCEN | \
CONFIG_PIC32MX_IESO | CONFIG_PIC32MX_POSCMOD | \
CONFIG_PIC32MX_OSCOUT << 10 | \
CONFIG_PIC32MX_PBDIV | CONFIG_PIC32MX_FCKSM | \
CONFIG_PIC32MX_WDENABLE | DEVCFG1_UNUSED
+
#endif
devconfig0:
#if defined(CHIP_PIC32MX1) || defined(CHIP_PIC32MX2)
+
.long CONFIG_PIC32MX_DEBUGGER << DEVCFG0_DEBUG_SHIFT | \
DEVCFG0_JTAGEN | \
CONFIG_PIC32MX_ICESEL << DEVCFG0_ICESEL_SHIFT | \
@@ -641,13 +655,16 @@ devconfig0:
CONFIG_PIC32MX_BOOTFLASHWP << 24 | \
CONFIG_PIC32MX_CODEWP << 28 | \
DEVCFG0_UNUSED
+
#else
+
.long CONFIG_PIC32MX_DEBUGGER << DEVCFG0_DEBUG_SHIFT | \
CONFIG_PIC32MX_ICESEL << 3 | \
CONFIG_PIC32MX_PROGFLASHWP << DEVCFG0_PWP_SHIFT | \
CONFIG_PIC32MX_BOOTFLASHWP << 24 | \
CONFIG_PIC32MX_CODEWP << 28 | \
DEVCFG0_UNUSED
+
#endif
.size devconfig, .-devconfig