aboutsummaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/Kconfig19
-rw-r--r--nuttx/arch/arm/Kconfig32
-rw-r--r--nuttx/arch/arm/include/elf.h243
-rw-r--r--nuttx/arch/arm/include/stm32/chip.h200
-rw-r--r--nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h58
-rw-r--r--nuttx/arch/arm/src/Makefile148
-rw-r--r--nuttx/arch/arm/src/armv7-m/Kconfig51
-rw-r--r--nuttx/arch/arm/src/armv7-m/Toolchain.defs266
-rw-r--r--nuttx/arch/arm/src/armv7-m/memcpy.S351
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_elf.c450
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_exception.S4
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_hardfault.c4
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_memcpy.S416
-rw-r--r--nuttx/arch/arm/src/common/arm-elf.h53
-rw-r--r--nuttx/arch/arm/src/stm32/Kconfig629
-rw-r--r--nuttx/arch/arm/src/stm32/Make.defs32
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_eth.h8
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_flash.h1
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h190
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f103vc_pinmap.h2
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h98
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f105vb_pinmap.h2
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f107vc_pinmap.h2
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h23
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h61
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h78
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h72
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h2
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_adc.h2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_eth.c11
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_eth.h35
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_i2c.c385
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_lowputc.c75
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_otgfsdev.c26
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_otgfshost.c53
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_qencoder.c1
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_serial.c154
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_uart.h14
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c56
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f20xxx_rcc.c4
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c4
42 files changed, 3304 insertions, 1013 deletions
diff --git a/nuttx/arch/Kconfig b/nuttx/arch/Kconfig
index bbe99c17c..f19228143 100644
--- a/nuttx/arch/Kconfig
+++ b/nuttx/arch/Kconfig
@@ -9,6 +9,7 @@ choice
config ARCH_8051
bool "8051"
+ select CUSTOM_STACK
---help---
Intel 8051 architectures and derivaties
@@ -111,12 +112,30 @@ config ARCH_DMA
bool
default n
+config ARCH_IRQPRIO
+ bool
+ default n
+
+config CUSTOM_STACK
+ bool
+ default n
+
+config ADDRENV
+ bool
+ default n
+
config ARCH_STACKDUMP
bool "Dump stack on assertions"
default n
---help---
Enable to do stack dumps after assertions
+config ENDIAN_BIG
+ bool "Big Endian Architecture"
+ default n
+ ---help---
+ Select if architecture operates using big-endian byte ordering.
+
comment "Board Settings"
config BOARD_LOOPSPERMSEC
diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig
index 2a7ea10b5..4fce8efbf 100644
--- a/nuttx/arch/arm/Kconfig
+++ b/nuttx/arch/arm/Kconfig
@@ -4,6 +4,8 @@
#
if ARCH_ARM
+comment "ARM Options"
+
choice
prompt "ARM chip selection"
default ARCH_CHIP_STM32
@@ -44,6 +46,7 @@ config ARCH_CHIP_KINETIS
bool "Freescale Kinetis"
select ARCH_CORTEXM4
select ARCH_HAVE_MPU
+ select ARCH_IRQPRIO
---help---
Freescale Kinetis Architectures (ARM Cortex-M4)
@@ -51,6 +54,7 @@ config ARCH_CHIP_LM3S
bool "TI Stellaris"
select ARCH_CORTEXM3
select ARCH_HAVE_MPU
+ select ARCH_IRQPRIO
---help---
TI Stellaris LMS3 architecutres (ARM Cortex-M3)
@@ -58,6 +62,7 @@ config ARCH_CHIP_LPC17XX
bool "NXP LPC17xx"
select ARCH_CORTEXM3
select ARCH_HAVE_MPU
+ select ARCH_IRQPRIO
---help---
NXP LPC17xx architectures (ARM Cortex-M3)
@@ -89,6 +94,7 @@ 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).
@@ -96,6 +102,7 @@ config ARCH_CHIP_SAM3U
bool "Atmel AT91SAM3U"
select ARCH_CORTEXM3
select ARCH_HAVE_MPU
+ select ARCH_IRQPRIO
---help---
Atmel AT91SAM3U architectures (ARM Cortex-M3)
@@ -104,6 +111,7 @@ 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).
@@ -153,6 +161,9 @@ config ARCH_CHIP
default "stm32" if ARCH_CHIP_STM32
default "str71x" if ARCH_CHIP_STR71X
+config ARCH_HAVE_CMNVECTOR
+ bool
+
config ARMV7M_CMNVECTOR
bool "Use common ARMv7-M vectors"
default n
@@ -217,12 +228,6 @@ config PAGING
If set =y in your configation file, this setting will enable the on-demand
paging feature as described in http://www.nuttx.org/NuttXDemandPaging.html.
-config ARCH_IRQPRIO
- bool "Interrupt priority"
- default y if ARCH_CORTEXM3 || ARCH_CORTEXM4
- ---help---
- Select if your board supports interrupt prioritization.
-
config BOARD_LOOPSPERMSEC
int "Delay loops per millisecond"
default 5000
@@ -239,6 +244,21 @@ config ARCH_CALIBRATION
watch to measure the 100 second delay then adjust BOARD_LOOPSPERMSEC until
the delay actually is 100 seconds.
+config DEBUG_HARDFAULT
+ bool "Verbose Hard-Fault Debug"
+ default n
+ depends on DEBUG && (ARCH_CORTEXM3 || ARCH_CORTEXM4)
+ ---help---
+ Enables verbose debug output when a hard fault is occurs. This verbose
+ output is sometimes helpful when debugging difficult hard fault problems,
+ but may be more than you typcially want to see.
+
+if ARCH_CORTEXM3 || ARCH_CORTEXM4
+source arch/arm/src/armv7-m/Kconfig
+endif
+if ARCH_ARM7TDMI || ARCH_ARM926EJS
+source arch/arm/src/arm/Kconfig
+endif
if ARCH_CHIP_C5471
source arch/arm/src/c5471/Kconfig
endif
diff --git a/nuttx/arch/arm/include/elf.h b/nuttx/arch/arm/include/elf.h
new file mode 100644
index 000000000..21b2c1c2c
--- /dev/null
+++ b/nuttx/arch/arm/include/elf.h
@@ -0,0 +1,243 @@
+/****************************************************************************
+ * arch/arm/include/syscall.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Reference: "ELF for the ARMŽ Architecture," ARM IHI 0044D, current through
+ * ABI release 2.08, October 28, 2009, ARM Limited.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_ARM_INCLUDE_ELF_H
+#define __ARCH_ARM_INCLUDE_ELF_H
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* 4.3.1 ELF Identification. Should have:
+ *
+ * e_machine = EM_ARM
+ * e_ident[EI_CLASS] = ELFCLASS32
+ * e_ident[EI_DATA] = ELFDATA2LSB (little endian) or ELFDATA2MSB (big endian)
+ */
+
+#if 0 /* Defined in include/elf32.h */
+#define EM_ARM 40
+#endif
+
+/* Table 4-2, ARM-specific e_flags */
+
+#define EF_ARM_EABI_MASK 0xff000000
+#define EF_ARM_EABI_UNKNOWN 0x00000000
+#define EF_ARM_EABI_VER1 0x01000000
+#define EF_ARM_EABI_VER2 0x02000000
+#define EF_ARM_EABI_VER3 0x03000000
+#define EF_ARM_EABI_VER4 0x04000000
+#define EF_ARM_EABI_VER5 0x05000000
+
+#define EF_ARM_BE8 0x00800000
+
+/* Table 4-4, Processor specific section types */
+
+#define SHT_ARM_EXIDX 0x70000001 /* Exception Index table */
+#define SHT_ARM_PREEMPTMAP 0x70000002 /* BPABI DLL dynamic linking pre-emption map */
+#define SHT_ARM_ATTRIBUTES 0x70000003 /* Object file compatibility attributes */
+#define SHT_ARM_DEBUGOVERLAY 0x70000004
+#define SHT_ARM_OVERLAYSECTION 0x70000005
+
+/* 4.7.1 Relocation codes
+ *
+ * S (when used on its own) is the address of the symbol.
+ * A is the addend for the relocation.
+ * P is the address of the place being relocated (derived from r_offset).
+ * Pa is the adjusted address of the place being relocated, defined as (P & 0xFFFFFFFC).
+ * T is 1 if the target symbol S has type STT_FUNC and the symbol addresses a Thumb instruction;
+ * it is 0 otherwise.
+ * B(S) is the addressing origin of the output segment defining the symbol S.
+ * GOT_ORG is the addressing origin of the Global Offset Table
+ * GOT(S) is the address of the GOT entry for the symbol S.
+ */
+
+#define R_ARM_NONE 0 /* No relocation */
+#define R_ARM_PC24 1 /* ARM ((S + A) | T) - P */
+#define R_ARM_ABS32 2 /* Data (S + A) | T */
+#define R_ARM_REL32 3 /* Data ((S + A) | T) - P */
+#define R_ARM_LDR_PC_G0 4 /* ARM S + A - P */
+#define R_ARM_ABS16 5 /* Data S + A */
+#define R_ARM_ABS12 6 /* ARM S + A */
+#define R_ARM_THM_ABS5 7 /* Thumb16 S + A */
+#define R_ARM_ABS8 8 /* Data S + A */
+#define R_ARM_SBREL32 9 /* Data ((S + A) | T) - B(S) */
+#define R_ARM_THM_CALL 10 /* Thumb32 ((S + A) | T) - P */
+#define R_ARM_THM_PC8 11 /* Thumb16 S + A - Pa */
+#define R_ARM_BREL_ADJ 12 /* Data ?B(S) + A */
+#define R_ARM_TLS_DESC 13 /* Data */
+#define R_ARM_THM_SWI8 14 /* Obsolete */
+#define R_ARM_XPC25 15 /* Obsolete */
+#define R_ARM_THM_XPC22 16 /* Obsolete */
+#define R_ARM_TLS_DTPMOD32 17 /* Data Module[S] */
+#define R_ARM_TLS_DTPOFF32 18 /* Data S + A - TLS */
+#define R_ARM_TLS_TPOFF32 19 /* Data S + A - tp */
+#define R_ARM_COPY 20 /* Miscellaneous */
+#define R_ARM_GLOB_DAT 21 /* Data (S + A) | T */
+#define R_ARM_JUMP_SLOT 22 /* Data (S + A) | T */
+#define R_ARM_RELATIVE 23 /* Data B(S) + A */
+#define R_ARM_GOTOFF32 24 /* Data ((S + A) | T) - GOT_ORG */
+#define R_ARM_BASE_PREL 25 /* Data B(S) + A - P */
+#define R_ARM_GOT_BREL 26 /* Data GOT(S) + A - GOT_ORG */
+#define R_ARM_PLT32 27 /* ARM ((S + A) | T) - P */
+#define R_ARM_CALL 28 /* ARM ((S + A) | T) - P */
+#define R_ARM_JUMP24 29 /* ARM ((S + A) | T) - P */
+#define R_ARM_THM_JUMP24 30 /* Thumb32 ((S + A) | T) - P */
+#define R_ARM_BASE_ABS 31 /* Data B(S) + A */
+#define R_ARM_ALU_PCREL_7_0 32 /* Obsolete */
+#define R_ARM_ALU_PCREL_15_8 33 /* Obsolete */
+#define R_ARM_ALU_PCREL_23_15 34 /* Obsolete */
+#define R_ARM_LDR_SBREL_11_0_NC 35 /* ARM S + A - B(S) */
+#define R_ARM_ALU_SBREL_19_12_NC 36 /* ARM S + A - B(S) */
+#define R_ARM_ALU_SBREL_27_20_CK 37 /* ARM S + A - B(S) */
+#define R_ARM_TARGET1 38 /* Miscellaneous (S + A) | T or ((S + A) | T) - P */
+#define R_ARM_SBREL31 39 /* Data ((S + A) | T) - B(S) */
+#define R_ARM_V4BX 40 /* Miscellaneous */
+#define R_ARM_TARGET2 41 /* Miscellaneous */
+#define R_ARM_PREL31 42 /* Data ((S + A) | T) - P */
+#define R_ARM_MOVW_ABS_NC 43 /* ARM (S + A) | T */
+#define R_ARM_MOVT_ABS 44 /* ARM S + A */
+#define R_ARM_MOVW_PREL_NC 45 /* ARM ((S + A) | T) - P */
+#define R_ARM_MOVT_PREL 46 /* ARM S + A - P */
+#define R_ARM_THM_MOVW_ABS_NC 47 /* Thumb32 (S + A) | T */
+#define R_ARM_THM_MOVT_ABS 48 /* Thumb32 S + A */
+#define R_ARM_THM_MOVW_PREL_NC 49 /* Thumb32 ((S + A) | T) - P */
+#define R_ARM_THM_MOVT_PREL 50 /* Thumb32 S + A - P */
+#define R_ARM_THM_JUMP19 51 /* Thumb32 ((S + A) | T) - P */
+#define R_ARM_THM_JUMP6 52 /* Thumb16 S + A - P */
+#define R_ARM_THM_ALU_PREL_11_0 53 /* Thumb32 ((S + A) | T) - Pa */
+#define R_ARM_THM_PC12 54 /* Thumb32 S + A - Pa */
+#define R_ARM_ABS32_NOI 55 /* Data S + A */
+#define R_ARM_REL32_NOI 56 /* Data S + A - P */
+#define R_ARM_ALU_PC_G0_NC 57 /* ARM ((S + A) | T) - P */
+#define R_ARM_ALU_PC_G0 58 /* ARM ((S + A) | T) - P */
+#define R_ARM_ALU_PC_G1_NC 59 /* ARM ((S + A) | T) - P */
+#define R_ARM_ALU_PC_G1 60 /* ARM ((S + A) | T) - P */
+#define R_ARM_ALU_PC_G2 61 /* ARM ((S + A) | T) - P */
+#define R_ARM_LDR_PC_G1 62 /* ARM S + A - P */
+#define R_ARM_LDR_PC_G2 63 /* ARM S + A - P */
+#define R_ARM_LDRS_PC_G0 64 /* ARM S + A - P */
+#define R_ARM_LDRS_PC_G1 65 /* ARM S + A - P */
+#define R_ARM_LDRS_PC_G2 66 /* ARM S + A - P */
+#define R_ARM_LDC_PC_G0 67 /* ARM S + A - P */
+#define R_ARM_LDC_PC_G1 68 /* ARM S + A - P */
+#define R_ARM_LDC_PC_G2 69 /* ARM S + A - P */
+#define R_ARM_ALU_SB_G0_NC 70 /* ARM ((S + A) | T) - B(S) */
+#define R_ARM_ALU_SB_G0 71 /* ARM ((S + A) | T) - B(S) */
+#define R_ARM_ALU_SB_G1_NC 72 /* ARM ((S + A) | T) - B(S) */
+#define R_ARM_ALU_SB_G1 73 /* ARM ((S + A) | T) - B(S) */
+#define R_ARM_ALU_SB_G2 74 /* ARM ((S + A) | T) - B(S) */
+#define R_ARM_LDR_SB_G0 75 /* ARM S + A - B(S) */
+#define R_ARM_LDR_SB_G1 76 /* ARM S + A - B(S) */
+#define R_ARM_LDR_SB_G2 77 /* ARM S + A - B(S) */
+#define R_ARM_LDRS_SB_G0 78 /* ARM S + A - B(S) */
+#define R_ARM_LDRS_SB_G1 79 /* ARM S + A - B(S) */
+#define R_ARM_LDRS_SB_G2 80 /* ARM S + A - B(S) */
+#define R_ARM_LDC_SB_G0 81 /* ARM S + A - B(S) */
+#define R_ARM_LDC_SB_G1 82 /* ARM S + A - B(S) */
+#define R_ARM_LDC_SB_G2 83 /* ARM S + A - B(S) */
+#define R_ARM_MOVW_BREL_NC 84 /* ARM ((S + A) | T) - B(S) */
+#define R_ARM_MOVT_BREL 85 /* ARM S + A - B(S) */
+#define R_ARM_MOVW_BREL 86 /* ARM ((S + A) | T) - B(S) */
+#define R_ARM_THM_MOVW_BREL_NC 87 /* Thumb32 ((S + A) | T) - B(S) */
+#define R_ARM_THM_MOVT_BREL 88 /* Thumb32 S + A - B(S) */
+#define R_ARM_THM_MOVW_BREL 89 /* Thumb32 ((S + A) | T) - B(S) */
+#define R_ARM_TLS_GOTDESC 90 /* Data */
+#define R_ARM_TLS_CALL 91 /* ARM */
+#define R_ARM_TLS_DESCSEQ 92 /* ARM TLS relaxation */
+#define R_ARM_THM_TLS_CALL 93 /* Thumb32 */
+#define R_ARM_PLT32_ABS 94 /* Data PLT(S) + A */
+#define R_ARM_GOT_ABS 95 /* Data GOT(S) + A */
+#define R_ARM_GOT_PREL 96 /* Data GOT(S) + A - P */
+#define R_ARM_GOT_BREL12 97 /* ARM GOT(S) + A - GOT_ORG */
+#define R_ARM_GOTOFF12 98 /* ARM S + A - GOT_ORG */
+#define R_ARM_GOTRELAX 99 /* Miscellaneous */
+#define R_ARM_GNU_VTENTRY 100 /* Data */
+#define R_ARM_GNU_VTINHERIT 101 /* Data */
+#define R_ARM_THM_JUMP11 102 /* Thumb16 S + A - P */
+#define R_ARM_THM_JUMP8 103 /* Thumb16 S + A - P */
+#define R_ARM_TLS_GD32 104 /* Data GOT(S) + A - P */
+#define R_ARM_TLS_LDM32 105 /* Data GOT(S) + A - P */
+#define R_ARM_TLS_LDO32 106 /* Data S + A - TLS */
+#define R_ARM_TLS_IE32 107 /* Data GOT(S) + A - P */
+#define R_ARM_TLS_LE32 108 /* Data S + A - tp */
+#define R_ARM_TLS_LDO12 109 /* ARM S + A - TLS */
+#define R_ARM_TLS_LE12 110 /* ARM S + A - tp */
+#define R_ARM_TLS_IE12GP 111 /* ARM GOT(S) + A - GOT_ORG */
+#define R_ARM_ME_TOO 128 /* Obsolete */
+#define R_ARM_THM_TLS_DESCSEQ16 129 /* Thumb16 */
+#define R_ARM_THM_TLS_DESCSEQ32 130 /* Thumb32 */
+
+/* 5.2.1 Platform architecture compatibility data */
+
+#define PT_ARM_ARCHEXT_FMTMSK 0xff000000
+#define PT_ARM_ARCHEXT_PROFMSK 0x00ff0000
+#define PT_ARM_ARCHEXT_ARCHMSK 0x000000ff
+
+#define PT_ARM_ARCHEXT_FMT_OS 0x00000000
+#define PT_ARM_ARCHEXT_FMT_ABI 0x01000000
+
+#define PT_ARM_ARCHEXT_PROF_NONE 0x00000000
+#define PT_ARM_ARCHEXT_PROF_ARM 0x00410000
+#define PT_ARM_ARCHEXT_PROF_RT 0x00520000
+#define PT_ARM_ARCHEXT_PROF_MC 0x004d0000
+#define PT_ARM_ARCHEXT_PROF_CLASSIC 0x00530000
+
+#define PT_ARM_ARCHEXT_ARCH_UNKNOWN 0x00
+#define PT_ARM_ARCHEXT_ARCHv4 0x01
+#define PT_ARM_ARCHEXT_ARCHv4T 0x02
+#define PT_ARM_ARCHEXT_ARCHv5T 0x03
+#define PT_ARM_ARCHEXT_ARCHv5TE 0x04
+#define PT_ARM_ARCHEXT_ARCHv5TEJ 0x05
+#define PT_ARM_ARCHEXT_ARCHv6 0x06
+#define PT_ARM_ARCHEXT_ARCHv6KZ 0x07
+#define PT_ARM_ARCHEXT_ARCHv6T2 0x08
+#define PT_ARM_ARCHEXT_ARCHv6K 0x09
+#define PT_ARM_ARCHEXT_ARCHv7 0x0a
+#define PT_ARM_ARCHEXT_ARCHv6M 0x0b
+#define PT_ARM_ARCHEXT_ARCHv6SM 0x0c
+#define PT_ARM_ARCHEXT_ARCHv7EM 0x0d
+
+/* Table 5-6, ARM-specific dynamic array tags */
+
+#define DT_ARM_RESERVED1 0x70000000
+#define DT_ARM_SYMTABSZ 0x70000001
+#define DT_ARM_PREEMPTMAP 0x70000002
+#define DT_ARM_RESERVED2 0x70000003
+
+#endif /* __ARCH_ARM_INCLUDE_ELF_H */
diff --git a/nuttx/arch/arm/include/stm32/chip.h b/nuttx/arch/arm/include/stm32/chip.h
index d01929e1c..d34c2eb4f 100644
--- a/nuttx/arch/arm/include/stm32/chip.h
+++ b/nuttx/arch/arm/include/stm32/chip.h
@@ -59,12 +59,11 @@
/* STM32 F100 Value Line ************************************************************/
#if defined(CONFIG_ARCH_CHIP_STM32F100C8) || defined(CONFIG_ARCH_CHIP_STM32F100CB) \
- || defined(CONFIG_ARCH_CHIP_STM32F100R8) || defined(CONFIG_ARCH_CHIP_STM32F100RB) \
- || defined(CONFIG_ARCH_CHIP_STM32F100V8) || defined(CONFIG_ARCH_CHIP_STM32F100VB)
+ || defined(CONFIG_ARCH_CHIP_STM32F100R8) || defined(CONFIG_ARCH_CHIP_STM32F100RB)
# define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */
-# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# define CONFIG_STM32_MEDIUMDENSITY 1 /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# 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 */
# define CONFIG_STM32_VALUELINE 1 /* STM32F100x */
# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */
# undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */
@@ -72,10 +71,41 @@
# define STM32_NFSMC 0 /* FSMC */
# define STM32_NATIM 1 /* One advanced timer TIM1 */
# define STM32_NGTIM 3 /* 16-bit general timers TIM2,3,4 with DMA */
-# define STM32_NBTIM 0 /* No basic timers */
-# define STM32_NDMA 2 /* DMA1-2 */
+# define STM32_NBTIM 2 /* 2 basic timers: TIM6, TIM7 */
+// TODO: there are also 3 additional timers (15-17) that don't fit any existing category
+# define STM32_NDMA 1 /* DMA1 */
# define STM32_NSPI 2 /* SPI1-2 */
-# define STM32_NI2S 0 /* No I2S (?) */
+# define STM32_NI2S 0 /* No I2S */
+# define STM32_NUSART 3 /* USART1-3 */
+# define STM32_NI2C 2 /* I2C1-2 */
+# define STM32_NCAN 0 /* No CAN */
+# define STM32_NSDIO 0 /* No SDIO */
+# define STM32_NUSBOTG 0 /* No USB OTG FS/HS */
+# define STM32_NGPIO 64 /* GPIOA-D */
+# define STM32_NADC 1 /* ADC1 */
+# define STM32_NDAC 2 /* DAC 1-2 */
+# define STM32_NCRC 1 /* CRC1 */
+# define STM32_NETHERNET 0 /* No ethernet */
+# define STM32_NRNG 0 /* No random number generator (RNG) */
+# define STM32_NDCMI 0 /* No digital camera interface (DCMI) */
+
+#elif defined(CONFIG_ARCH_CHIP_STM32F100V8) || defined(CONFIG_ARCH_CHIP_STM32F100VB)
+# 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 */
+# define CONFIG_STM32_VALUELINE 1 /* 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 /* 16-bit general timers TIM2,3,4 with DMA */
+# define STM32_NBTIM 2 /* 2 basic timers: TIM6, TIM7 */
+// TODO: there are also 3 additional timers (15-17) that don't fit any existing category
+# 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 0 /* No CAN */
@@ -89,6 +119,70 @@
# define STM32_NRNG 0 /* No random number generator (RNG) */
# define STM32_NDCMI 0 /* No digital camera interface (DCMI) */
+/* STM32 F100 High-density value Line ************************************************************/
+
+#elif defined(CONFIG_ARCH_CHIP_STM32F100RC) || defined(CONFIG_ARCH_CHIP_STM32F100RD) \
+ || defined(CONFIG_ARCH_CHIP_STM32F100RE)
+# define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
+# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */
+# define CONFIG_STM32_VALUELINE 1 /* 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 4 /* 16-bit general timers TIM2,3,4,5 with DMA */
+# define STM32_NBTIM 2 /* 2 basic timers: TIM6, TIM7 */
+// TODO: there are also 6 additional timers (12-17) that don't fit any existing category
+# define STM32_NDMA 2 /* DMA1-2 */
+# define STM32_NSPI 3 /* SPI1-3 */
+# define STM32_NI2S 0 /* No I2S */
+# define STM32_NUSART 5 /* USART1-5 */
+# define STM32_NI2C 2 /* I2C1-2 */
+# define STM32_NCAN 0 /* No CAN */
+# define STM32_NSDIO 0 /* No SDIO */
+# define STM32_NUSBOTG 0 /* No USB OTG FS/HS */
+# define STM32_NGPIO 64 /* GPIOA-D */
+# define STM32_NADC 1 /* ADC1 */
+# define STM32_NDAC 2 /* DAC 1-2 */
+# define STM32_NCRC 1 /* CRC1 */
+# define STM32_NETHERNET 0 /* No ethernet */
+# define STM32_NRNG 0 /* No random number generator (RNG) */
+# define STM32_NDCMI 0 /* No digital camera interface (DCMI) */
+
+#elif defined(CONFIG_ARCH_CHIP_STM32F100VC) || defined(CONFIG_ARCH_CHIP_STM32F100VD) \
+ || defined(CONFIG_ARCH_CHIP_STM32F100VE)
+# define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
+# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */
+# define CONFIG_STM32_VALUELINE 1 /* 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 1 /* FSMC */
+# define STM32_NATIM 1 /* One advanced timer TIM1 */
+# define STM32_NGTIM 4 /* 16-bit general timers TIM2,3,4,5 with DMA */
+# define STM32_NBTIM 2 /* 2 basic timers: TIM6, TIM7 */
+// TODO: there are also 6 additional timers (12-17) that don't fit any existing category
+# define STM32_NDMA 2 /* DMA1-2 */
+# define STM32_NSPI 3 /* SPI1-3 */
+# define STM32_NI2S 0 /* No I2S */
+# define STM32_NUSART 5 /* USART1-5 */
+# define STM32_NI2C 2 /* I2C1-2 */
+# define STM32_NCAN 0 /* No CAN */
+# define STM32_NSDIO 0 /* No SDIO */
+# define STM32_NUSBOTG 0 /* No USB OTG FS/HS */
+# define STM32_NGPIO 80 /* GPIOA-E */
+# define STM32_NADC 1 /* ADC1 */
+# define STM32_NDAC 2 /* DAC 1-2 */
+# define STM32_NCRC 1 /* CRC1 */
+# define STM32_NETHERNET 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.
@@ -96,9 +190,9 @@
#elif defined(CONFIG_ARCH_CHIP_STM32F103RET6)
# define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
+# define CONFIG_STM32_HIGHDENSITY 1 /* 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 */
@@ -129,9 +223,9 @@
#elif defined(CONFIG_ARCH_CHIP_STM32F103VCT6) || defined(CONFIG_ARCH_CHIP_STM32F103VET6)
# define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
+# define CONFIG_STM32_HIGHDENSITY 1 /* 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 */
@@ -162,9 +256,9 @@
#elif defined(CONFIG_ARCH_CHIP_STM32F103ZET6)
# define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# define CONFIG_STM32_HIGHDENSITY 1 /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
+# define CONFIG_STM32_HIGHDENSITY 1 /* 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 */
@@ -192,9 +286,9 @@
/* STM32 F105/F107 Connectivity Line *******************************************************/
#elif defined(CONFIG_ARCH_CHIP_STM32F105VBT7)
# define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* 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 */
# define CONFIG_STM32_CONNECTIVITYLINE 1 /* STM32F105x and STM32F107x */
# undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */
@@ -221,9 +315,9 @@
#elif defined(CONFIG_ARCH_CHIP_STM32F107VC)
# define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* 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 */
# define CONFIG_STM32_CONNECTIVITYLINE 1 /* STM32F105x and STM32F107x */
# undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */
@@ -251,9 +345,9 @@
/* STM32 F2 Family ******************************************************************/
#elif defined(CONFIG_ARCH_CHIP_STM32F207IG) /* UFBGA-176 1024Kb FLASH 128Kb SRAM */
# undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* 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 */
# define CONFIG_STM32_STM32F20XX 1 /* STM32F205x and STM32F207x */
@@ -283,9 +377,9 @@
/* STM23 F4 Family ******************************************************************/
#elif defined(CONFIG_ARCH_CHIP_STM32F405RG) /* LQFP 64 10x10x1.4 1024Kb FLASH 192Kb SRAM */
# undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* 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 */
@@ -314,9 +408,9 @@
#elif defined(CONFIG_ARCH_CHIP_STM32F405VG) /* LQFP 100 14x14x1.4 1024Kb FLASH 192Kb SRAM */
# undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* 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 */
@@ -345,9 +439,9 @@
#elif defined(CONFIG_ARCH_CHIP_STM32F405ZG) /* LQFP 144 20x20x1.4 1024Kb FLASH 192Kb SRAM */
# undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* 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 */
@@ -376,9 +470,9 @@
#elif defined(CONFIG_ARCH_CHIP_STM32F407VE) /* LQFP-100 512Kb FLASH 192Kb SRAM */
# undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* 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 */
@@ -407,9 +501,9 @@
#elif defined(CONFIG_ARCH_CHIP_STM32F407VG) /* LQFP-100 14x14x1.4 1024Kb FLASH 192Kb SRAM */
# undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* 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 */
@@ -438,9 +532,9 @@
#elif defined(CONFIG_ARCH_CHIP_STM32F407ZE) /* LQFP-144 512Kb FLASH 192Kb SRAM */
# undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* 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 */
@@ -469,9 +563,9 @@
#elif defined(CONFIG_ARCH_CHIP_STM32F407ZG) /* LQFP 144 20x20x1.4 1024Kb FLASH 192Kb SRAM */
# undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* 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 */
@@ -500,9 +594,9 @@
#elif defined(CONFIG_ARCH_CHIP_STM32F407IE) /* LQFP 176 24x24x1.4 512Kb FLASH 192Kb SRAM */
# undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* 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 */
@@ -531,9 +625,9 @@
#elif defined(CONFIG_ARCH_CHIP_STM32F407IG) /* BGA 176; LQFP 176 24x24x1.4 1024Kb FLASH 192Kb SRAM */
# undef CONFIG_STM32_STM32F10XX /* STM32F10xxx family */
-# undef CONFIG_STM32_LOWDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
-# undef CONFIG_STM32_MEDIUMDENSITY /* STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
-# undef CONFIG_STM32_HIGHDENSITY /* STM32F101x and STM32F103x w/ 256/512 Kbytes */
+# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
+# undef CONFIG_STM32_MEDIUMDENSITY /* 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 */
diff --git a/nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h b/nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h
index 67f4ba436..7c3f7cf95 100644
--- a/nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h
+++ b/nuttx/arch/arm/include/stm32/stm32f10xxx_irq.h
@@ -61,11 +61,13 @@
* External interrupts (vectors >= 16)
*/
-#if defined(CONFIG_STM32_VALUELINE) && defined(CONFIG_STM32_MEDIUMDENSITY)
+ /* Value line devices */
+
+#if defined(CONFIG_STM32_VALUELINE)
# define STM32_IRQ_WWDG (16) /* 0: Window Watchdog interrupt */
# define STM32_IRQ_PVD (17) /* 1: PVD through EXTI Line detection interrupt */
# define STM32_IRQ_TAMPER (18) /* 2: Tamper interrupt */
-# define STM32_IRQ_RTC (19) /* 3: RTC global interrupt */
+# define STM32_IRQ_RTC (19) /* 3: RTC Wakeup through EXTI line interrupt */
# define STM32_IRQ_FLASH (20) /* 4: Flash global interrupt */
# define STM32_IRQ_RCC (21) /* 5: RCC global interrupt */
# define STM32_IRQ_EXTI0 (22) /* 6: EXTI Line 0 interrupt */
@@ -80,12 +82,18 @@
# define STM32_IRQ_DMA1CH5 (31) /* 15: DMA1 Channel 5 global interrupt */
# define STM32_IRQ_DMA1CH6 (32) /* 16: DMA1 Channel 6 global interrupt */
# define STM32_IRQ_DMA1CH7 (33) /* 17: DMA1 Channel 7 global interrupt */
-# define STM32_IRQ_ADC12 (34) /* 18: ADC1 and ADC2 global interrupt */
- /* 19-22: reserved */
+# define STM32_IRQ_ADC1 (34) /* 18: ADC1 global interrupt */
+# define STM32_IRQ_RESERVED0 (35) /* 19: Reserved 0 */
+# define STM32_IRQ_RESERVED1 (36) /* 20: Reserved 1 */
+# define STM32_IRQ_RESERVED2 (37) /* 21: Reserved 2 */
+# define STM32_IRQ_RESERVED3 (38) /* 22: Reserved 3 */
# define STM32_IRQ_EXTI95 (39) /* 23: EXTI Line[9:5] interrupts */
# define STM32_IRQ_TIM1BRK (40) /* 24: TIM1 Break interrupt */
-# define STM32_IRQ_TIM1UP (41) /* 25: TIM1 Update interrupt (TIM16 global interrupt) */
-# define STM32_IRQ_TIM1TRGCOM (42) /* 26: TIM1 Trigger and Commutation interrupts (TIM17 global interrupt) */
+# define STM32_IRQ_TIM15 (40) /* TIM15 global interrupt */
+# define STM32_IRQ_TIM1UP (41) /* 25: TIM1 Update interrupt */
+# define STM32_IRQ_TIM16 (41) /* TIM16 global interrupt */
+# define STM32_IRQ_TIM1TRGCOM (42) /* 26: TIM1 Trigger and Commutation interrupts */
+# define STM32_IRQ_TIM17 (42) /* TIM17 global interrupt */
# define STM32_IRQ_TIM1CC (43) /* 27: TIM1 Capture Compare interrupt */
# define STM32_IRQ_TIM2 (44) /* 28: TIM2 global interrupt */
# define STM32_IRQ_TIM3 (45) /* 29: TIM3 global interrupt */
@@ -100,29 +108,30 @@
# define STM32_IRQ_USART2 (54) /* 38: USART2 global interrupt */
# define STM32_IRQ_USART3 (55) /* 39: USART3 global interrupt */
# define STM32_IRQ_EXTI1510 (56) /* 40: EXTI Line[15:10] interrupts */
-# define STM32_IRQ_RTCALR (57) /* 41: RTC alarm through EXTI line interrupt */
+# define STM32_IRQ_RTCALR (57) /* 41: RTC alarms (A and B) through EXTI line interrupt */
# define STM32_IRQ_CEC (58) /* 42: CEC global interrupt */
-# if defined(CONFIG_STM32_HIGHDENSITY)
-# define STM32_IRQ_TIM12 (59) /* 43: TIM12 global interrupt */
-# define STM32_IRQ_TIM13 (60) /* 44: TIM13 global interrupt */
-# define STM32_IRQ_TIM14 (61) /* 45: TIM14 global interrupt */
- /* 46-47: reserved */
-# define STM32_IRQ_FSMC (64) /* 48: FSMC global interrupt */
- /* 49: reserved */
-# define STM32_IRQ_TIM5 (66) /* 50: TIM5 global interrupt */
-# define STM32_IRQ_SPI3 (67) /* 51: SPI1 global interrupt */
-# define STM32_IRQ_UART4 (68) /* 52: USART2 global interrupt */
-# define STM32_IRQ_UART5 (69) /* 53: USART3 global interrupt */
-# else
- /* 43-53: reserved */
-# endif
+# define STM32_IRQ_TIM12 (59) /* 43: TIM12 global interrupt */
+# define STM32_IRQ_TIM13 (60) /* 44: TIM13 global interrupt */
+# define STM32_IRQ_TIM14 (61) /* 45: TIM14 global interrupt */
+# define STM32_IRQ_RESERVED4 (62) /* 46: Reserved 4 */
+# define STM32_IRQ_RESERVED5 (63) /* 47: Reserved 5 */
+# define STM32_IRQ_FSMC (64) /* 48: FSMC global interrupt */
+# define STM32_IRQ_RESERVED6 (65) /* 49: Reserved 6 */
+# define STM32_IRQ_TIM5 (66) /* 50: TIM5 global interrupt */
+# define STM32_IRQ_SPI3 (67) /* 51: SPI3 global interrupt */
+# define STM32_IRQ_UART4 (68) /* 52: USART2 global interrupt */
+# define STM32_IRQ_UART5 (69) /* 53: USART5 global interrupt */
# define STM32_IRQ_TIM6 (70) /* 54: TIM6 global interrupt */
# define STM32_IRQ_TIM7 (71) /* 55: TIM7 global interrupt */
# define STM32_IRQ_DMA2CH1 (72) /* 56: DMA2 Channel 1 global interrupt */
# define STM32_IRQ_DMA2CH2 (73) /* 57: DMA2 Channel 2 global interrupt */
# define STM32_IRQ_DMA2CH3 (74) /* 58: DMA2 Channel 3 global interrupt */
-# define STM32_IRQ_DMA2CH45 (75) /* 59: DMA2 Channel 4 global interrupt */
-# define NR_IRQS (76)
+# define STM32_IRQ_DMA2CH45 (75) /* 59: DMA2 Channel 4 and 5 global interrupt */
+# define STM32_IRQ_DMA2CH5 (76) /* 60: DMA2 Channel 5 global interrupt */
+# define NR_IRQS (77)
+
+/* Connectivity Line Devices */
+
#elif defined(CONFIG_STM32_CONNECTIVITYLINE)
# define STM32_IRQ_WWDG (16) /* 0: Window Watchdog interrupt */
# define STM32_IRQ_PVD (17) /* 1: PVD through EXTI Line detection interrupt */
@@ -193,6 +202,9 @@
# define STM32_IRQ_CAN2SCE (82) /* 66: CAN2 SCE interrupt */
# define STM32_IRQ_OTGFS (83) /* 67: USB On The Go FS global interrupt */
# define NR_IRQS (84)
+
+/* Medium and High Density Devices */
+
#else
# define STM32_IRQ_WWDG (16) /* 0: Window Watchdog interrupt */
# define STM32_IRQ_PVD (17) /* 1: PVD through EXTI Line detection interrupt */
diff --git a/nuttx/arch/arm/src/Makefile b/nuttx/arch/arm/src/Makefile
index 74be6c18d..e44def30c 100644
--- a/nuttx/arch/arm/src/Makefile
+++ b/nuttx/arch/arm/src/Makefile
@@ -36,58 +36,90 @@
-include $(TOPDIR)/Make.defs
-include chip/Make.defs
-ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
ifeq ($(CONFIG_ARCH_CORTEXM3),y) # Cortex-M3 is ARMv7-M
-ARCH_SUBDIR = armv7-m
+ARCH_SUBDIR = armv7-m
else
ifeq ($(CONFIG_ARCH_CORTEXM4),y) # Cortex-M4 is ARMv7E-M
-ARCH_SUBDIR = armv7-m
+ARCH_SUBDIR = armv7-m
else
-ARCH_SUBDIR = arm
+ARCH_SUBDIR = arm
endif
endif
+ifeq ($(CONFIG_WINDOWS_NATIVE),y)
+ ARCH_SRCDIR = $(TOPDIR)\arch\$(CONFIG_ARCH)\src
+ NUTTX = "$(TOPDIR)\nuttx$(EXEEXT)"
+ CFLAGS += -I$(ARCH_SRCDIR)\chip
+ CFLAGS += -I$(ARCH_SRCDIR)\common
+ CFLAGS += -I$(ARCH_SRCDIR)\$(ARCH_SUBDIR)
+ CFLAGS += -I$(TOPDIR)\sched
+else
+ ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
ifeq ($(WINTOOL),y)
- NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx}"
- CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
- -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
- -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}" \
- -I "${shell cygpath -w $(TOPDIR)/sched}"
+ NUTTX = "${shell cygpath -w $(TOPDIR)/nuttx$(EXEEXT)}"
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}"
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/common}"
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/$(ARCH_SUBDIR)}"
+ CFLAGS += -I "${shell cygpath -w $(TOPDIR)/sched}"
else
- NUTTX = $(TOPDIR)/nuttx
- CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common \
- -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR) -I$(TOPDIR)/sched
+ NUTTX = "$(TOPDIR)/nuttx$(EXEEXT)"
+ CFLAGS += -I$(ARCH_SRCDIR)/chip
+ CFLAGS += -I$(ARCH_SRCDIR)/common
+ CFLAGS += -I$(ARCH_SRCDIR)/$(ARCH_SUBDIR)
+ CFLAGS += -I$(TOPDIR)/sched
+endif
endif
-HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT))
+HEAD_OBJ = $(HEAD_ASRC:.S=$(OBJEXT))
+
+ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS)
+AOBJS = $(ASRCS:.S=$(OBJEXT))
-ASRCS = $(CHIP_ASRCS) $(CMN_ASRCS)
-AOBJS = $(ASRCS:.S=$(OBJEXT))
+CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS)
+COBJS = $(CSRCS:.c=$(OBJEXT))
-CSRCS = $(CHIP_CSRCS) $(CMN_CSRCS)
-COBJS = $(CSRCS:.c=$(OBJEXT))
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
-SRCS = $(ASRCS) $(CSRCS)
-OBJS = $(AOBJS) $(COBJS)
+LDFLAGS += $(ARCHSCRIPT)
-LDFLAGS = $(ARCHSCRIPT)
-EXTRA_LIBS ?=
+EXTRA_LIBS ?=
+EXTRA_LIBPATHS ?=
+LINKLIBS ?=
+
+ifeq ($(CONFIG_WINDOWS_NATIVE),y)
+ BOARDMAKE = $(if $(wildcard .\board\Makefile),y,)
+ LIBPATHS += -L"$(TOPDIR)\lib"
+ifeq ($(BOARDMAKE),y)
+ LIBPATHS += -L"$(TOPDIR)\arch\$(CONFIG_ARCH)\src\board"
+endif
+
+else
+ BOARDMAKE = $(if $(wildcard ./board/Makefile),y,)
-LINKLIBS =
ifeq ($(WINTOOL),y)
- LIBPATHS = ${shell for path in $(LINKLIBS); do dir=`dirname $(TOPDIR)/$$path`;echo "-L\"`cygpath -w $$dir`\"";done}
- LIBPATHS += -L"${shell cygpath -w $(BOARDDIR)}"
+ LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/lib"}"
+ifeq ($(BOARDMAKE),y)
+ LIBPATHS += -L"${shell cygpath -w "$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"}"
+endif
+
else
- LIBPATHS = $(addprefix -L$(TOPDIR)/,$(dir $(LINKLIBS)))
- LIBPATHS += -L"$(BOARDDIR)"
+ LIBPATHS += -L"$(TOPDIR)/lib"
+ifeq ($(BOARDMAKE),y)
+ LIBPATHS += -L"$(TOPDIR)/arch/$(CONFIG_ARCH)/src/board"
+endif
+endif
endif
-LDLIBS = $(patsubst lib%,-l%,$(basename $(notdir $(LINKLIBS))))
-BOARDDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src/board
+LDLIBS = $(patsubst %.a,%,$(patsubst lib%,-l%,$(LINKLIBS)))
+ifeq ($(BOARDMAKE),y)
+ LDLIBS += -lboard
+endif
-LIBGCC = "${shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name}"
+LIBGCC = "${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}"
+GCC_LIBDIR := ${shell dirname $(LIBGCC)}
-VPATH = chip:common:$(ARCH_SUBDIR)
+VPATH = chip:common:$(ARCH_SUBDIR)
all: $(HEAD_OBJ) libarch$(LIBEXT)
@@ -100,20 +132,21 @@ $(COBJS): %$(OBJEXT): %.c
$(call COMPILE, $<, $@)
libarch$(LIBEXT): $(OBJS)
- @( for obj in $(OBJS) ; do \
- $(call ARCHIVE, $@, $${obj}); \
- done ; )
+ $(call ARCHIVE, $@, $(OBJS))
board/libboard$(LIBEXT):
- @$(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
-
-nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT)
- @echo "LD: nuttx"
- @$(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \
- --start-group $(LDLIBS) -lboard $(EXTRA_LIBS) $(LIBGCC) --end-group
- @$(NM) $(NUTTX)$(EXEEXT) | \
+ $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" libboard$(LIBEXT) EXTRADEFINES=$(EXTRADEFINES)
+
+nuttx$(EXEEXT): $(HEAD_OBJ) board/libboard$(LIBEXT)
+ $(Q) echo "LD: nuttx"
+ $(Q) $(LD) --entry=__start $(LDFLAGS) $(LIBPATHS) $(EXTRA_LIBPATHS) \
+ -o $(NUTTX)$(EXEEXT) $(HEAD_OBJ) $(EXTRA_OBJS) \
+ --start-group $(LDLIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group
+ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ $(Q) $(NM) $(NUTTX)$(EXEEXT) | \
grep -v '\(compiled\)\|\(\$(OBJEXT)$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
sort > $(TOPDIR)/System.map
+endif
# This is part of the top-level export target
# Note that there may not be a head object if layout is handled
@@ -121,37 +154,38 @@ nuttx: $(HEAD_OBJ) board/libboard$(LIBEXT)
export_head: board/libboard$(LIBEXT) $(HEAD_OBJ)
ifneq ($(HEAD_OBJ),)
- @if [ -d "$(EXPORT_DIR)/startup" ]; then \
+ $(Q) if [ -d "$(EXPORT_DIR)/startup" ]; then \
cp -f $(HEAD_OBJ) "$(EXPORT_DIR)/startup"; \
else \
echo "$(EXPORT_DIR)/startup does not exist"; \
- exit 1; \
- fi
+ exit 1; \
+ fi
endif
# Dependencies
.depend: Makefile chip/Make.defs $(SRCS)
- @if [ -e board/Makefile ]; then \
- $(MAKE) -C board TOPDIR="$(TOPDIR)" depend ; \
- fi
- @$(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
- $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
- @touch $@
+ifeq ($(BOARDMAKE),y)
+ $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" depend
+endif
+ $(Q) $(MKDEP) --dep-path chip --dep-path common --dep-path $(ARCH_SUBDIR) \
+ "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
+ $(Q) touch $@
depend: .depend
clean:
- @if [ -e board/Makefile ]; then \
- $(MAKE) -C board TOPDIR="$(TOPDIR)" clean ; \
- fi
- @rm -f libarch$(LIBEXT) *~ .*.swp
+ifeq ($(BOARDMAKE),y)
+ $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" clean
+endif
+ $(call DELFILE, libarch$(LIBEXT))
$(call CLEAN)
distclean: clean
- @if [ -e board/Makefile ]; then \
- $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean ; \
- fi
- @rm -f Make.dep .depend
+ifeq ($(BOARDMAKE),y)
+ $(Q) $(MAKE) -C board TOPDIR="$(TOPDIR)" distclean
+endif
+ $(call DELFILE, Make.dep)
+ $(call DELFILE, .depend)
-include Make.dep
diff --git a/nuttx/arch/arm/src/armv7-m/Kconfig b/nuttx/arch/arm/src/armv7-m/Kconfig
new file mode 100644
index 000000000..dc5aa3915
--- /dev/null
+++ b/nuttx/arch/arm/src/armv7-m/Kconfig
@@ -0,0 +1,51 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+comment "ARMV7M Configuration Options"
+
+choice
+ prompt "Toolchain Selection"
+ default ARMV7M_TOOLCHAIN_CODESOURCERYW if HOST_WINDOWS
+ default ARMV7M_TOOLCHAIN_GNU_EABI if !HOST_WINDOWS
+
+config ARMV7M_TOOLCHAIN_ATOLLIC
+ bool "Atollic Lite/Pro for Windows"
+ depends on HOST_WINDOWS
+
+config ARMV7M_TOOLCHAIN_BUILDROOT
+ bool "Buildroot (Cygwin or Linux)"
+ depends on !WINDOWS_NATIVE
+
+config ARMV7M_TOOLCHAIN_CODEREDL
+ bool "CodeRed for Linux"
+ depends on HOST_LINUX
+
+config ARMV7M_TOOLCHAIN_CODEREDW
+ bool "CodeRed for Windows"
+ depends on HOST_WINDOWS
+
+config ARMV7M_TOOLCHAIN_CODESOURCERYL
+ bool "CodeSourcery GNU toolchain under Linux"
+ depends on HOST_LINUX
+
+config ARMV7M_TOOLCHAIN_CODESOURCERYW
+ bool "CodeSourcery GNU toolchain under Windows"
+ depends on HOST_WINDOWS
+
+config ARMV7M_TOOLCHAIN_DEVKITARM
+ bool "devkitARM GNU toolchain"
+ depends on HOST_WINDOWS
+
+config ARMV7M_TOOLCHAIN_GNU_EABI
+ bool "Generic GNU EABI toolchain"
+ ---help---
+ This option should work for any modern GNU toolchain (GCC 4.5 or newer)
+ configured for arm-none-eabi.
+
+config ARMV7M_TOOLCHAIN_RAISONANCE
+ bool "STMicro Raisonance for Windows"
+ depends on HOST_WINDOWS
+
+endchoice
diff --git a/nuttx/arch/arm/src/armv7-m/Toolchain.defs b/nuttx/arch/arm/src/armv7-m/Toolchain.defs
new file mode 100644
index 000000000..e214ce8bd
--- /dev/null
+++ b/nuttx/arch/arm/src/armv7-m/Toolchain.defs
@@ -0,0 +1,266 @@
+############################################################################
+# arch/arm/src/armv7-m/Toolchain.defs
+#
+# Copyright (C) 2012 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# Setup for the selected toolchain
+
+#
+# Handle old-style chip-specific toolchain names in the absence of
+# a new-style toolchain specification, force the selection of a single
+# toolchain and allow the selected toolchain to be overridden by a
+# command-line selection.
+#
+
+ifeq ($(filter y, \
+ $(CONFIG_LPC43_ATOLLIC_LITE) \
+ $(CONFIG_STM32_ATOLLIC_LITE) \
+ $(CONFIG_LPC43_ATOLLIC_PRO) \
+ $(CONFIG_STM32_ATOLLIC_PRO) \
+ $(CONFIG_ARMV7M_TOOLCHAIN_ATOLLIC) \
+ ),y)
+ CONFIG_ARMV7M_TOOLCHAIN ?= ATOLLIC
+endif
+ifeq ($(filter y, \
+ $(CONFIG_KINETIS_BUILDROOT) \
+ $(CONFIG_LM3S_BUILDROOT) \
+ $(CONFIG_LPC17_BUILDROOT) \
+ $(CONFIG_LPC43_BUILDROOT) \
+ $(CONFIG_SAM3U_BUILDROOT) \
+ $(CONFIG_STM32_BUILDROOT) \
+ $(CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT) \
+ ),y)
+ CONFIG_ARMV7M_TOOLCHAIN ?= BUILDROOT
+endif
+ifeq ($(filter y, \
+ $(CONFIG_LPC17_CODEREDL) \
+ $(CONFIG_ARMV7M_TOOLCHAIN_CODEREDL) \
+ ),y)
+ CONFIG_ARMV7M_TOOLCHAIN ?= CODEREDL
+endif
+ifeq ($(filter y, \
+ $(CONFIG_LPC17_CODEREDW) \
+ $(CONFIG_LPC43_CODEREDW) \
+ $(CONFIG_ARMV7M_TOOLCHAIN_CODEREDW) \
+ ),y)
+ CONFIG_ARMV7M_TOOLCHAIN ?= CODEREDW
+endif
+ifeq ($(filter y, \
+ $(CONFIG_KINETIS_CODESOURCERYL) \
+ $(CONFIG_LM3S_CODESOURCERYL) \
+ $(CONFIG_LPC17_CODESOURCERYL) \
+ $(CONFIG_LPC43_CODESOURCERYL) \
+ $(CONFIG_SAM3U_CODESOURCERYL) \
+ $(CONFIG_STM32_CODESOURCERYL) \
+ $(CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL) \
+ ),y)
+ CONFIG_ARMV7M_TOOLCHAIN ?= CODESOURCERYL
+endif
+ifeq ($(filter y, \
+ $(CONFIG_KINETIS_CODESOURCERYW) \
+ $(CONFIG_LM3S_CODESOURCERYW) \
+ $(CONFIG_LPC17_CODESOURCERYW) \
+ $(CONFIG_LPC43_CODESOURCERYW) \
+ $(CONFIG_SAM3U_CODESOURCERYW) \
+ $(CONFIG_STM32_CODESOURCERYW) \
+ $(CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW) \
+ ),y)
+ CONFIG_ARMV7M_TOOLCHAIN ?= CODESOURCERYW
+endif
+ifeq ($(filter y, \
+ $(CONFIG_KINETIS_DEVKITARM) \
+ $(CONFIG_LM3S_DEVKITARM) \
+ $(CONFIG_LPC17_DEVKITARM) \
+ $(CONFIG_LPC43_DEVKITARM) \
+ $(CONFIG_SAM3U_DEVKITARM) \
+ $(CONFIG_STM32_DEVKITARM) \
+ $(CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM) \
+ ),y)
+ CONFIG_ARMV7M_TOOLCHAIN ?= DEVKITARM
+endif
+ifeq ($(filter y, \
+ $(CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI) \
+ ),y)
+ CONFIG_ARMV7M_TOOLCHAIN ?= GNU_EABI
+endif
+ifeq ($(filter y, \
+ $(CONFIG_STM32_RAISONANCE) \
+ $(CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE) \
+ ),y)
+ CONFIG_ARMV7M_TOOLCHAIN ?= RAISONANCE
+endif
+
+#
+# Supported toolchains
+#
+# TODO - It's likely that all of these toolchains now support the
+# CortexM4. Since they are all GCC-based, we could almost
+# certainly simplify this further.
+#
+# Each toolchain definition should set:
+#
+# CROSSDEV The GNU toolchain triple (command prefix)
+# ARCROSSDEV If required, an alternative prefix used when
+# invoking ar and nm.
+# ARCHCPUFLAGS CPU-specific flags selecting the instruction set
+# FPU options, etc.
+# MAXOPTIMIZATION The maximum optimization level that results in
+# reliable code generation.
+#
+
+# Atollic toolchain under Windows
+
+ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),ATOLLIC)
+ CROSSDEV = arm-atollic-eabi-
+ ARCROSSDEV = arm-atollic-eabi-
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
+ ifeq ($(CONFIG_ARCH_CORTEXM4),y)
+ ifeq ($(CONFIG_ARCH_FPU),y)
+ ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard
+ else
+ ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfloat-abi=soft
+ endif
+ else ifeq ($(CONFIG_ARCH_CORTEXM3),y)
+ ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
+ endif
+endif
+
+# NuttX buildroot under Linux or Cygwin
+
+ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),BUILDROOT)
+ # OABI
+ # CROSSDEV = arm-nuttx-elf-
+ # ARCROSSDEV = arm-nuttx-elf-
+ # ARCHCPUFLAGS = -mtune=cortex-m3 -march=armv7-m -mfloat-abi=soft
+ # EABI
+ CROSSDEV = arm-nuttx-eabi-
+ ARCROSSDEV = arm-nuttx-eabi-
+ ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
+ MAXOPTIMIZATION = -Os
+endif
+
+# Code Red RedSuite under Linux
+
+ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODEREDL)
+ CROSSDEV = arm-none-eabi-
+ ARCROSSDEV = arm-none-eabi-
+ ifeq ($(CONFIG_ARCH_CORTEXM4),y)
+ ifeq ($(CONFIG_ARCH_FPU),y)
+ ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard
+ else
+ ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfloat-abi=soft
+ endif
+ else ifeq ($(CONFIG_ARCH_CORTEXM3),y)
+ ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
+ endif
+endif
+
+# Code Red RedSuite under Windows
+
+ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODEREDW)
+ CROSSDEV = arm-none-eabi-
+ ARCROSSDEV = arm-none-eabi-
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
+ ifeq ($(CONFIG_ARCH_CORTEXM4),y)
+ ifeq ($(CONFIG_ARCH_FPU),y)
+ ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard
+ else
+ ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfloat-abi=soft
+ endif
+ else ifeq ($(CONFIG_ARCH_CORTEXM3),y)
+ ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
+ endif
+endif
+
+# CodeSourcery under Linux
+
+ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODESOURCERYL)
+ CROSSDEV = arm-none-eabi-
+ ARCROSSDEV = arm-none-eabi-
+ ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
+ MAXOPTIMIZATION = -O2
+endif
+
+# CodeSourcery under Windows
+
+ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),CODESOURCERYW)
+ CROSSDEV = arm-none-eabi-
+ ARCROSSDEV = arm-none-eabi-
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
+ ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
+endif
+
+# devkitARM under Windows
+
+ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),DEVKITARM)
+ CROSSDEV = arm-eabi-
+ ARCROSSDEV = arm-eabi-
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
+ ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
+endif
+
+# Generic GNU EABI toolchain on OS X, Linux or any typical Posix system
+
+ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),GNU_EABI)
+ CROSSDEV = arm-none-eabi-
+ ARCROSSDEV = arm-none-eabi-
+ MAXOPTIMIZATION = -O3
+ ifeq ($(CONFIG_ARCH_CORTEXM4),y)
+ ifeq ($(CONFIG_ARCH_FPU),y)
+ ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard
+ else
+ ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -march=armv7e-m -mfloat-abi=soft
+ endif
+ else ifeq ($(CONFIG_ARCH_CORTEXM3),y)
+ ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
+ endif
+endif
+
+# Raisonance RIDE7 under Windows
+
+ifeq ($(CONFIG_ARMV7M_TOOLCHAIN),RAISONANCE)
+ CROSSDEV = arm-none-eabi-
+ ARCROSSDEV = arm-none-eabi-
+ ifneq ($(CONFIG_WINDOWS_NATIVE),y)
+ WINTOOL = y
+ endif
+ ARCHCPUFLAGS = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
+endif
diff --git a/nuttx/arch/arm/src/armv7-m/memcpy.S b/nuttx/arch/arm/src/armv7-m/memcpy.S
deleted file mode 100644
index c6d3ff649..000000000
--- a/nuttx/arch/arm/src/armv7-m/memcpy.S
+++ /dev/null
@@ -1,351 +0,0 @@
-@
-@ armv7m-optimised memcpy, apparently in the public domain
-@
-@ Obtained via a posting on the Stellaris forum:
-@ http://e2e.ti.com/support/microcontrollers/stellaris_arm_cortex-m3_microcontroller/f/473/t/44360.aspx
-@
-@ Posted by rocksoft on Jul 24, 2008 10:19 AM
-@
-@ Hi,
-@
-@ I recently finished a "memcpy" replacement and thought it might be useful for others...
-@
-@ I've put some instructions and the code here:
-@
-@ http://www.rock-software.net/downloads/memcpy/
-@
-@ Hope it works for you as well as it did for me.
-@
-@ Liam.
-@ @
-@ ----------------------------------------------------------------------------
-
-.syntax unified
-
-.thumb
-
-.cpu cortex-m3
-
-@ ----------------------------------------------------------------------------
-
- .global memcpy
-
-
-@ ----------------------------------------------------------------------------
-@ Optimised "general" copy routine
-
-.text
-
-@ We have 16 possible alignment combinations of src and dst, this jump table directs the copy operation
-@ Bits: Src=00, Dst=00 - Long to Long copy
-@ Bits: Src=00, Dst=01 - Long to Byte before half word
-@ Bits: Src=00, Dst=10 - Long to Half word
-@ Bits: Src=00, Dst=11 - Long to Byte before long word
-@ Bits: Src=01, Dst=00 - Byte before half word to long
-@ Bits: Src=01, Dst=01 - Byte before half word to byte before half word - Same alignment
-@ Bits: Src=01, Dst=10 - Byte before half word to half word
-@ Bits: Src=01, Dst=11 - Byte before half word to byte before long word
-@ Bits: Src=10, Dst=00 - Half word to long word
-@ Bits: Src=10, Dst=01 - Half word to byte before half word
-@ Bits: Src=10, Dst=10 - Half word to half word - Same Alignment
-@ Bits: Src=10, Dst=11 - Half word to byte before long word
-@ Bits: Src=11, Dst=00 - Byte before long word to long word
-@ Bits: Src=11, Dst=01 - Byte before long word to byte before half word
-@ Bits: Src=11, Dst=11 - Byte before long word to half word
-@ Bits: Src=11, Dst=11 - Byte before long word to Byte before long word - Same alignment
-
-MEM_DataCopyTable:
- .byte (MEM_DataCopy0 - MEM_DataCopyJump) >> 1
- .byte (MEM_DataCopy1 - MEM_DataCopyJump) >> 1
- .byte (MEM_DataCopy2 - MEM_DataCopyJump) >> 1
- .byte (MEM_DataCopy3 - MEM_DataCopyJump) >> 1
- .byte (MEM_DataCopy4 - MEM_DataCopyJump) >> 1
- .byte (MEM_DataCopy5 - MEM_DataCopyJump) >> 1
- .byte (MEM_DataCopy6 - MEM_DataCopyJump) >> 1
- .byte (MEM_DataCopy7 - MEM_DataCopyJump) >> 1
- .byte (MEM_DataCopy8 - MEM_DataCopyJump) >> 1
- .byte (MEM_DataCopy9 - MEM_DataCopyJump) >> 1
- .byte (MEM_DataCopy10 - MEM_DataCopyJump) >> 1
- .byte (MEM_DataCopy11 - MEM_DataCopyJump) >> 1
- .byte (MEM_DataCopy12 - MEM_DataCopyJump) >> 1
- .byte (MEM_DataCopy13 - MEM_DataCopyJump) >> 1
- .byte (MEM_DataCopy14 - MEM_DataCopyJump) >> 1
- .byte (MEM_DataCopy15 - MEM_DataCopyJump) >> 1
-
- .align 2
-
-@ ----------------------------------------------------------------------------
-
-//#define 10 10
-
-MEM_LongCopyTable:
- .byte (MEM_LongCopyEnd - MEM_LongCopyJump) >> 1 @ 0 bytes left
- .byte 0 @ 4 bytes left
- .byte (1 * 10) >> 1 @ 8 bytes left
- .byte (2 * 10) >> 1 @ 12 bytes left
- .byte (3 * 10) >> 1 @ 16 bytes left
- .byte (4 * 10) >> 1 @ 20 bytes left
- .byte (5 * 10) >> 1 @ 24 bytes left
- .byte (6 * 10) >> 1 @ 28 bytes left
- .byte (7 * 10) >> 1 @ 32 bytes left
- .byte (8 * 10) >> 1 @ 36 bytes left
-
- .align 2
-
-@ ----------------------------------------------------------------------------
-@ r0 = destination, r1 = source, r2 = length
-
-.thumb_func
-
-memcpy:
- push {r14}
-
- @ This allows the inner workings to "assume" a minimum amount of bytes
- cmp r2, #4
- blt MEM_DataCopyBytes
-
- and r14, r0, #3 @ Get destination alignment bits
- bfi r14, r1, #2, #2 @ Get source alignment bits
- ldr r3, =MEM_DataCopyTable @ Jump table base
- tbb [r3, r14] @ Perform jump on src/dst alignment bits
-MEM_DataCopyJump:
-
- .align 4
-
-@ ----------------------------------------------------------------------------
-@ Bits: Src=01, Dst=01 - Byte before half word to byte before half word - Same alignment
-@ 3 bytes to read for long word aligning
-
-MEM_DataCopy5:
- ldrb r3, [r1], #0x01
- strb r3, [r0], #0x01
- sub r2, r2, #0x01
-
-@ ----------------------------------------------------------------------------
-@ Bits: Src=10, Dst=10 - Half word to half word - Same Alignment
-@ 2 bytes to read for long word aligning
-
-MEM_DataCopy10:
- ldrb r3, [r1], #0x01
- strb r3, [r0], #0x01
- sub r2, r2, #0x01
-
-@ ----------------------------------------------------------------------------
-@ Bits: Src=11, Dst=11 - Byte before long word to Byte before long word - Same alignment
-@ 1 bytes to read for long word aligning
-
-MEM_DataCopy15:
- ldrb r3, [r1], #0x01
- strb r3, [r0], #0x01
- sub r2, r2, #0x01
-
-@ ----------------------------------------------------------------------------
-@ Bits: Src=00, Dst=00 - Long to Long copy
-
-MEM_DataCopy0:
- @ Save regs
- push {r4-r12}
-
- cmp r2, #0x28
- blt MEM_DataCopy0_2
-
-MEM_DataCopy0_1:
- ldmia r1!, {r3-r12}
- stmia r0!, {r3-r12}
- sub r2, r2, #0x28
- cmp r2, #0x28
- bge MEM_DataCopy0_1
-
-MEM_DataCopy0_2:
- @ Copy remaining long words
- ldr r14, =MEM_LongCopyTable
- lsr r11, r2, #0x02
- tbb [r14, r11]
-
-MEM_LongCopyJump:
- ldr.w r3, [r1], #0x04 @ 4 bytes remain
- str.w r3, [r0], #0x04
- b MEM_LongCopyEnd
- ldmia.w r1!, {r3-r4} @ 8 bytes remain
- stmia.w r0!, {r3-r4}
- b MEM_LongCopyEnd
- ldmia.w r1!, {r3-r5} @ 12 bytes remain
- stmia.w r0!, {r3-r5}
- b MEM_LongCopyEnd
- ldmia.w r1!, {r3-r6} @ 16 bytes remain
- stmia.w r0!, {r3-r6}
- b MEM_LongCopyEnd
- ldmia.w r1!, {r3-r7} @ 20 bytes remain
- stmia.w r0!, {r3-r7}
- b MEM_LongCopyEnd
- ldmia.w r1!, {r3-r8} @ 24 bytes remain
- stmia.w r0!, {r3-r8}
- b MEM_LongCopyEnd
- ldmia.w r1!, {r3-r9} @ 28 bytes remain
- stmia.w r0!, {r3-r9}
- b MEM_LongCopyEnd
- ldmia.w r1!, {r3-r10} @ 32 bytes remain
- stmia.w r0!, {r3-r10}
- b MEM_LongCopyEnd
- ldmia.w r1!, {r3-r11} @ 36 bytes remain
- stmia.w r0!, {r3-r11}
-
-MEM_LongCopyEnd:
- pop {r4-r12}
- and r2, r2, #0x03 @ All the longs have been copied
-
-@ ----------------------------------------------------------------------------
-
-MEM_DataCopyBytes:
- @ Deal with up to 3 remaining bytes
- cmp r2, #0x00
- it eq
- popeq {pc}
- ldrb r3, [r1], #0x01
- strb r3, [r0], #0x01
- subs r2, r2, #0x01
- it eq
- popeq {pc}
- ldrb r3, [r1], #0x01
- strb r3, [r0], #0x01
- subs r2, r2, #0x01
- it eq
- popeq {pc}
- ldrb r3, [r1], #0x01
- strb r3, [r0], #0x01
- pop {pc}
-
- .align 4
-
-@ ----------------------------------------------------------------------------
-@ Bits: Src=01, Dst=11 - Byte before half word to byte before long word
-@ 3 bytes to read for long word aligning the source
-
-MEM_DataCopy7:
- ldrb r3, [r1], #0x01
- strb r3, [r0], #0x01
- sub r2, r2, #0x01
-
-@ ----------------------------------------------------------------------------
-@ Bits: Src=10, Dst=00 - Half word to long word
-@ 2 bytes to read for long word aligning the source
-
-MEM_DataCopy8:
- ldrb r3, [r1], #0x01
- strb r3, [r0], #0x01
- sub r2, r2, #0x01
-
-@ ----------------------------------------------------------------------------
-@ Bits: Src=11, Dst=01 - Byte before long word to byte before half word
-@ 1 byte to read for long word aligning the source
-
-MEM_DataCopy13:
- ldrb r3, [r1], #0x01
- strb r3, [r0], #0x01
- sub r2, r2, #0x01
-
-@ ----------------------------------------------------------------------------
-@ Bits: Src=00, Dst=10 - Long to Half word
-
-MEM_DataCopy2:
- cmp r2, #0x28
- blt MEM_DataCopy2_1
-
- @ Save regs
- push {r4-r12}
-MEM_DataCopy2_2:
- ldmia r1!, {r3-r12}
-
- strh r3, [r0], #0x02
-
- lsr r3, r3, #0x10
- bfi r3, r4, #0x10, #0x10
- lsr r4, r4, #0x10
- bfi r4, r5, #0x10, #0x10
- lsr r5, r5, #0x10
- bfi r5, r6, #0x10, #0x10
- lsr r6, r6, #0x10
- bfi r6, r7, #0x10, #0x10
- lsr r7, r7, #0x10
- bfi r7, r8, #0x10, #0x10
- lsr r8, r8, #0x10
- bfi r8, r9, #0x10, #0x10
- lsr r9, r9, #0x10
- bfi r9, r10, #0x10, #0x10
- lsr r10, r10, #0x10
- bfi r10, r11, #0x10, #0x10
- lsr r11, r11, #0x10
- bfi r11, r12, #0x10, #0x10
- stmia r0!, {r3-r11}
- lsr r12, r12, #0x10
- strh r12, [r0], #0x02
-
- sub r2, r2, #0x28
- cmp r2, #0x28
- bge MEM_DataCopy2_2
- pop {r4-r12}
-
-MEM_DataCopy2_1: @ Read longs and write 2 x half words
- cmp r2, #4
- blt MEM_DataCopyBytes
- ldr r3, [r1], #0x04
- strh r3, [r0], #0x02
- lsr r3, r3, #0x10
- strh r3, [r0], #0x02
- sub r2, r2, #0x04
- b MEM_DataCopy2
-
-@ ----------------------------------------------------------------------------
-@ Bits: Src=01, Dst=00 - Byte before half word to long
-@ Bits: Src=01, Dst=10 - Byte before half word to half word
-@ 3 bytes to read for long word aligning the source
-
-MEM_DataCopy4:
-MEM_DataCopy6:
- @ Read B and write B
- ldrb r3, [r1], #0x01
- strb r3, [r0], #0x01
- sub r2, r2, #0x01
-
-@ ----------------------------------------------------------------------------
-@ Bits: Src=10, Dst=01 - Half word to byte before half word
-@ Bits: Src=10, Dst=11 - Half word to byte before long word
-@ 2 bytes to read for long word aligning the source
-
-MEM_DataCopy9:
-MEM_DataCopy11:
- ldrb r3, [r1], #0x01
- strb r3, [r0], #0x01
- sub r2, r2, #0x01
-
-@ ----------------------------------------------------------------------------
-@ Bits: Src=11, Dst=00 - Byte before long word to long word
-@ Bits: Src=11, Dst=11 - Byte before long word to half word
-@ 1 byte to read for long word aligning the source
-
-MEM_DataCopy12:
-MEM_DataCopy14:
- @ Read B and write B
- ldrb r3, [r1], #0x01
- strb r3, [r0], #0x01
- sub r2, r2, #0x01
-
-@ ----------------------------------------------------------------------------
-@ Bits: Src=00, Dst=01 - Long to Byte before half word
-@ Bits: Src=00, Dst=11 - Long to Byte before long word
-
-MEM_DataCopy1: @ Read longs, write B->H->B
-MEM_DataCopy3:
- cmp r2, #4
- blt MEM_DataCopyBytes
- ldr r3, [r1], #0x04
- strb r3, [r0], #0x01
- lsr r3, r3, #0x08
- strh r3, [r0], #0x02
- lsr r3, r3, #0x10
- strb r3, [r0], #0x01
- sub r2, r2, #0x04
- b MEM_DataCopy3
-
-@ ----------------------------------------------------------------------------
-
diff --git a/nuttx/arch/arm/src/armv7-m/up_elf.c b/nuttx/arch/arm/src/armv7-m/up_elf.c
new file mode 100644
index 000000000..b838a6905
--- /dev/null
+++ b/nuttx/arch/arm/src/armv7-m/up_elf.c
@@ -0,0 +1,450 @@
+/****************************************************************************
+ * arch/arm/src/armv7-m/up_elf.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdlib.h>
+#include <elf32.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/elf.h>
+#include <nuttx/arch.h>
+#include <nuttx/binfmt/elf.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: arch_checkarch
+ *
+ * Description:
+ * Given the ELF header in 'hdr', verify that the ELF file is appropriate
+ * for the current, configured architecture. Every architecture that uses
+ * the ELF loader must provide this function.
+ *
+ * Input Parameters:
+ * hdr - The ELF header read from the ELF file.
+ *
+ * Returned Value:
+ * True if the architecture supports this ELF file.
+ *
+ ****************************************************************************/
+
+bool arch_checkarch(FAR const Elf32_Ehdr *ehdr)
+{
+ /* Make sure it's an ARM executable */
+
+ if (ehdr->e_machine != EM_ARM)
+ {
+ bdbg("Not for ARM: e_machine=%04x\n", ehdr->e_machine);
+ return -ENOEXEC;
+ }
+
+ /* Make sure that 32-bit objects are supported */
+
+ if (ehdr->e_ident[EI_CLASS] != ELFCLASS32)
+ {
+ bdbg("Need 32-bit objects: e_ident[EI_CLASS]=%02x\n", ehdr->e_ident[EI_CLASS]);
+ return -ENOEXEC;
+ }
+
+ /* Verify endian-ness */
+
+#ifdef CONFIG_ENDIAN_BIG
+ if (ehdr->e_ident[EI_DATA] != ELFDATA2MSB)
+#else
+ if (ehdr->e_ident[EI_DATA] != ELFDATA2LSB)
+#endif
+ {
+ bdbg("Wrong endian-ness: e_ident[EI_DATA]=%02x\n", ehdr->e_ident[EI_DATA]);
+ return -ENOEXEC;
+ }
+
+ /* TODO: Check ABI here. */
+ return OK;
+}
+
+/****************************************************************************
+ * Name: arch_relocate and arch_relocateadd
+ *
+ * Description:
+ * Perform on architecture-specific ELF relocation. Every architecture
+ * that uses the ELF loader must provide this function.
+ *
+ * Input Parameters:
+ * rel - The relocation type
+ * sym - The ELF symbol structure containing the fully resolved value.
+ * addr - The address that requires the relocation.
+ *
+ * Returned Value:
+ * Zero (OK) if the relocation was successful. Otherwise, a negated errno
+ * value indicating the cause of the relocation failure.
+ *
+ ****************************************************************************/
+
+int arch_relocate(FAR const Elf32_Rel *rel, FAR const Elf32_Sym *sym,
+ uintptr_t addr)
+{
+ int32_t offset;
+ uint32_t upper_insn;
+ uint32_t lower_insn;
+
+ switch (ELF32_R_TYPE(rel->r_info))
+ {
+ case R_ARM_NONE:
+ {
+ /* No relocation */
+ }
+ break;
+
+ case R_ARM_PC24:
+ case R_ARM_CALL:
+ case R_ARM_JUMP24:
+ {
+ bvdbg("Performing PC24 [%d] link at addr %08lx [%08lx] to sym '%s' st_value=%08lx\n",
+ ELF32_R_TYPE(rel->r_info), (long)addr, (long)(*(uint32_t*)addr),
+ sym, (long)sym->st_value);
+
+ offset = (*(uint32_t*)addr & 0x00ffffff) << 2;
+ if (offset & 0x02000000)
+ {
+ offset -= 0x04000000;
+ }
+
+ offset += sym->st_value - addr;
+ if (offset & 3 || offset <= (int32_t) 0xfe000000 || offset >= (int32_t) 0x02000000)
+ {
+ bdbg(" ERROR: PC24 [%d] relocation out of range, offset=%08lx\n",
+ ELF32_R_TYPE(rel->r_info), offset);
+
+ return -EINVAL;
+ }
+
+ offset >>= 2;
+
+ *(uint32_t*)addr &= 0xff000000;
+ *(uint32_t*)addr |= offset & 0x00ffffff;
+ }
+ break;
+
+ case R_ARM_ABS32:
+ case R_ARM_TARGET1: /* New ABI: TARGET1 always treated as ABS32 */
+ {
+ bvdbg("Performing ABS32 link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n",
+ (long)addr, (long)(*(uint32_t*)addr), sym, (long)sym->st_value);
+
+ *(uint32_t*)addr += sym->st_value;
+ }
+ break;
+
+ case R_ARM_THM_CALL:
+ case R_ARM_THM_JUMP24:
+ {
+ uint32_t S;
+ uint32_t J1;
+ uint32_t J2;
+
+ /* Thumb BL and B.W instructions. Encoding:
+ *
+ * upper_insn:
+ *
+ * 1 1 1 1 1 1
+ * 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0
+ * +----------+---+-------------------------------+--------------+
+ * |1 1 1 |OP1| OP2 | | 32-Bit Instructions
+ * +----------+---+--+-----+----------------------+--------------+
+ * |1 1 1 | 1 0| S | imm10 | BL Instruction
+ * +----------+------+-----+-------------------------------------+
+ *
+ * lower_insn:
+ *
+ * 1 1 1 1 1 1
+ * 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0
+ * +---+---------------------------------------------------------+
+ * |OP | | 32-Bit Instructions
+ * +---+--+---+---+---+------------------------------------------+
+ * |1 1 |J1 | 1 |J2 | imm11 | BL Instruction
+ * +------+---+---+---+------------------------------------------+
+ *
+ * The branch target is encoded in these bits:
+ *
+ * S = upper_insn[10]
+ * imm10 = upper_insn[0:9]
+ * imm11 = lower_insn[0:10]
+ * J1 = lower_insn[13]
+ * J2 = lower_insn[11]
+ */
+
+ upper_insn = (uint32_t)(*(uint16_t*)addr);
+ lower_insn = (uint32_t)(*(uint16_t*)(addr + 2));
+
+ bvdbg("Performing THM_JUMP24 [%d] link at addr=%08lx [%04x %04x] to sym=%p st_value=%08lx\n",
+ ELF32_R_TYPE(rel->r_info), (long)addr, (int)upper_insn, (int)lower_insn,
+ sym, (long)sym->st_value);
+
+ /* Extract the 25-bit offset from the 32-bit instruction:
+ *
+ * offset[24] = S
+ * offset[23] = ~(J1 ^ S)
+ * offset[22] = ~(J2 ^ S)]
+ * offset[12:21] = imm10
+ * offset[1:11] = imm11
+ * offset[0] = 0
+ */
+
+ S = (upper_insn >> 10) & 1;
+ J1 = (lower_insn >> 13) & 1;
+ J2 = (lower_insn >> 11) & 1;
+
+ offset = (S << 24) | /* S - > offset[24] */
+ ((~(J1 ^ S) & 1) << 23) | /* J1 -> offset[23] */
+ ((~(J2 ^ S) & 1) << 22) | /* J2 -> offset[22] */
+ ((upper_insn & 0x03ff) << 12) | /* imm10 -> offset[12:21] */
+ ((lower_insn & 0x07ff) << 1); /* imm11 -> offset[1:11] */
+ /* 0 -> offset[0] */
+
+ /* Sign extend */
+
+ if (offset & 0x01000000)
+ {
+ offset -= 0x02000000;
+ }
+
+ /* And perform the relocation */
+
+ bvdbg(" S=%d J1=%d J2=%d offset=%08lx branch target=%08lx\n",
+ S, J1, J2, (long)offset, offset + sym->st_value - addr);
+
+ offset += sym->st_value - addr;
+
+ /* Is this a function symbol? If so, then the branch target must be
+ * an odd Thumb address
+ */
+
+ if (ELF32_ST_TYPE(sym->st_info) == STT_FUNC && (offset & 1) == 0)
+ {
+ bdbg(" ERROR: JUMP24 [%d] requires odd offset, offset=%08lx\n",
+ ELF32_R_TYPE(rel->r_info), offset);
+
+ return -EINVAL;
+ }
+
+ /* Check the range of the offset */
+
+ if (offset <= (int32_t)0xff000000 || offset >= (int32_t)0x01000000)
+ {
+ bdbg(" ERROR: JUMP24 [%d] relocation out of range, branch taget=%08lx\n",
+ ELF32_R_TYPE(rel->r_info), offset);
+
+ return -EINVAL;
+ }
+
+ /* Now, reconstruct the 32-bit instruction using the new, relocated
+ * branch target.
+ */
+
+ S = (offset >> 24) & 1;
+ J1 = S ^ (~(offset >> 23) & 1);
+ J2 = S ^ (~(offset >> 22) & 1);
+
+ upper_insn = ((upper_insn & 0xf800) | (S << 10) | ((offset >> 12) & 0x03ff));
+ *(uint16_t*)addr = (uint16_t)upper_insn;
+
+ lower_insn = ((lower_insn & 0xd000) | (J1 << 13) | (J2 << 11) | ((offset >> 1) & 0x07ff));
+ *(uint16_t*)(addr + 2) = (uint16_t)lower_insn;
+
+ bvdbg(" S=%d J1=%d J2=%d insn [%04x %04x]\n",
+ S, J1, J2, (int)upper_insn, (int)lower_insn);
+ }
+ break;
+
+ case R_ARM_V4BX:
+ {
+ bvdbg("Performing V4BX link at addr=%08lx [%08lx]\n",
+ (long)addr, (long)(*(uint32_t*)addr));
+
+ /* Preserve only Rm and the condition code */
+
+ *(uint32_t*)addr &= 0xf000000f;
+
+ /* Change instruction to 'mov pc, Rm' */
+
+ *(uint32_t*)addr |= 0x01a0f000;
+ }
+ break;
+
+ case R_ARM_PREL31:
+ {
+ bvdbg("Performing PREL31 link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n",
+ (long)addr, (long)(*(uint32_t*)addr), sym, (long)sym->st_value);
+
+ offset = *(uint32_t*)addr + sym->st_value - addr;
+ *(uint32_t*)addr = offset & 0x7fffffff;
+ }
+ break;
+
+ case R_ARM_MOVW_ABS_NC:
+ case R_ARM_MOVT_ABS:
+ {
+ bvdbg("Performing MOVx_ABS [%d] link at addr=%08lx [%08lx] to sym=%p st_value=%08lx\n",
+ ELF32_R_TYPE(rel->r_info), (long)addr, (long)(*(uint32_t*)addr),
+ sym, (long)sym->st_value);
+
+ offset = *(uint32_t*)addr;
+ offset = ((offset & 0xf0000) >> 4) | (offset & 0xfff);
+ offset = (offset ^ 0x8000) - 0x8000;
+
+ offset += sym->st_value;
+ if (ELF32_R_TYPE(rel->r_info) == R_ARM_MOVT_ABS)
+ {
+ offset >>= 16;
+ }
+
+ *(uint32_t*)addr &= 0xfff0f000;
+ *(uint32_t*)addr |= ((offset & 0xf000) << 4) | (offset & 0x0fff);
+ }
+ break;
+
+ case R_ARM_THM_MOVW_ABS_NC:
+ case R_ARM_THM_MOVT_ABS:
+ {
+ /* Thumb BL and B.W instructions. Encoding:
+ *
+ * upper_insn:
+ *
+ * 1 1 1 1 1 1
+ * 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0
+ * +----------+---+-------------------------------+--------------+
+ * |1 1 1 |OP1| OP2 | | 32-Bit Instructions
+ * +----------+---+--+-----+----------------------+--------------+
+ * |1 1 1 | 1 0| i | 1 0 1 1 0 0 | imm4 | MOVT Instruction
+ * +----------+------+-----+----------------------+--------------+
+ *
+ * lower_insn:
+ *
+ * 1 1 1 1 1 1
+ * 5 4 3 2 1 0 9 8 7 6 5 4 3 2 1 0
+ * +---+---------------------------------------------------------+
+ * |OP | | 32-Bit Instructions
+ * +---+----------+--------------+-------------------------------+
+ * |0 | imm3 | Rd | imm8 | MOVT Instruction
+ * +---+----------+--------------+-------------------------------+
+ *
+ * The 16-bit immediate value is encoded in these bits:
+ *
+ * i = imm16[11] = upper_insn[10]
+ * imm4 = imm16[12:15] = upper_insn[3:0]
+ * imm3 = imm16[8:10] = lower_insn[14:12]
+ * imm8 = imm16[0:7] = lower_insn[7:0]
+ */
+
+ upper_insn = (uint32_t)(*(uint16_t*)addr);
+ lower_insn = (uint32_t)(*(uint16_t*)(addr + 2));
+
+ bvdbg("Performing THM_MOVx [%d] link at addr=%08lx [%04x %04x] to sym=%p st_value=%08lx\n",
+ ELF32_R_TYPE(rel->r_info), (long)addr, (int)upper_insn, (int)lower_insn,
+ sym, (long)sym->st_value);
+
+ /* Extract the 16-bit offset from the 32-bit instruction */
+
+ offset = ((upper_insn & 0x000f) << 12) | /* imm4 -> imm16[8:10] */
+ ((upper_insn & 0x0400) << 1) | /* i -> imm16[11] */
+ ((lower_insn & 0x7000) >> 4) | /* imm3 -> imm16[8:10] */
+ (lower_insn & 0x00ff); /* imm8 -> imm16[0:7] */
+
+ /* Sign extend */
+
+ offset = (offset ^ 0x8000) - 0x8000;
+
+ /* And perform the relocation */
+
+ bvdbg(" offset=%08lx branch target=%08lx\n",
+ (long)offset, offset + sym->st_value);
+
+ offset += sym->st_value;
+
+ /* Update the immediate value in the instruction. For MOVW we want the bottom
+ * 16-bits; for MOVT we want the top 16-bits.
+ */
+
+ if (ELF32_R_TYPE(rel->r_info) == R_ARM_THM_MOVT_ABS)
+ {
+ offset >>= 16;
+ }
+
+ upper_insn = ((upper_insn & 0xfbf0) | ((offset & 0xf000) >> 12) | ((offset & 0x0800) >> 1));
+ *(uint16_t*)addr = (uint16_t)upper_insn;
+
+ lower_insn = ((lower_insn & 0x8f00) | ((offset & 0x0700) << 4) | (offset & 0x00ff));
+ *(uint16_t*)(addr + 2) = (uint16_t)lower_insn;
+
+ bvdbg(" insn [%04x %04x]\n",
+ (int)upper_insn, (int)lower_insn);
+ }
+ break;
+
+ default:
+ bdbg("Unsupported relocation: %d\n", ELF32_R_TYPE(rel->r_info));
+ return -EINVAL;
+ }
+
+ return OK;
+}
+
+int arch_relocateadd(FAR const Elf32_Rela *rel, FAR const Elf32_Sym *sym,
+ uintptr_t addr)
+{
+ bdbg("RELA relocation not supported\n");
+ return -ENOSYS;
+}
+
diff --git a/nuttx/arch/arm/src/armv7-m/up_exception.S b/nuttx/arch/arm/src/armv7-m/up_exception.S
index 31d8dbb0c..c9f216027 100644
--- a/nuttx/arch/arm/src/armv7-m/up_exception.S
+++ b/nuttx/arch/arm/src/armv7-m/up_exception.S
@@ -134,9 +134,9 @@ exception_common:
#if CONFIG_ARCH_INTERRUPTSTACK > 3
ldr sp, =g_intstackbase
- push r1 /* Save the MSP on the interrupt stack */
+ push {r1} /* Save the MSP on the interrupt stack */
bl up_doirq /* R0=IRQ, R1=register save area on stack */
- pop r1 /* Recover R1=main stack pointer */
+ pop {r1} /* Recover R1=main stack pointer */
#else
msr msp, r1 /* We are using the main stack pointer */
bl up_doirq /* R0=IRQ, R1=register save area on stack */
diff --git a/nuttx/arch/arm/src/armv7-m/up_hardfault.c b/nuttx/arch/arm/src/armv7-m/up_hardfault.c
index cb3ce9e8a..c30015ad2 100644
--- a/nuttx/arch/arm/src/armv7-m/up_hardfault.c
+++ b/nuttx/arch/arm/src/armv7-m/up_hardfault.c
@@ -57,9 +57,7 @@
/* Debug output from this file may interfere with context switching! */
-#undef DEBUG_HARDFAULTS /* Define to debug hard faults */
-
-#ifdef DEBUG_HARDFAULTS
+#ifdef CONFIG_DEBUG_HARDFAULT
# define hfdbg(format, arg...) lldbg(format, ##arg)
#else
# define hfdbg(x...)
diff --git a/nuttx/arch/arm/src/armv7-m/up_memcpy.S b/nuttx/arch/arm/src/armv7-m/up_memcpy.S
new file mode 100644
index 000000000..a154cab61
--- /dev/null
+++ b/nuttx/arch/arm/src/armv7-m/up_memcpy.S
@@ -0,0 +1,416 @@
+/************************************************************************************
+ * nuttx/arch/arm/src/armv7-m/up_memcpy.S
+ *
+ * armv7m-optimised memcpy, contributed by Mike Smith. Apparently in the public
+ * domain and is re-released here under the modified BSD license:
+ *
+ * Obtained via a posting on the Stellaris forum:
+ * http://e2e.ti.com/support/microcontrollers/\
+ * stellaris_arm_cortex-m3_microcontroller/f/473/t/44360.aspx
+ *
+ * Posted by rocksoft on Jul 24, 2008 10:19 AM
+ *
+ * Hi,
+ *
+ * I recently finished a "memcpy" replacement and thought it might be useful for
+ * others...
+ *
+ * I've put some instructions and the code here:
+ *
+ * http://www.rock-software.net/downloads/memcpy/
+ *
+ * Hope it works for you as well as it did for me.
+ *
+ * Liam.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Global Symbols
+ ************************************************************************************/
+
+ .global memcpy
+
+ .syntax unified
+ .thumb
+ .cpu cortex-m3
+ .file "up_memcpy.S"
+
+/************************************************************************************
+ * .text
+ ************************************************************************************/
+
+ .text
+
+/************************************************************************************
+ * Private Constant Data
+ ************************************************************************************/
+
+/* We have 16 possible alignment combinations of src and dst, this jump table
+ * directs the copy operation
+ *
+ * Bits: Src=00, Dst=00 - Long to Long copy
+ * Bits: Src=00, Dst=01 - Long to Byte before half word
+ * Bits: Src=00, Dst=10 - Long to Half word
+ * Bits: Src=00, Dst=11 - Long to Byte before long word
+ * Bits: Src=01, Dst=00 - Byte before half word to long
+ * Bits: Src=01, Dst=01 - Byte before half word to byte before half word -
+ * Same alignment
+ * Bits: Src=01, Dst=10 - Byte before half word to half word
+ * Bits: Src=01, Dst=11 - Byte before half word to byte before long word
+ * Bits: Src=10, Dst=00 - Half word to long word
+ * Bits: Src=10, Dst=01 - Half word to byte before half word
+ * Bits: Src=10, Dst=10 - Half word to half word - Same Alignment
+ * Bits: Src=10, Dst=11 - Half word to byte before long word
+ * Bits: Src=11, Dst=00 - Byte before long word to long word
+ * Bits: Src=11, Dst=01 - Byte before long word to byte before half word
+ * Bits: Src=11, Dst=11 - Byte before long word to half word
+ * Bits: Src=11, Dst=11 - Byte before long word to Byte before long word -
+ * Same alignment
+ */
+
+MEM_DataCopyTable:
+ .byte (MEM_DataCopy0 - MEM_DataCopyJump) >> 1
+ .byte (MEM_DataCopy1 - MEM_DataCopyJump) >> 1
+ .byte (MEM_DataCopy2 - MEM_DataCopyJump) >> 1
+ .byte (MEM_DataCopy3 - MEM_DataCopyJump) >> 1
+ .byte (MEM_DataCopy4 - MEM_DataCopyJump) >> 1
+ .byte (MEM_DataCopy5 - MEM_DataCopyJump) >> 1
+ .byte (MEM_DataCopy6 - MEM_DataCopyJump) >> 1
+ .byte (MEM_DataCopy7 - MEM_DataCopyJump) >> 1
+ .byte (MEM_DataCopy8 - MEM_DataCopyJump) >> 1
+ .byte (MEM_DataCopy9 - MEM_DataCopyJump) >> 1
+ .byte (MEM_DataCopy10 - MEM_DataCopyJump) >> 1
+ .byte (MEM_DataCopy11 - MEM_DataCopyJump) >> 1
+ .byte (MEM_DataCopy12 - MEM_DataCopyJump) >> 1
+ .byte (MEM_DataCopy13 - MEM_DataCopyJump) >> 1
+ .byte (MEM_DataCopy14 - MEM_DataCopyJump) >> 1
+ .byte (MEM_DataCopy15 - MEM_DataCopyJump) >> 1
+
+ .align 2
+
+MEM_LongCopyTable:
+ .byte (MEM_LongCopyEnd - MEM_LongCopyJump) >> 1 /* 0 bytes left */
+ .byte 0 /* 4 bytes left */
+ .byte (1 * 10) >> 1 /* 8 bytes left */
+ .byte (2 * 10) >> 1 /* 12 bytes left */
+ .byte (3 * 10) >> 1 /* 16 bytes left */
+ .byte (4 * 10) >> 1 /* 20 bytes left */
+ .byte (5 * 10) >> 1 /* 24 bytes left */
+ .byte (6 * 10) >> 1 /* 28 bytes left */
+ .byte (7 * 10) >> 1 /* 32 bytes left */
+ .byte (8 * 10) >> 1 /* 36 bytes left */
+
+ .align 2
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+/************************************************************************************
+ * Name: memcpy
+ *
+ * Description:
+ * Optimised "general" copy routine
+ *
+ * Input Parameters:
+ * r0 = destination, r1 = source, r2 = length
+ *
+ ************************************************************************************/
+
+ .thumb_func
+memcpy:
+ push {r14}
+
+ /* This allows the inner workings to "assume" a minimum amount of bytes */
+ /* Quickly check for very short copies */
+
+ cmp r2, #4
+ blt MEM_DataCopyBytes
+
+ and r14, r0, #3 /* Get destination alignment bits */
+ bfi r14, r1, #2, #2 /* Get source alignment bits */
+ ldr r3, =MEM_DataCopyTable /* Jump table base */
+ tbb [r3, r14] /* Perform jump on src/dst alignment bits */
+MEM_DataCopyJump:
+
+ .align 4
+
+/* Bits: Src=01, Dst=01 - Byte before half word to byte before half word - Same alignment
+ * 3 bytes to read for long word aligning
+ */
+
+MEM_DataCopy5:
+ ldrb r3, [r1], #0x01
+ strb r3, [r0], #0x01
+ sub r2, r2, #0x01
+
+/* Bits: Src=10, Dst=10 - Half word to half word - Same Alignment
+ * 2 bytes to read for long word aligning
+ */
+
+MEM_DataCopy10:
+ ldrb r3, [r1], #0x01
+ strb r3, [r0], #0x01
+ sub r2, r2, #0x01
+
+/* Bits: Src=11, Dst=11 - Byte before long word to Byte before long word - Same alignment
+ * 1 bytes to read for long word aligning
+ */
+
+MEM_DataCopy15:
+ ldrb r3, [r1], #0x01
+ strb r3, [r0], #0x01
+ sub r2, r2, #0x01
+
+/* Bits: Src=00, Dst=00 - Long to Long copy */
+
+MEM_DataCopy0:
+ /* Save regs that may be used by memcpy */
+
+ push {r4-r12}
+
+ /* Check for short word-aligned copy */
+
+ cmp r2, #0x28
+ blt MEM_DataCopy0_2
+
+ /* Bulk copy loop */
+
+MEM_DataCopy0_1:
+ ldmia r1!, {r3-r12}
+ stmia r0!, {r3-r12}
+ sub r2, r2, #0x28
+ cmp r2, #0x28
+ bge MEM_DataCopy0_1
+
+ /* Copy remaining long words */
+
+MEM_DataCopy0_2:
+ /* Copy remaining long words */
+
+ ldr r14, =MEM_LongCopyTable
+ lsr r11, r2, #0x02
+ tbb [r14, r11]
+
+ /* longword copy branch table anchor */
+
+MEM_LongCopyJump:
+ ldr.w r3, [r1], #0x04 /* 4 bytes remain */
+ str.w r3, [r0], #0x04
+ b MEM_LongCopyEnd
+ ldmia.w r1!, {r3-r4} /* 8 bytes remain */
+ stmia.w r0!, {r3-r4}
+ b MEM_LongCopyEnd
+ ldmia.w r1!, {r3-r5} /* 12 bytes remain */
+ stmia.w r0!, {r3-r5}
+ b MEM_LongCopyEnd
+ ldmia.w r1!, {r3-r6} /* 16 bytes remain */
+ stmia.w r0!, {r3-r6}
+ b MEM_LongCopyEnd
+ ldmia.w r1!, {r3-r7} /* 20 bytes remain */
+ stmia.w r0!, {r3-r7}
+ b MEM_LongCopyEnd
+ ldmia.w r1!, {r3-r8} /* 24 bytes remain */
+ stmia.w r0!, {r3-r8}
+ b MEM_LongCopyEnd
+ ldmia.w r1!, {r3-r9} /* 28 bytes remain */
+ stmia.w r0!, {r3-r9}
+ b MEM_LongCopyEnd
+ ldmia.w r1!, {r3-r10} /* 32 bytes remain */
+ stmia.w r0!, {r3-r10}
+ b MEM_LongCopyEnd
+ ldmia.w r1!, {r3-r11} /* 36 bytes remain */
+ stmia.w r0!, {r3-r11}
+
+MEM_LongCopyEnd:
+ pop {r4-r12}
+ and r2, r2, #0x03 /* All the longs have been copied */
+
+ /* Deal with up to 3 remaining bytes */
+
+MEM_DataCopyBytes:
+ /* Deal with up to 3 remaining bytes */
+
+ cmp r2, #0x00
+ it eq
+ popeq {pc}
+ ldrb r3, [r1], #0x01
+ strb r3, [r0], #0x01
+ subs r2, r2, #0x01
+ it eq
+ popeq {pc}
+ ldrb r3, [r1], #0x01
+ strb r3, [r0], #0x01
+ subs r2, r2, #0x01
+ it eq
+ popeq {pc}
+ ldrb r3, [r1], #0x01
+ strb r3, [r0], #0x01
+ pop {pc}
+
+ .align 4
+
+/* Bits: Src=01, Dst=11 - Byte before half word to byte before long word
+ * 3 bytes to read for long word aligning the source
+ */
+
+MEM_DataCopy7:
+ ldrb r3, [r1], #0x01
+ strb r3, [r0], #0x01
+ sub r2, r2, #0x01
+
+/* Bits: Src=10, Dst=00 - Half word to long word
+ * 2 bytes to read for long word aligning the source
+ */
+
+MEM_DataCopy8:
+ ldrb r3, [r1], #0x01
+ strb r3, [r0], #0x01
+ sub r2, r2, #0x01
+
+/* Bits: Src=11, Dst=01 - Byte before long word to byte before half word
+ * 1 byte to read for long word aligning the source
+ */
+
+MEM_DataCopy13:
+ ldrb r3, [r1], #0x01
+ strb r3, [r0], #0x01
+ sub r2, r2, #0x01
+
+/* Bits: Src=00, Dst=10 - Long to Half word */
+
+MEM_DataCopy2:
+ cmp r2, #0x28
+ blt MEM_DataCopy2_1
+
+ /* Save regs */
+
+ push {r4-r12}
+
+ /* Bulk copy loop */
+
+MEM_DataCopy2_2:
+ ldmia r1!, {r3-r12}
+
+ strh r3, [r0], #0x02
+
+ lsr r3, r3, #0x10
+ bfi r3, r4, #0x10, #0x10
+ lsr r4, r4, #0x10
+ bfi r4, r5, #0x10, #0x10
+ lsr r5, r5, #0x10
+ bfi r5, r6, #0x10, #0x10
+ lsr r6, r6, #0x10
+ bfi r6, r7, #0x10, #0x10
+ lsr r7, r7, #0x10
+ bfi r7, r8, #0x10, #0x10
+ lsr r8, r8, #0x10
+ bfi r8, r9, #0x10, #0x10
+ lsr r9, r9, #0x10
+ bfi r9, r10, #0x10, #0x10
+ lsr r10, r10, #0x10
+ bfi r10, r11, #0x10, #0x10
+ lsr r11, r11, #0x10
+ bfi r11, r12, #0x10, #0x10
+ stmia r0!, {r3-r11}
+ lsr r12, r12, #0x10
+ strh r12, [r0], #0x02
+
+ sub r2, r2, #0x28
+ cmp r2, #0x28
+ bge MEM_DataCopy2_2
+ pop {r4-r12}
+
+MEM_DataCopy2_1: /* Read longs and write 2 x half words */
+ cmp r2, #4
+ blt MEM_DataCopyBytes
+ ldr r3, [r1], #0x04
+ strh r3, [r0], #0x02
+ lsr r3, r3, #0x10
+ strh r3, [r0], #0x02
+ sub r2, r2, #0x04
+ b MEM_DataCopy2
+
+/* Bits: Src=01, Dst=00 - Byte before half word to long
+ * Bits: Src=01, Dst=10 - Byte before half word to half word
+ * 3 bytes to read for long word aligning the source
+ */
+
+MEM_DataCopy4:
+MEM_DataCopy6:
+ /* Read B and write B */
+
+ ldrb r3, [r1], #0x01
+ strb r3, [r0], #0x01
+ sub r2, r2, #0x01
+
+/* Bits: Src=10, Dst=01 - Half word to byte before half word
+ * Bits: Src=10, Dst=11 - Half word to byte before long word
+ * 2 bytes to read for long word aligning the source
+ */
+
+MEM_DataCopy9:
+MEM_DataCopy11:
+ ldrb r3, [r1], #0x01
+ strb r3, [r0], #0x01
+ sub r2, r2, #0x01
+
+/* Bits: Src=11, Dst=00 -chm Byte before long word to long word
+ * Bits: Src=11, Dst=11 - Byte before long word to half word
+ * 1 byte to read for long word aligning the source
+ */
+
+MEM_DataCopy12:
+MEM_DataCopy14:
+ /* Read B and write B */
+
+ ldrb r3, [r1], #0x01
+ strb r3, [r0], #0x01
+ sub r2, r2, #0x01
+
+/* Bits: Src=00, Dst=01 - Long to Byte before half word
+ * Bits: Src=00, Dst=11 - Long to Byte before long word
+ */
+
+MEM_DataCopy1: /* Read longs, write B->H->B */
+MEM_DataCopy3:
+ cmp r2, #4
+ blt MEM_DataCopyBytes
+ ldr r3, [r1], #0x04
+ strb r3, [r0], #0x01
+ lsr r3, r3, #0x08
+ strh r3, [r0], #0x02
+ lsr r3, r3, #0x10
+ strb r3, [r0], #0x01
+ sub r2, r2, #0x04
+ b MEM_DataCopy3
+
+ .size memcpy, .-memcpy
+ .end
diff --git a/nuttx/arch/arm/src/common/arm-elf.h b/nuttx/arch/arm/src/common/arm-elf.h
new file mode 100644
index 000000000..fac387b11
--- /dev/null
+++ b/nuttx/arch/arm/src/common/arm-elf.h
@@ -0,0 +1,53 @@
+/****************************************************************************
+ * arch/arm/src/common/arm-elf.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_ARM_ELF_H
+#define __ARCH_ARM_SRC_ARM_ELF_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_ARM_ELF_H */
diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig
index 2f9100236..99dde3209 100644
--- a/nuttx/arch/arm/src/stm32/Kconfig
+++ b/nuttx/arch/arm/src/stm32/Kconfig
@@ -34,6 +34,27 @@ config ARCH_CHIP_STM32F100RB
select STM32_STM32F10XX
select STM32_VALUELINE
+config ARCH_CHIP_STM32F100RC
+ bool "STM32F100RC"
+ select ARCH_CORTEXM3
+ select STM32_STM32F10XX
+ select STM32_VALUELINE
+ select STM32_HIGHDENSITY
+
+config ARCH_CHIP_STM32F100RD
+ bool "STM32F100RD"
+ select ARCH_CORTEXM3
+ select STM32_STM32F10XX
+ select STM32_VALUELINE
+ select STM32_HIGHDENSITY
+
+config ARCH_CHIP_STM32F100RE
+ bool "STM32F100RE"
+ select ARCH_CORTEXM3
+ select STM32_STM32F10XX
+ select STM32_VALUELINE
+ select STM32_HIGHDENSITY
+
config ARCH_CHIP_STM32F100V8
bool "STM32F100V8"
select ARCH_CORTEXM3
@@ -46,6 +67,27 @@ config ARCH_CHIP_STM32F100VB
select STM32_STM32F10XX
select STM32_VALUELINE
+config ARCH_CHIP_STM32F100VC
+ bool "STM32F100VC"
+ select ARCH_CORTEXM3
+ select STM32_STM32F10XX
+ select STM32_VALUELINE
+ select STM32_HIGHDENSITY
+
+config ARCH_CHIP_STM32F100VD
+ bool "STM32F100VD"
+ select ARCH_CORTEXM3
+ select STM32_STM32F10XX
+ select STM32_VALUELINE
+ select STM32_HIGHDENSITY
+
+config ARCH_CHIP_STM32F100VE
+ bool "STM32F100VE"
+ select ARCH_CORTEXM3
+ select STM32_STM32F10XX
+ select STM32_VALUELINE
+ select STM32_HIGHDENSITY
+
config ARCH_CHIP_STM32F103RET6
bool "STM32F103RET6"
select ARCH_CORTEXM3
@@ -108,7 +150,7 @@ config ARCH_CHIP_STM32F407VE
config ARCH_CHIP_STM32F407VG
bool "STM32F407VG"
- select ARCH_CORTEXM3
+ select ARCH_CORTEXM4
select STM32_STM32F40XX
config ARCH_CHIP_STM32F407ZE
@@ -151,37 +193,10 @@ config STM32_STM32F20XX
config STM32_STM32F40XX
bool
-choice
- prompt "Toolchain Selection"
- default STM32_CODESOURCERYW
- depends on ARCH_CHIP_STM32
-
-config STM32_CODESOURCERYW
- bool "CodeSourcery for Windows"
-
-config STM32_CODESOURCERYL
- bool "CodeSourcery for Linux"
-
-config STM32_ATOLLIC_LITE
- bool "Atollic Lite for Windows"
-
-config STM32_ATOLLIC_PRO
- bool "Atollic Pro for Windows"
-
-config STM32_DEVKITARM
- bool "DevkitARM (Windows)"
-
-config STM32_RAISONANCE
- bool "STMicro Raisonance for Windows"
-
-config STM32_BUILDROOT
- bool "NuttX buildroot (Cygwin or Linux)"
-
-endchoice
-
config STM32_DFU
bool "DFU bootloader"
default n
+ depends on !STM32_VALUELINE
---help---
Configure and position code for use with the STMicro DFU bootloader. Do
not select this option if you will load code using JTAG/SWM.
@@ -197,25 +212,13 @@ config STM32_ADC2
bool "ADC2"
default n
select STM32_ADC
+ depends on !STM32_VALUELINE
config STM32_ADC3
bool "ADC3"
default n
select STM32_ADC
-
-config STM32_CRC
- bool "CRC"
- default n
-
-config STM32_DMA1
- bool "DMA1"
- default n
- select ARCH_DMA
-
-config STM32_DMA2
- bool "DMA2"
- default n
- select ARCH_DMA
+ depends on !STM32_VALUELINE
config STM32_BKP
bool "BKP"
@@ -232,6 +235,7 @@ config STM32_CAN1
default n
select CAN
select STM32_CAN
+ depends on !STM32_VALUELINE
config STM32_CAN2
bool "CAN2"
@@ -245,11 +249,31 @@ config STM32_CCMDATARAM
default n
depends on STM32_STM32F40XX
+config STM32_CEC
+ bool "CEC"
+ default n
+ depends on STM32_VALUELINE
+
+config STM32_CRC
+ bool "CRC"
+ default n
+
config STM32_CRYP
bool "CRYP"
default n
depends on STM32_STM32F20XX || STM32_STM32F40XX
+config STM32_DMA1
+ bool "DMA1"
+ default n
+ select ARCH_DMA
+
+config STM32_DMA2
+ bool "DMA2"
+ default n
+ select ARCH_DMA
+ depends on !STM32_VALUELINE || (STM32_VALUELINE && STM32_HIGHDENSITY)
+
config STM32_DAC1
bool "DAC1"
default n
@@ -274,7 +298,7 @@ config STM32_ETHMAC
config STM32_FSMC
bool "FSMC"
default n
- depends on !STM32_CONNECTIVITYLINE
+ depends on !STM32_CONNECTIVITYLINE && (STM32_HIGHDENSITY || STM32_STM32F20XX || STM32_STM32F40XX)
config STM32_HASH
bool "HASH"
@@ -325,7 +349,7 @@ config STM32_RNG
config STM32_SDIO
bool "SDIO"
default n
- depends on !STM32_CONNECTIVITYLINE
+ depends on !STM32_CONNECTIVITYLINE && !STM32_VALUELINE
config STM32_SPI1
bool "SPI1"
@@ -342,7 +366,7 @@ config STM32_SPI2
config STM32_SPI3
bool "SPI3"
default n
- depends on STM32_CONNECTIVITYLINE || STM32_STM32F20XX || STM32_STM32F40XX
+ depends on STM32_CONNECTIVITYLINE || STM32_STM32F20XX || STM32_STM32F40XX || (STM32_VALUELINE && STM32_HIGHDENSITY)
select SPI
select STM32_SPI
@@ -382,6 +406,7 @@ config STM32_TIM7
config STM32_TIM8
bool "TIM8"
default n
+ depends on !STM32_VALUELINE
config STM32_TIM9
bool "TIM9"
@@ -401,17 +426,32 @@ config STM32_TIM11
config STM32_TIM12
bool "TIM12"
default n
- depends on STM32_STM32F20XX || STM32_STM32F40XX
+ depends on STM32_STM32F20XX || STM32_STM32F40XX || STM32_VALUELINE
config STM32_TIM13
bool "TIM13"
default n
- depends on STM32_STM32F20XX || STM32_STM32F40XX
+ depends on STM32_STM32F20XX || STM32_STM32F40XX || STM32_VALUELINE
config STM32_TIM14
bool "TIM14"
default n
- depends on STM32_STM32F20XX || STM32_STM32F40XX
+ depends on STM32_STM32F20XX || STM32_STM32F40XX || STM32_VALUELINE
+
+config STM32_TIM15
+ bool "TIM15"
+ default n
+ depends on STM32_VALUELINE
+
+config STM32_TIM16
+ bool "TIM16"
+ default n
+ depends on STM32_VALUELINE
+
+config STM32_TIM17
+ bool "TIM17"
+ default n
+ depends on STM32_VALUELINE
config STM32_USART1
bool "USART1"
@@ -447,7 +487,7 @@ config STM32_USART6
config STM32_USB
bool "USB Device"
default n
- depends on STM32_STM32F10XX
+ depends on STM32_STM32F10XX && !STM32_VALUELINE
select USBDEV
config STM32_WWDG
@@ -475,6 +515,52 @@ config STM32_CAN
menu "Alternate Pin Mapping"
choice
+ prompt "CAN1 Alternate Pin Mappings"
+ depends on STM32_STM32F10XX && STM32_CAN1
+ default STM32_CAN1_NO_REMAP
+
+config STM32_CAN1_NO_REMAP
+ bool "No pin remapping"
+
+config STM32_CAN1_REMAP1
+ bool "CAN1 alternate pin remapping #1"
+
+config STM32_CAN1_REMAP2
+ bool "CAN1 alternate pin remapping #2"
+
+endchoice
+
+config STM32_CAN2_REMAP
+ bool "CAN2 Alternate Pin Mapping"
+ default n
+ depends on STM32_CONNECTIVITYLINE && STM32_CAN2
+
+config STM32_CEC_REMAP
+ bool "CEC Alternate Pin Mapping"
+ default n
+ depends on STM32_STM32F10XX && STM32_CEC
+
+config STM32_ETH_REMAP
+ bool "Ethernet Alternate Pin Mapping"
+ default n
+ depends on STM32_CONNECTIVITYLINE && STM32_ETHMAC
+
+config STM32_I2C1_REMAP
+ bool "I2C1 Alternate Pin Mapping"
+ default n
+ depends on STM32_STM32F10XX && STM32_I2C1
+
+config STM32_SPI1_REMAP
+ bool "SPI1 Alternate Pin Mapping"
+ default n
+ depends on STM32_STM32F10XX && STM32_SPI1
+
+config STM32_SPI3_REMAP
+ bool "SPI3 Alternate Pin Mapping"
+ default n
+ depends on STM32_STM32F10XX && STM32_SPI3 && !STM32_VALUELINE
+
+choice
prompt "TIM1 Alternate Pin Mappings"
depends on STM32_STM32F10XX && STM32_TIM1
default STM32_TIM1_NO_REMAP
@@ -530,6 +616,51 @@ config STM32_TIM4_REMAP
default n
depends on STM32_STM32F10XX && STM32_TIM4
+config STM32_TIM9_REMAP
+ bool "TIM9 Alternate Pin Mapping"
+ default n
+ depends on STM32_STM32F10XX && STM32_TIM9
+
+config STM32_TIM10_REMAP
+ bool "TIM10 Alternate Pin Mapping"
+ default n
+ depends on STM32_STM32F10XX && STM32_TIM10
+
+config STM32_TIM11_REMAP
+ bool "TIM11 Alternate Pin Mapping"
+ default n
+ depends on STM32_STM32F10XX && STM32_TIM11
+
+config STM32_TIM12_REMAP
+ bool "TIM12 Alternate Pin Mapping"
+ default n
+ depends on STM32_STM32F10XX && STM32_TIM12
+
+config STM32_TIM13_REMAP
+ bool "TIM13 Alternate Pin Mapping"
+ default n
+ depends on STM32_STM32F10XX && STM32_TIM13
+
+config STM32_TIM14_REMAP
+ bool "TIM14 Alternate Pin Mapping"
+ default n
+ depends on STM32_STM32F10XX && STM32_TIM14
+
+config STM32_TIM15_REMAP
+ bool "TIM15 Alternate Pin Mapping"
+ default n
+ depends on STM32_STM32F10XX && STM32_TIM15
+
+config STM32_TIM16_REMAP
+ bool "TIM16 Alternate Pin Mapping"
+ default n
+ depends on STM32_STM32F10XX && STM32_TIM16
+
+config STM32_TIM17_REMAP
+ bool "TIM17 Alternate Pin Mapping"
+ default n
+ depends on STM32_STM32F10XX && STM32_TIM17
+
config STM32_USART1_REMAP
bool "USART1 Alternate Pin Mapping"
default n
@@ -556,48 +687,16 @@ config STM32_USART3_PARTIAL_REMAP
endchoice
-config STM32_SPI1_REMAP
- bool "SPI1 Alternate Pin Mapping"
- default n
- depends on STM32_STM32F10XX && STM32_SPI1
-
-config STM32_SPI3_REMAP
- bool "SPI3 Alternate Pin Mapping"
- default n
- depends on STM32_STM32F10XX && STM32_SPI3
-
-config STM32_I2C1_REMAP
- bool "I2C1 Alternate Pin Mapping"
- default n
- depends on STM32_STM32F10XX && STM32_I2C1
-
-choice
- prompt "CAN1 Alternate Pin Mappings"
- depends on STM32_STM32F10XX && STM32_CAN1
- default STM32_CAN1_NO_REMAP
-
-config STM32_CAN1_NO_REMAP
- bool "No pin remapping"
-
-config STM32_CAN1_REMAP1
- bool "CAN1 alternate pin remapping #1"
-
-config STM32_CAN1_REMAP2
- bool "CAN1 alternate pin remapping #2"
-
-endchoice
-
-config STM32_CAN2_REMAP
- bool "CAN2 Alternate Pin Mapping"
- default n
- depends on STM32_CONNECTIVITYLINE && STM32_CAN2
+endmenu
-config STM32_ETH_REMAP
- bool "Ethernet Alternate Pin Mapping"
+config STM32_FLASH_PREFETCH
+ bool "Enable FLASH Pre-fetch"
+ depends on STM32_STM32F20XX || STM32_STM32F40XX
default n
- depends on STM32_CONNECTIVITYLINE && STM32_ETHMAC
-
-endmenu
+ ---help---
+ Enable FLASH prefetch and F2 and F4 parts (FLASH pre-fetch is always enabled
+ on F1 parts). Some early revisions of F4 parts do not support FLASH pre-fetch
+ properly and enabling this option may interfere with ADC accuracy.
choice
prompt "JTAG Configuration"
@@ -636,9 +735,11 @@ config ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG
config STM32_CCMEXCLUDE
bool "Exclude CCM SRAM from the heap"
depends on STM32_STM32F20XX || STM32_STM32F40XX
- default y if ARCH_DMA
+ default y if ARCH_DMA || ELF
---help---
- Exclude CCM SRAM from the HEAP because it cannot be used for DMA.
+ Exclude CCM SRAM from the HEAP because (1) it cannot be used for DMA
+ and (2) it appears to be impossible to execute ELF modules from CCM
+ RAM.
config STM32_FSMC_SRAM
bool "External SRAM on FSMC"
@@ -663,6 +764,7 @@ config STM32_TIM1_PWM
config STM32_TIM1_CHANNEL
int "TIM1 PWM Output Channel"
default 1
+ range 1 4
depends on STM32_TIM1_PWM
---help---
If TIM1 is enabled for PWM usage, you also need specifies the timer output
@@ -673,7 +775,7 @@ config STM32_TIM2_PWM
default n
depends on STM32_TIM2
---help---
- Reserve timer 1 for use by PWM
+ Reserve timer 2 for use by PWM
Timer devices may be used for different purposes. One special purpose is
to generate modulated outputs for such things as motor control. If STM32_TIM2
@@ -683,6 +785,7 @@ config STM32_TIM2_PWM
config STM32_TIM2_CHANNEL
int "TIM2 PWM Output Channel"
default 1
+ range 1 4
depends on STM32_TIM2_PWM
---help---
If TIM2 is enabled for PWM usage, you also need specifies the timer output
@@ -693,7 +796,7 @@ config STM32_TIM3_PWM
default n
depends on STM32_TIM3
---help---
- Reserve timer 1 for use by PWM
+ Reserve timer 3 for use by PWM
Timer devices may be used for different purposes. One special purpose is
to generate modulated outputs for such things as motor control. If STM32_TIM3
@@ -703,6 +806,7 @@ config STM32_TIM3_PWM
config STM32_TIM3_CHANNEL
int "TIM3 PWM Output Channel"
default 1
+ range 1 4
depends on STM32_TIM3_PWM
---help---
If TIM3 is enabled for PWM usage, you also need specifies the timer output
@@ -713,7 +817,7 @@ config STM32_TIM4_PWM
default n
depends on STM32_TIM4
---help---
- Reserve timer 1 for use by PWM
+ Reserve timer 4 for use by PWM
Timer devices may be used for different purposes. One special purpose is
to generate modulated outputs for such things as motor control. If STM32_TIM4
@@ -723,6 +827,7 @@ config STM32_TIM4_PWM
config STM32_TIM4_CHANNEL
int "TIM4 PWM Output Channel"
default 1
+ range 1 4
depends on STM32_TIM4_PWM
---help---
If TIM4 is enabled for PWM usage, you also need specifies the timer output
@@ -733,7 +838,7 @@ config STM32_TIM5_PWM
default n
depends on STM32_TIM5
---help---
- Reserve timer 1 for use by PWM
+ Reserve timer 5 for use by PWM
Timer devices may be used for different purposes. One special purpose is
to generate modulated outputs for such things as motor control. If STM32_TIM5
@@ -743,6 +848,7 @@ config STM32_TIM5_PWM
config STM32_TIM5_CHANNEL
int "TIM5 PWM Output Channel"
default 1
+ range 1 4
depends on STM32_TIM5_PWM
---help---
If TIM5 is enabled for PWM usage, you also need specifies the timer output
@@ -753,7 +859,7 @@ config STM32_TIM8_PWM
default n
depends on STM32_TIM8
---help---
- Reserve timer 1 for use by PWM
+ Reserve timer 8 for use by PWM
Timer devices may be used for different purposes. One special purpose is
to generate modulated outputs for such things as motor control. If STM32_TIM8
@@ -763,6 +869,7 @@ config STM32_TIM8_PWM
config STM32_TIM8_CHANNEL
int "TIM8 PWM Output Channel"
default 1
+ range 1 4
depends on STM32_TIM8_PWM
---help---
If TIM8 is enabled for PWM usage, you also need specifies the timer output
@@ -773,7 +880,7 @@ config STM32_TIM9_PWM
default n
depends on STM32_TIM9
---help---
- Reserve timer 1 for use by PWM
+ Reserve timer 9 for use by PWM
Timer devices may be used for different purposes. One special purpose is
to generate modulated outputs for such things as motor control. If STM32_TIM9
@@ -783,6 +890,7 @@ config STM32_TIM9_PWM
config STM32_TIM9_CHANNEL
int "TIM9 PWM Output Channel"
default 1
+ range 1 4
depends on STM32_TIM9_PWM
---help---
If TIM9 is enabled for PWM usage, you also need specifies the timer output
@@ -793,7 +901,7 @@ config STM32_TIM10_PWM
default n
depends on STM32_TIM10
---help---
- Reserve timer 1 for use by PWM
+ Reserve timer 10 for use by PWM
Timer devices may be used for different purposes. One special purpose is
to generate modulated outputs for such things as motor control. If STM32_TIM10
@@ -803,6 +911,7 @@ config STM32_TIM10_PWM
config STM32_TIM10_CHANNEL
int "TIM10 PWM Output Channel"
default 1
+ range 1 4
depends on STM32_TIM10_PWM
---help---
If TIM10 is enabled for PWM usage, you also need specifies the timer output
@@ -813,7 +922,7 @@ config STM32_TIM11_PWM
default n
depends on STM32_TIM11
---help---
- Reserve timer 1 for use by PWM
+ Reserve timer 11 for use by PWM
Timer devices may be used for different purposes. One special purpose is
to generate modulated outputs for such things as motor control. If STM32_TIM11
@@ -823,6 +932,7 @@ config STM32_TIM11_PWM
config STM32_TIM11_CHANNEL
int "TIM11 PWM Output Channel"
default 1
+ range 1 4
depends on STM32_TIM11_PWM
---help---
If TIM11 is enabled for PWM usage, you also need specifies the timer output
@@ -833,7 +943,7 @@ config STM32_TIM12_PWM
default n
depends on STM32_TIM12
---help---
- Reserve timer 1 for use by PWM
+ Reserve timer 12 for use by PWM
Timer devices may be used for different purposes. One special purpose is
to generate modulated outputs for such things as motor control. If STM32_TIM12
@@ -843,6 +953,7 @@ config STM32_TIM12_PWM
config STM32_TIM12_CHANNEL
int "TIM12 PWM Output Channel"
default 1
+ range 1 4
depends on STM32_TIM12_PWM
---help---
If TIM12 is enabled for PWM usage, you also need specifies the timer output
@@ -853,7 +964,7 @@ config STM32_TIM13_PWM
default n
depends on STM32_TIM13
---help---
- Reserve timer 1 for use by PWM
+ Reserve timer 13 for use by PWM
Timer devices may be used for different purposes. One special purpose is
to generate modulated outputs for such things as motor control. If STM32_TIM13
@@ -863,6 +974,7 @@ config STM32_TIM13_PWM
config STM32_TIM13_CHANNEL
int "TIM13 PWM Output Channel"
default 1
+ range 1 4
depends on STM32_TIM13_PWM
---help---
If TIM13 is enabled for PWM usage, you also need specifies the timer output
@@ -873,7 +985,7 @@ config STM32_TIM14_PWM
default n
depends on STM32_TIM14
---help---
- Reserve timer 1 for use by PWM
+ Reserve timer 14 for use by PWM
Timer devices may be used for different purposes. One special purpose is
to generate modulated outputs for such things as motor control. If STM32_TIM14
@@ -883,11 +995,75 @@ config STM32_TIM14_PWM
config STM32_TIM14_CHANNEL
int "TIM14 PWM Output Channel"
default 1
+ range 1 4
depends on STM32_TIM14_PWM
---help---
If TIM14 is enabled for PWM usage, you also need specifies the timer output
channel {1,..,4}
+config STM32_TIM15_PWM
+ bool "TIM15 PWM"
+ default n
+ depends on STM32_TIM15
+ ---help---
+ Reserve timer 15 for use by PWM
+
+ Timer devices may be used for different purposes. One special purpose is
+ to generate modulated outputs for such things as motor control. If STM32_TIM15
+ is defined then THIS following may also be defined to indicate that
+ the timer is intended to be used for pulsed output modulation.
+
+config STM32_TIM15_CHANNEL
+ int "TIM15 PWM Output Channel"
+ default 1
+ range 1 2
+ depends on STM32_TIM15_PWM
+ ---help---
+ If TIM15 is enabled for PWM usage, you also need specifies the timer output
+ channel {1,2}
+
+config STM32_TIM16_PWM
+ bool "TIM16 PWM"
+ default n
+ depends on STM32_TIM16
+ ---help---
+ Reserve timer 16 for use by PWM
+
+ Timer devices may be used for different purposes. One special purpose is
+ to generate modulated outputs for such things as motor control. If STM32_TIM16
+ is defined then THIS following may also be defined to indicate that
+ the timer is intended to be used for pulsed output modulation.
+
+config STM32_TIM16_CHANNEL
+ int "TIM16 PWM Output Channel"
+ default 1
+ range 1 1
+ depends on STM32_TIM16_PWM
+ ---help---
+ If TIM16 is enabled for PWM usage, you also need specifies the timer output
+ channel {1}
+
+config STM32_TIM17_PWM
+ bool "TIM17 PWM"
+ default n
+ depends on STM32_TIM17
+ ---help---
+ Reserve timer 17 for use by PWM
+
+ Timer devices may be used for different purposes. One special purpose is
+ to generate modulated outputs for such things as motor control. If STM32_TIM17
+ is defined then THIS following may also be defined to indicate that
+ the timer is intended to be used for pulsed output modulation.
+
+config STM32_TIM17_CHANNEL
+ int "TIM17 PWM Output Channel"
+ default 1
+ range 1 1
+ depends on STM32_TIM17_PWM
+ ---help---
+ If TIM17 is enabled for PWM usage, you also need specifies the timer output
+ channel {1}
+
config STM32_TIM1_ADC
bool "TIM1 ADC"
default n
@@ -909,16 +1085,22 @@ choice
config STM32_TIM1_ADC1
bool "TIM1 ADC channel 1"
+ depends on STM32_ADC1
+ select HAVE_ADC1_TIMER
---help---
Reserve TIM1 to trigger ADC1
config STM32_TIM1_ADC2
bool "TIM1 ADC channel 2"
+ depends on STM32_ADC2
+ select HAVE_ADC2_TIMER
---help---
Reserve TIM1 to trigger ADC2
config STM32_TIM1_ADC3
bool "TIM1 ADC channel 3"
+ depends on STM32_ADC3
+ select HAVE_ADC3_TIMER
---help---
Reserve TIM1 to trigger ADC3
@@ -945,16 +1127,22 @@ choice
config STM32_TIM2_ADC1
bool "TIM2 ADC channel 1"
+ depends on STM32_ADC1
+ select HAVE_ADC1_TIMER
---help---
Reserve TIM2 to trigger ADC1
config STM32_TIM2_ADC2
bool "TIM2 ADC channel 2"
+ depends on STM32_ADC2
+ select HAVE_ADC2_TIMER
---help---
Reserve TIM2 to trigger ADC2
config STM32_TIM2_ADC3
bool "TIM2 ADC channel 3"
+ depends on STM32_ADC3
+ select HAVE_ADC3_TIMER
---help---
Reserve TIM2 to trigger ADC3
@@ -981,16 +1169,22 @@ choice
config STM32_TIM3_ADC1
bool "TIM3 ADC channel 1"
+ depends on STM32_ADC1
+ select HAVE_ADC1_TIMER
---help---
Reserve TIM3 to trigger ADC1
config STM32_TIM3_ADC2
bool "TIM3 ADC channel 2"
+ depends on STM32_ADC2
+ select HAVE_ADC2_TIMER
---help---
Reserve TIM3 to trigger ADC2
config STM32_TIM3_ADC3
bool "TIM3 ADC channel 3"
+ depends on STM32_ADC3
+ select HAVE_ADC3_TIMER
---help---
Reserve TIM3 to trigger ADC3
@@ -1017,16 +1211,22 @@ choice
config STM32_TIM4_ADC1
bool "TIM4 ADC channel 1"
+ depends on STM32_ADC1
+ select HAVE_ADC1_TIMER
---help---
Reserve TIM4 to trigger ADC1
config STM32_TIM4_ADC2
bool "TIM4 ADC channel 2"
+ depends on STM32_ADC2
+ select HAVE_ADC2_TIMER
---help---
Reserve TIM4 to trigger ADC2
config STM32_TIM4_ADC3
bool "TIM4 ADC channel 3"
+ depends on STM32_ADC3
+ select HAVE_ADC3_TIMER
---help---
Reserve TIM4 to trigger ADC3
@@ -1053,16 +1253,22 @@ choice
config STM32_TIM5_ADC1
bool "TIM5 ADC channel 1"
+ depends on STM32_ADC1
+ select HAVE_ADC1_TIMER
---help---
Reserve TIM5 to trigger ADC1
config STM32_TIM5_ADC2
bool "TIM5 ADC channel 2"
+ depends on STM32_ADC2
+ select HAVE_ADC2_TIMER
---help---
Reserve TIM5 to trigger ADC2
config STM32_TIM5_ADC3
bool "TIM5 ADC channel 3"
+ depends on STM32_ADC3
+ select HAVE_ADC3_TIMER
---help---
Reserve TIM5 to trigger ADC3
@@ -1089,21 +1295,81 @@ choice
config STM32_TIM8_ADC1
bool "TIM8 ADC channel 1"
+ depends on STM32_ADC1
+ select HAVE_ADC1_TIMER
---help---
Reserve TIM8 to trigger ADC1
config STM32_TIM8_ADC2
bool "TIM8 ADC channel 2"
+ depends on STM32_ADC2
+ select HAVE_ADC2_TIMER
---help---
Reserve TIM8 to trigger ADC2
config STM32_TIM8_ADC3
bool "TIM8 ADC channel 3"
+ depends on STM32_ADC3
+ select HAVE_ADC3_TIMER
---help---
Reserve TIM8 to trigger ADC3
endchoice
+config HAVE_ADC1_TIMER
+ bool
+
+config HAVE_ADC2_TIMER
+ bool
+
+config HAVE_ADC3_TIMER
+ bool
+
+config STM32_ADC1_SAMPLE_FREQUENCY
+ int "ADC1 Sampling Frequency"
+ default 100
+ depends on HAVE_ADC1_TIMER
+ ---help---
+ ADC1 sampling frequency. Default: 100Hz
+
+config STM32_ADC1_TIMTRIG
+ int "ADC1 Timer Trigger"
+ default 0
+ range 0 4
+ depends on HAVE_ADC1_TIMER
+ ---help---
+ Values 0:CC1 1:CC2 2:CC3 3:CC4 4:TRGO
+
+config STM32_ADC2_SAMPLE_FREQUENCY
+ int "ADC2 Sampling Frequency"
+ default 100
+ depends on HAVE_ADC2_TIMER
+ ---help---
+ ADC2 sampling frequency. Default: 100Hz
+
+config STM32_ADC2_TIMTRIG
+ int "ADC2 Timer Trigger"
+ default 0
+ range 0 4
+ depends on HAVE_ADC2_TIMER
+ ---help---
+ Values 0:CC1 1:CC2 2:CC3 3:CC4 4:TRGO
+
+config STM32_ADC3_SAMPLE_FREQUENCY
+ int "ADC3 Sampling Frequency"
+ default 100
+ depends on HAVE_ADC3_TIMER
+ ---help---
+ ADC3 sampling frequency. Default: 100Hz
+
+config STM32_ADC3_TIMTRIG
+ int "ADC3 Timer Trigger"
+ default 0
+ range 0 4
+ depends on HAVE_ADC3_TIMER
+ ---help---
+ Values 0:CC1 1:CC2 2:CC3 3:CC4 4:TRGO
+
config STM32_TIM1_DAC
bool "TIM1 DAC"
default n
@@ -1140,7 +1406,7 @@ config STM32_TIM2_DAC
default n
depends on STM32_TIM2 && STM32_DAC
---help---
- Reserve timer 1 for use by DAC
+ Reserve timer 2 for use by DAC
Timer devices may be used for different purposes. If STM32_TIM2 is
defined then the following may also be defined to indicate that the
@@ -1171,7 +1437,7 @@ config STM32_TIM3_DAC
default n
depends on STM32_TIM3 && STM32_DAC
---help---
- Reserve timer 1 for use by DAC
+ Reserve timer 3 for use by DAC
Timer devices may be used for different purposes. If STM32_TIM3 is
defined then the following may also be defined to indicate that the
@@ -1202,7 +1468,7 @@ config STM32_TIM4_DAC
default n
depends on STM32_TIM4 && STM32_DAC
---help---
- Reserve timer 1 for use by DAC
+ Reserve timer 4 for use by DAC
Timer devices may be used for different purposes. If STM32_TIM4 is
defined then the following may also be defined to indicate that the
@@ -1233,7 +1499,7 @@ config STM32_TIM5_DAC
default n
depends on STM32_TIM5 && STM32_DAC
---help---
- Reserve timer 1 for use by DAC
+ Reserve timer 5 for use by DAC
Timer devices may be used for different purposes. If STM32_TIM5 is
defined then the following may also be defined to indicate that the
@@ -1264,7 +1530,7 @@ config STM32_TIM6_DAC
default n
depends on STM32_TIM6 && STM32_DAC
---help---
- Reserve timer 1 for use by DAC
+ Reserve timer 6 for use by DAC
Timer devices may be used for different purposes. If STM32_TIM6 is
defined then the following may also be defined to indicate that the
@@ -1295,7 +1561,7 @@ config STM32_TIM7_DAC
default n
depends on STM32_TIM7 && STM32_DAC
---help---
- Reserve timer 1 for use by DAC
+ Reserve timer 7 for use by DAC
Timer devices may be used for different purposes. If STM32_TIM7 is
defined then the following may also be defined to indicate that the
@@ -1326,7 +1592,7 @@ config STM32_TIM8_DAC
default n
depends on STM32_TIM8 && STM32_DAC
---help---
- Reserve timer 1 for use by DAC
+ Reserve timer 8 for use by DAC
Timer devices may be used for different purposes. If STM32_TIM8 is
defined then the following may also be defined to indicate that the
@@ -1357,7 +1623,7 @@ config STM32_TIM9_DAC
default n
depends on STM32_TIM9 && STM32_DAC
---help---
- Reserve timer 1 for use by DAC
+ Reserve timer 9 for use by DAC
Timer devices may be used for different purposes. If STM32_TIM9 is
defined then the following may also be defined to indicate that the
@@ -1388,7 +1654,7 @@ config STM32_TIM10_DAC
default n
depends on STM32_TIM10 && STM32_DAC
---help---
- Reserve timer 1 for use by DAC
+ Reserve timer 10 for use by DAC
Timer devices may be used for different purposes. If STM32_TIM10 is
defined then the following may also be defined to indicate that the
@@ -1419,7 +1685,7 @@ config STM32_TIM11_DAC
default n
depends on STM32_TIM11 && STM32_DAC
---help---
- Reserve timer 1 for use by DAC
+ Reserve timer 11 for use by DAC
Timer devices may be used for different purposes. If STM32_TIM11 is
defined then the following may also be defined to indicate that the
@@ -1450,7 +1716,7 @@ config STM32_TIM12_DAC
default n
depends on STM32_TIM12 && STM32_DAC
---help---
- Reserve timer 1 for use by DAC
+ Reserve timer 12 for use by DAC
Timer devices may be used for different purposes. If STM32_TIM12 is
defined then the following may also be defined to indicate that the
@@ -1481,7 +1747,7 @@ config STM32_TIM13_DAC
default n
depends on STM32_TIM13 && STM32_DAC
---help---
- Reserve timer 1 for use by DAC
+ Reserve timer 13 for use by DAC
Timer devices may be used for different purposes. If STM32_TIM13 is
defined then the following may also be defined to indicate that the
@@ -1512,7 +1778,7 @@ config STM32_TIM14_DAC
default n
depends on STM32_TIM14 && STM32_DAC
---help---
- Reserve timer 1 for use by DAC
+ Reserve timer 14 for use by DAC
Timer devices may be used for different purposes. If STM32_TIM14 is
defined then the following may also be defined to indicate that the
@@ -1538,6 +1804,27 @@ config STM32_TIM14_DAC2
endchoice
+menu "U[S]ART Configuration"
+ depends on STM32_USART1 || STM32_USART2 || STM32_USART3 || STM32_USART4 || STM32_USART5 || STM32_USART6
+
+config USART1_RS485
+ bool "RS-485 on USART1"
+ default n
+ depends on STM32_USART1
+ ---help---
+ Enable RS-485 interface on USART1. Your board config will have to
+ provide GPIO_USART1_RS485_DIR pin definition. Currently it cannot be
+ used with USART1_RXDMA.
+
+config USART1_RS485_DIR_POLARITY
+ int "USART1 RS-485 DIR pin polarity"
+ default 1
+ range 0 1
+ depends on USART1_RS485
+ ---help---
+ Polarity of DIR pin for RS-485 on USART1. Set to state on DIR pin which
+ enables TX (0 - low / nTXEN, 1 - high / TXEN).
+
config USART1_RXDMA
bool "USART1 Rx DMA"
default n
@@ -1545,6 +1832,24 @@ config USART1_RXDMA
---help---
In high data rate usage, Rx DMA may eliminate Rx overrun errors
+config USART2_RS485
+ bool "RS-485 on USART2"
+ default n
+ depends on STM32_USART2
+ ---help---
+ Enable RS-485 interface on USART2. Your board config will have to
+ provide GPIO_USART2_RS485_DIR pin definition. Currently it cannot be
+ used with USART2_RXDMA.
+
+config USART2_RS485_DIR_POLARITY
+ int "USART2 RS-485 DIR pin polarity"
+ default 1
+ range 0 1
+ depends on USART2_RS485
+ ---help---
+ Polarity of DIR pin for RS-485 on USART2. Set to state on DIR pin which
+ enables TX (0 - low / nTXEN, 1 - high / TXEN).
+
config USART2_RXDMA
bool "USART2 Rx DMA"
default n
@@ -1552,6 +1857,24 @@ config USART2_RXDMA
---help---
In high data rate usage, Rx DMA may eliminate Rx overrun errors
+config USART3_RS485
+ bool "RS-485 on USART3"
+ default n
+ depends on STM32_USART3
+ ---help---
+ Enable RS-485 interface on USART3. Your board config will have to
+ provide GPIO_USART3_RS485_DIR pin definition. Currently it cannot be
+ used with USART3_RXDMA.
+
+config USART3_RS485_DIR_POLARITY
+ int "USART3 RS-485 DIR pin polarity"
+ default 1
+ range 0 1
+ depends on USART3_RS485
+ ---help---
+ Polarity of DIR pin for RS-485 on USART3. Set to state on DIR pin which
+ enables TX (0 - low / nTXEN, 1 - high / TXEN).
+
config USART3_RXDMA
bool "USART3 Rx DMA"
default n
@@ -1559,6 +1882,24 @@ config USART3_RXDMA
---help---
In high data rate usage, Rx DMA may eliminate Rx overrun errors
+config UART4_RS485
+ bool "RS-485 on UART4"
+ default n
+ depends on STM32_UART4
+ ---help---
+ Enable RS-485 interface on UART4. Your board config will have to
+ provide GPIO_UART4_RS485_DIR pin definition. Currently it cannot be
+ used with UART4_RXDMA.
+
+config UART4_RS485_DIR_POLARITY
+ int "UART4 RS-485 DIR pin polarity"
+ default 1
+ range 0 1
+ depends on UART4_RS485
+ ---help---
+ Polarity of DIR pin for RS-485 on UART4. Set to state on DIR pin which
+ enables TX (0 - low / nTXEN, 1 - high / TXEN).
+
config UART4_RXDMA
bool "UART4 Rx DMA"
default n
@@ -1566,6 +1907,24 @@ config UART4_RXDMA
---help---
In high data rate usage, Rx DMA may eliminate Rx overrun errors
+config UART5_RS485
+ bool "RS-485 on UART5"
+ default n
+ depends on STM32_UART5
+ ---help---
+ Enable RS-485 interface on UART5. Your board config will have to
+ provide GPIO_UART5_RS485_DIR pin definition. Currently it cannot be
+ used with UART5_RXDMA.
+
+config UART5_RS485_DIR_POLARITY
+ int "UART5 RS-485 DIR pin polarity"
+ default 1
+ range 0 1
+ depends on UART5_RS485
+ ---help---
+ Polarity of DIR pin for RS-485 on UART5. Set to state on DIR pin which
+ enables TX (0 - low / nTXEN, 1 - high / TXEN).
+
config UART5_RXDMA
bool "UART5 Rx DMA"
default n
@@ -1573,6 +1932,24 @@ config UART5_RXDMA
---help---
In high data rate usage, Rx DMA may eliminate Rx overrun errors
+config USART6_RS485
+ bool "RS-485 on USART6"
+ default n
+ depends on STM32_USART6
+ ---help---
+ Enable RS-485 interface on USART6. Your board config will have to
+ provide GPIO_USART6_RS485_DIR pin definition. Currently it cannot be
+ used with USART6_RXDMA.
+
+config USART6_RS485_DIR_POLARITY
+ int "USART6 RS-485 DIR pin polarity"
+ default 1
+ range 0 1
+ depends on USART6_RS485
+ ---help---
+ Polarity of DIR pin for RS-485 on USART6. Set to state on DIR pin which
+ enables TX (0 - low / nTXEN, 1 - high / TXEN).
+
config USART6_RXDMA
bool "USART6 Rx DMA"
default n
@@ -1589,6 +1966,8 @@ config SERIAL_TERMIOS
If this is not defined, then the terminal settings (baud, parity, etc).
are not configurable at runtime; serial streams cannot be flushed, etc..
+endmenu
+
menu "SPI Configuration"
depends on STM32_SPI
@@ -1688,6 +2067,16 @@ config STM32_PHYADDR
---help---
The 5-bit address of the PHY on the board. Default: 1
+config STM32_PHYINIT
+ bool "Board-specific PHY Initialization"
+ default n
+ ---help---
+ Some boards require specialized initialization of the PHY before it can be used.
+ This may include such things as configuring GPIOs, resetting the PHY, etc. If
+ STM32_PHYINIT is defined in the configuration then the board specific logic must
+ provide stm32_phyinitialize(); The STM32 Ethernet driver will call this function
+ one time before it first uses the PHY.
+
config STM32_MII
bool "Use MII interface"
default n
@@ -1899,14 +2288,14 @@ config STM32_OTGFS_NPTXFIFO_SIZE
depends on USBHOST && STM32_OTGFS
---help---
Size of the non-periodic Tx FIFO in 32-bit words. Default 96 (384 bytes)
-
+
config STM32_OTGFS_PTXFIFO_SIZE
int "Periodic Tx FIFO size"
default 128
depends on USBHOST && STM32_OTGFS
---help---
Size of the periodic Tx FIFO in 32-bit words. Default 96 (384 bytes)
-
+
config STM32_OTGFS_DESCSIZE
int "Descriptor Size"
default 128
@@ -1920,14 +2309,14 @@ config STM32_OTGFS_SOFINTR
depends on USBHOST && STM32_OTGFS
---help---
Enable SOF interrupts. Why would you ever want to do that?
-
+
config STM32_USBHOST_REGDEBUG
bool "Register-Level Debug"
default n
depends on USBHOST && STM32_OTGFS
---help---
Enable very low-level register access debug. Depends on DEBUG.
-
+
config STM32_USBHOST_PKTDUMP
bool "Packet Dump Debug"
default n
diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs
index 54067a168..baa751c7d 100644
--- a/nuttx/arch/arm/src/stm32/Make.defs
+++ b/nuttx/arch/arm/src/stm32/Make.defs
@@ -41,36 +41,40 @@ endif
CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S
CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c \
- up_createstack.c up_mdelay.c up_udelay.c up_exit.c \
- up_initialize.c up_initialstate.c up_interruptcontext.c \
- up_memfault.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \
- up_releasepending.c up_releasestack.c up_reprioritizertr.c \
- up_schedulesigaction.c up_sigdeliver.c up_systemreset.c \
- up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c up_svcall.c \
- up_stackcheck.c
+ up_createstack.c up_mdelay.c up_udelay.c up_exit.c \
+ up_initialize.c up_initialstate.c up_interruptcontext.c \
+ up_memfault.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \
+ up_releasepending.c up_releasestack.c up_reprioritizertr.c \
+ up_schedulesigaction.c up_sigdeliver.c up_systemreset.c \
+ up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c up_svcall.c \
+ up_stackcheck.c
ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
CMN_ASRCS += up_exception.S
CMN_CSRCS += up_vectors.c
endif
+ifeq ($(CONFIG_ARCH_MEMCPY),y)
+CMN_ASRCS += up_memcpy.S
+endif
+
ifeq ($(CONFIG_DEBUG_STACK),y)
CMN_CSRCS += up_checkstack.c
endif
-ifeq ($(CONFIG_ARCH_FPU),y)
-CMN_ASRCS += up_fpu.S
+ifeq ($(CONFIG_ELF),y)
+CMN_CSRCS += up_elf.c
endif
-ifeq ($(CONFIG_ARCH_MEMCPY),y)
-CMN_ASRCS += memcpy.S
+ifeq ($(CONFIG_ARCH_FPU),y)
+CMN_ASRCS += up_fpu.S
endif
CHIP_ASRCS =
CHIP_CSRCS = stm32_allocateheap.c stm32_start.c stm32_rcc.c stm32_lse.c \
- stm32_lsi.c stm32_gpio.c stm32_exti_gpio.c stm32_flash.c stm32_irq.c \
- stm32_timerisr.c stm32_dma.c stm32_lowputc.c stm32_serial.c \
- stm32_spi.c stm32_sdio.c stm32_tim.c stm32_i2c.c stm32_waste.c
+ stm32_lsi.c stm32_gpio.c stm32_exti_gpio.c stm32_flash.c stm32_irq.c \
+ stm32_timerisr.c stm32_dma.c stm32_lowputc.c stm32_serial.c \
+ stm32_spi.c stm32_sdio.c stm32_tim.c stm32_i2c.c stm32_waste.c
ifeq ($(CONFIG_USBDEV),y)
ifeq ($(CONFIG_STM32_USB),y)
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_eth.h b/nuttx/arch/arm/src/stm32/chip/stm32_eth.h
index a4a109d01..92a229ccc 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_eth.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_eth.h
@@ -835,14 +835,6 @@ struct eth_rxdesc_s
* Public Functions
****************************************************************************************************/
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
#endif /* __ASSEMBLY__ */
#endif /* STM32_NETHERNET > 0 */
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32_ETH_H */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_flash.h b/nuttx/arch/arm/src/stm32/chip/stm32_flash.h
index c2e440923..d6fcecc11 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_flash.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_flash.h
@@ -110,6 +110,7 @@
# define FLASH_ACR_HLFCYA (1 << 3) /* FLASH half cycle access */
# define FLASH_ACR_PRTFBE (1 << 4) /* FLASH prefetch enable */
#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
+# define FLASH_ACR_PRFTEN (1 << 8) /* FLASH prefetch enable */
# define FLASH_ACR_ICEN (1 << 9) /* Bit 9: Instruction cache enable */
# define FLASH_ACR_DCEN (1 << 10) /* Bit 10: Data cache enable */
# define FLASH_ACR_ICRST (1 << 11) /* Bit 11: Instruction cache reset */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h
index 01d6e1ce0..addef0265 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f100_pinmap.h
@@ -6,6 +6,8 @@
* Copyright (C) 2012 Michael Smith. All Rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Uros Platise <uros.platise@isotel.eu>
+ * Michael Smith
+ * Freddie Chopin <freddie_chopin@op.pl>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -49,6 +51,87 @@
* Pre-processor Definitions
************************************************************************************/
+/* Alternate Pin Functions: */
+
+/* ADC */
+
+#define GPIO_ADC1_IN0 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_ADC1_IN1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_ADC1_IN2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_ADC1_IN3 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_ADC1_IN4 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
+#define GPIO_ADC1_IN5 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
+#define GPIO_ADC1_IN6 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6)
+#define GPIO_ADC1_IN7 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7)
+#define GPIO_ADC1_IN8 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_ADC1_IN9 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_ADC1_IN10 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0)
+#define GPIO_ADC1_IN11 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1)
+#define GPIO_ADC1_IN12 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2)
+#define GPIO_ADC1_IN13 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3)
+#define GPIO_ADC1_IN14 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4)
+#define GPIO_ADC1_IN15 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5)
+
+/* CEC */
+#if defined(CONFIG_STM32_CEC_REMAP)
+# define GPIO_CEC (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10)
+#else
+# define GPIO_CEC (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8)
+#endif
+
+/* DAC
+ * Note from RM0041, 11.2: "Once the DAC channelx is enabled, the corresponding
+ * GPIO pin (PA4 or PA5) is automatically connected to the analog converter
+ * output (DAC_OUTx). In order to avoid parasitic consumption, the PA4 or PA5
+ * pin should first be configured to analog (AIN)."
+ */
+
+#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
+#define GPIO_DAC_OUT2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
+
+/* FSMC */
+
+/* TODO - VL devices in 100- and 144-pin packages have FSMC */
+
+/* I2C */
+
+#if defined(CONFIG_STM32_I2C1_REMAP)
+# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8)
+# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9)
+#else
+# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6)
+# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN7)
+#endif
+#define GPIO_I2C1_SMBA (GPIO_ALT|GPIO_CNF_INFLOAT|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
+
+#define GPIO_I2C2_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_I2C2_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11)
+#define GPIO_I2C2_SMBA (GPIO_ALT|GPIO_CNF_INFLOAT|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12)
+
+/* SPI */
+
+#if defined(CONFIG_STM32_SPI1_REMAP)
+# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
+# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3)
+# define GPIO_SPI1_MISO (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN4)
+# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
+#else
+# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN4)
+# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN5)
+# define GPIO_SPI1_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN6)
+# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7)
+#endif
+
+#define GPIO_SPI2_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12)
+#define GPIO_SPI2_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13)
+#define GPIO_SPI2_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14)
+#define GPIO_SPI2_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15)
+
+#define GPIO_SPI3_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15)
+#define GPIO_SPI3_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3)
+#define GPIO_SPI3_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN4)
+#define GPIO_SPI3_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
+
/* TIMERS */
#if defined(CONFIG_STM32_TIM1_FULL_REMAP)
@@ -186,6 +269,77 @@
# define GPIO_TIM4_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9)
#endif
+#define GPIO_TIM5_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_TIM5_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_TIM5_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_TIM5_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_TIM5_CH3IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_TIM5_CH3OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_TIM5_CH4IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_TIM5_CH4OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3)
+
+#if defined(CONFIG_STM32_TIM12_REMAP)
+# define GPIO_TIM12_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN12)
+# define GPIO_TIM12_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12)
+# define GPIO_TIM12_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13)
+# define GPIO_TIM12_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13)
+#else
+# define GPIO_TIM12_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4)
+# define GPIO_TIM12_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN4)
+# define GPIO_TIM12_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5)
+# define GPIO_TIM12_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN5)
+#endif
+
+#if defined(CONFIG_STM32_TIM13_REMAP)
+# define GPIO_TIM13_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0)
+# define GPIO_TIM13_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0)
+#else
+# define GPIO_TIM13_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN8)
+# define GPIO_TIM13_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN8)
+#endif
+
+#if defined(CONFIG_STM32_TIM14_REMAP)
+# define GPIO_TIM14_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1)
+# define GPIO_TIM14_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN1)
+#else
+# define GPIO_TIM14_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN9)
+# define GPIO_TIM14_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN9)
+#endif
+
+#if defined(CONFIG_STM32_TIM15_REMAP)
+# define GPIO_TIM15_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN14)
+# define GPIO_TIM15_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14)
+# define GPIO_TIM15_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN15)
+# define GPIO_TIM15_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15)
+#else
+# define GPIO_TIM15_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2)
+# define GPIO_TIM15_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN2)
+# define GPIO_TIM15_CH2IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
+# define GPIO_TIM15_CH2OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN3)
+#endif
+#define GPIO_TIM15_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN9)
+#define GPIO_TIM15_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15)
+
+#if defined(CONFIG_STM32_TIM16_REMAP)
+# define GPIO_TIM16_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6)
+# define GPIO_TIM16_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN6)
+#else
+# define GPIO_TIM16_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN8)
+# define GPIO_TIM16_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8)
+#endif
+#define GPIO_TIM16_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN5)
+#define GPIO_TIM16_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6)
+
+#if defined(CONFIG_STM32_TIM17_REMAP)
+# define GPIO_TIM17_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7)
+# define GPIO_TIM17_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7)
+#else
+# define GPIO_TIM17_CH1IN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN9)
+# define GPIO_TIM17_CH1OUT (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9)
+#endif
+#define GPIO_TIM17_BKIN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN10)
+#define GPIO_TIM17_CH1N (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN7)
+
/* USART */
#if defined(CONFIG_STM32_USART1_REMAP)
@@ -230,38 +384,10 @@
# define GPIO_USART3_RTS (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14)
#endif
-/* SPI */
-
-#if defined(CONFIG_STM32_SPI1_REMAP)
-# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
-# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN3)
-# define GPIO_SPI1_MISO (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN4)
-# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
-#else
-# define GPIO_SPI1_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN4)
-# define GPIO_SPI1_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN5)
-# define GPIO_SPI1_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN6)
-# define GPIO_SPI1_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN7)
-#endif
-
-#define GPIO_SPI2_NSS (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12)
-#define GPIO_SPI2_SCK (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN13)
-#define GPIO_SPI2_MISO (GPIO_INPUT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN14)
-#define GPIO_SPI2_MOSI (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN15)
-
-/* I2C */
-
-#if defined(CONFIG_STM32_I2C1_REMAP)
-# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN8)
-# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN9)
-#else
-# define GPIO_I2C1_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN6)
-# define GPIO_I2C1_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN7)
-#endif
-#define GPIO_I2C1_SMBA (GPIO_ALT|GPIO_CNF_INFLOAT|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN5)
+#define GPIO_UART4_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN10)
+#define GPIO_UART4_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN11)
-#define GPIO_I2C2_SCL (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN10)
-#define GPIO_I2C2_SDA (GPIO_ALT|GPIO_CNF_AFOD|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN11)
-#define GPIO_I2C2_SMBA (GPIO_ALT|GPIO_CNF_INFLOAT|GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN12)
+#define GPIO_UART5_TX (GPIO_ALT|GPIO_CNF_AFPP|GPIO_MODE_50MHz|GPIO_PORTC|GPIO_PIN12)
+#define GPIO_UART5_RX (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN2)
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F100_PINMAP_H */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f103vc_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f103vc_pinmap.h
index 160676802..52a513215 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f103vc_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f103vc_pinmap.h
@@ -129,7 +129,7 @@
#if 0 /* Needs further investigation */
-#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUTz|GPIO_PORTA|GPIO_PIN4)
+#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
#define GPIO_DAC_OUT2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
#endif
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h
index 9bcee49f5..581b026a0 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f103ze_pinmap.h
@@ -50,53 +50,53 @@
/* ADC */
-#define GPIO_ADC1_IN0 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
-#define GPIO_ADC1_IN1 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1)
-#define GPIO_ADC1_IN2 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2)
-#define GPIO_ADC1_IN3 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
-#define GPIO_ADC1_IN4 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
-#define GPIO_ADC1_IN5 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
-#define GPIO_ADC1_IN6 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6)
-#define GPIO_ADC1_IN7 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7)
-#define GPIO_ADC1_IN8 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0)
-#define GPIO_ADC1_IN9 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1)
-#define GPIO_ADC1_IN10 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0)
-#define GPIO_ADC1_IN11 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1)
-#define GPIO_ADC1_IN12 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2)
-#define GPIO_ADC1_IN13 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3)
-#define GPIO_ADC1_IN14 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4)
-#define GPIO_ADC1_IN15 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5)
-
-#define GPIO_ADC2_IN0 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
-#define GPIO_ADC2_IN1 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1)
-#define GPIO_ADC2_IN2 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2)
-#define GPIO_ADC2_IN3 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
-#define GPIO_ADC2_IN4 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
-#define GPIO_ADC2_IN5 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
-#define GPIO_ADC2_IN6 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6)
-#define GPIO_ADC2_IN7 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7)
-#define GPIO_ADC2_IN8 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0)
-#define GPIO_ADC2_IN9 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1)
-#define GPIO_ADC2_IN10 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0)
-#define GPIO_ADC2_IN11 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1)
-#define GPIO_ADC2_IN12 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2)
-#define GPIO_ADC2_IN13 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3)
-#define GPIO_ADC2_IN14 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4)
-#define GPIO_ADC2_IN15 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5)
-
-#define GPIO_ADC3_IN0 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
-#define GPIO_ADC3_IN1 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1)
-#define GPIO_ADC3_IN2 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2)
-#define GPIO_ADC3_IN3 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
-#define GPIO_ADC3_IN4 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN6)
-#define GPIO_ADC3_IN5 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN7)
-#define GPIO_ADC3_IN6 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN8)
-#define GPIO_ADC3_IN7 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN9)
-#define GPIO_ADC3_IN8 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN10)
-#define GPIO_ADC3_IN10 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0)
-#define GPIO_ADC3_IN11 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1)
-#define GPIO_ADC3_IN12 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2)
-#define GPIO_ADC3_IN13 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3)
+#define GPIO_ADC1_IN0 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_ADC1_IN1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_ADC1_IN2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_ADC1_IN3 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_ADC1_IN4 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
+#define GPIO_ADC1_IN5 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
+#define GPIO_ADC1_IN6 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6)
+#define GPIO_ADC1_IN7 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7)
+#define GPIO_ADC1_IN8 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_ADC1_IN9 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_ADC1_IN10 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0)
+#define GPIO_ADC1_IN11 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1)
+#define GPIO_ADC1_IN12 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2)
+#define GPIO_ADC1_IN13 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3)
+#define GPIO_ADC1_IN14 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4)
+#define GPIO_ADC1_IN15 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5)
+
+#define GPIO_ADC2_IN0 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_ADC2_IN1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_ADC2_IN2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_ADC2_IN3 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_ADC2_IN4 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
+#define GPIO_ADC2_IN5 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
+#define GPIO_ADC2_IN6 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN6)
+#define GPIO_ADC2_IN7 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN7)
+#define GPIO_ADC2_IN8 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_ADC2_IN9 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_ADC2_IN10 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0)
+#define GPIO_ADC2_IN11 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1)
+#define GPIO_ADC2_IN12 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2)
+#define GPIO_ADC2_IN13 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3)
+#define GPIO_ADC2_IN14 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4)
+#define GPIO_ADC2_IN15 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5)
+
+#define GPIO_ADC3_IN0 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_ADC3_IN1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_ADC3_IN2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_ADC3_IN3 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_ADC3_IN4 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN6)
+#define GPIO_ADC3_IN5 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN7)
+#define GPIO_ADC3_IN6 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN8)
+#define GPIO_ADC3_IN7 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN9)
+#define GPIO_ADC3_IN8 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN10)
+#define GPIO_ADC3_IN10 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0)
+#define GPIO_ADC3_IN11 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN1)
+#define GPIO_ADC3_IN12 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN2)
+#define GPIO_ADC3_IN13 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN3)
/* DAC - "Once the DAC channelx is enabled, the corresponding GPIO pin
* (PA4 or PA5) is automatically connected to the analog converter output
@@ -104,8 +104,8 @@
* should first be configured to analog (AIN)."
*/
-#define GPIO_DAC_OUT1 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTF|GPIO_PIN10)
-#define GPIO_DAC_OUT2 (GPIO_ALT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PIN10)
+#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
+#define GPIO_DAC_OUT2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
/* TIMERS */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f105vb_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f105vb_pinmap.h
index 7a5ec3381..054a7337d 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f105vb_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f105vb_pinmap.h
@@ -85,7 +85,7 @@
#endif
#if 0 /* Needs further investigation */
-#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUTz|GPIO_PORTA|GPIO_PIN4)
+#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
#define GPIO_DAC_OUT2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
#endif
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f107vc_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f107vc_pinmap.h
index 9bbc21479..2419620fc 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f107vc_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f107vc_pinmap.h
@@ -85,7 +85,7 @@
#endif
#if 0 /* Needs further investigation */
-#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUTz|GPIO_PORTA|GPIO_PIN4)
+#define GPIO_DAC_OUT1 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
#define GPIO_DAC_OUT2 (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
#endif
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h
index a95d13100..d339fc15e 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_gpio.h
@@ -59,6 +59,7 @@
#define STM32_AFIO_EXTICR2_OFFSET 0x000c /* External interrupt configuration register 2 */
#define STM32_AFIO_EXTICR3_OFFSET 0x0010 /* External interrupt configuration register 3 */
#define STM32_AFIO_EXTICR4_OFFSET 0x0014 /* External interrupt configuration register 4 */
+#define STM32_AFIO_MAPR2_OFFSET 0x001c /* AF remap and debug I/O configuration register 2 */
/* Register Addresses ***************************************************************/
@@ -373,5 +374,27 @@
#define AFIO_EXTICR4_EXTI15_SHIFT (12) /* Bits 15-12: EXTI 15 configuration */
#define AFIO_EXTICR4_EXTI15_MASK (AFIO_EXTICR_PORT_MASK << AFIO_EXTICR4_EXTI15_SHIFT)
+/* AF remap and debug I/O configuration register 2 */
+
+#ifdef CONFIG_STM32_VALUELINE
+# define AFIO_MAPR2_TIM15_REMAP (1 << 0) /* Bit 0: TIM15 remapping */
+# define AFIO_MAPR2_TIM16_REMAP (1 << 1) /* Bit 1: TIM16 remapping */
+# define AFIO_MAPR2_TIM17_REMAP (1 << 2) /* Bit 2: TIM17 remapping */
+# define AFIO_MAPR2_CEC_REMAP (1 << 3) /* Bit 3: CEC remapping */
+# define AFIO_MAPR2_TIM1_DMA_REMAP (1 << 4) /* Bit 4: TIM1 DMA remapping */
+#else
+# define AFIO_MAPR2_TIM9_REMAP (1 << 5) /* Bit 5: TIM9 remapping */
+# define AFIO_MAPR2_TIM10_REMAP (1 << 6) /* Bit 6: TIM10 remapping */
+# define AFIO_MAPR2_TIM11_REMAP (1 << 7) /* Bit 7: TIM11 remapping */
+#endif
+#define AFIO_MAPR2_TIM13_REMAP (1 << 8) /* Bit 8: TIM13 remapping */
+#define AFIO_MAPR2_TIM14_REMAP (1 << 9) /* Bit 9: TIM14 remapping */
+#define AFIO_MAPR2_FSMC_NADV (1 << 10) /* Bit 10: NADV connect/disconnect */
+#ifdef CONFIG_STM32_VALUELINE
+# define AFIO_MAPR2_TIM67_DAC_DMA_REMAP (1 << 11) /* Bit 11: TIM67_DAC DMA remapping */
+# define AFIO_MAPR2_TIM12_REMAP (1 << 12) /* Bit 12: TIM12 remapping */
+# define AFIO_MAPR2_MISC_REMAP (1 << 13) /* Bit 13: Miscellaneous features remapping */
+#endif
+
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F10XXX_GPIO_H */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h
index ed1bc2625..a1d2e26d3 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_memorymap.h
@@ -60,7 +60,9 @@
#define STM32_TIM5_BASE 0x40000c00 /* 0x40000c00 - 0x40000fff: TIM5 timer */
#define STM32_TIM6_BASE 0x40001000 /* 0x40001000 - 0x400013ff: TIM6 timer */
#define STM32_TIM7_BASE 0x40001400 /* 0x40001400 - 0x400007ff: TIM7 timer */
- /* 0x40001800 - 0x40000fff: Reserved */
+#define STM32_TIM12_BASE 0x40001800 /* 0x40001800 - 0x40001bff: TIM12 timer */
+#define STM32_TIM13_BASE 0x40001c00 /* 0x40001c00 - 0x40001fff: TIM13 timer */
+#define STM32_TIM14_BASE 0x40002000 /* 0x40002000 - 0x400023ff: TIM14 timer */
#define STM32_RTC_BASE 0x40002800 /* 0x40002800 - 0x40002bff: RTC */
#define STM32_WWDG_BASE 0x40002c00 /* 0x40002C00 - 0x40002fff: Window watchdog (WWDG) */
#define STM32_IWDG_BASE 0x40003000 /* 0x40003000 - 0x400033ff: Independent watchdog (IWDG) */
@@ -83,8 +85,8 @@
#define STM32_BKP_BASE 0x40006c00 /* 0x40006c00 - 0x40006fff: Backup registers (BKP) */
#define STM32_PWR_BASE 0x40007000 /* 0x40007000 - 0x400073ff: Power control PWR */
#define STM32_DAC_BASE 0x40007400 /* 0x40007400 - 0x400077ff: DAC */
- /* 0x40007800 - 0x4000ffff: Reserved */
-
+#define STM32_CEC_BASE 0x40007800 /* 0x40007800 - 0x40007bff: CEC */
+ /* 0x40007c00 - 0x4000ffff: Reserved */
/* APB2 bus */
#define STM32_AFIO_BASE 0x40010000 /* 0x40010000 - 0x400103ff: AFIO */
@@ -102,44 +104,49 @@
#define STM32_SPI1_BASE 0x40013000 /* 0x40013000 - 0x400133ff: SPI1 */
#define STM32_TIM8_BASE 0x40013400 /* 0x40013400 - 0x400137ff: TIM8 timer */
#define STM32_USART1_BASE 0x40013800 /* 0x40013800 - 0x40013bff: USART1 */
-#define STM32_ADC3_BASE 0x40012800 /* 0x40012800 - 0x40013fff: ADC3 */
- /* 0x40014000 - 0x40017fff: Reserved */
+#define STM32_ADC3_BASE 0x40012800 /* 0x40012800 - 0x40013c00: ADC3 */
+ /* 0x40013c00 - 0x40013fff: Reserved */
+#define STM32_TIM15_BASE 0x40014400 /* 0x40014400 - 0x400147ff: TIM15 */
+#define STM32_TIM16_BASE 0x40014400 /* 0x40014400 - 0x400147ff: TIM16 */
+#define STM32_TIM17_BASE 0x40014800 /* 0x40014800 - 0x40014bff: TIM17 */
+ /* 0x40014c00 - 0x4001ffff: Reserved */
+
/* AHB bus */
-#define STM32_SDIO_BASE 0x40018000 /* 0x40018000 - 0x400183ff: SDIO */
- /* 0x40018400 - 0x40017fff: Reserved */
-#define STM32_DMA1_BASE 0x40020000 /* 0x40020000 - 0x400203ff: DMA1 */
-#define STM32_DMA2_BASE 0x40020400 /* 0x40020000 - 0x400207ff: DMA2 */
- /* 0x40020800 - 0x40020fff: Reserved */
-#define STM32_RCC_BASE 0x40021000 /* 0x40021000 - 0x400213ff: Reset and Clock control RCC */
- /* 0x40021400 - 0x40021fff: Reserved */
-#define STM32_OTGFS_BASE 0x50000000 /* 0x50000000 - 0x500003ff: USB OTG FS */
-#define STM32_FLASHIF_BASE 0x40022000 /* 0x40022000 - 0x400223ff: Flash memory interface */
-#define STM32_CRC_BASE 0x40028000 /* 0x40023000 - 0x400233ff: CRC */
- /* 0x40023400 - 0x40027fff: Reserved */
-#define STM32_ETHERNET_BASE 0x40028000 /* 0x40028000 - 0x40029fff: Ethernet */
- /* 0x40030000 - 0x4fffffff: Reserved */
+#define STM32_SDIO_BASE 0x40018000 /* 0x40018000 - 0x400183ff: SDIO */
+ /* 0x40018400 - 0x40017fff: Reserved */
+#define STM32_DMA1_BASE 0x40020000 /* 0x40020000 - 0x400203ff: DMA1 */
+#define STM32_DMA2_BASE 0x40020400 /* 0x40020000 - 0x400207ff: DMA2 */
+ /* 0x40020800 - 0x40020fff: Reserved */
+#define STM32_RCC_BASE 0x40021000 /* 0x40021000 - 0x400213ff: Reset and Clock control RCC */
+ /* 0x40021400 - 0x40021fff: Reserved */
+#define STM32_OTGFS_BASE 0x50000000 /* 0x50000000 - 0x500003ff: USB OTG FS */
+#define STM32_FLASHIF_BASE 0x40022000 /* 0x40022000 - 0x400223ff: Flash memory interface */
+#define STM32_CRC_BASE 0x40028000 /* 0x40023000 - 0x400233ff: CRC */
+ /* 0x40023400 - 0x40027fff: Reserved */
+#define STM32_ETHERNET_BASE 0x40028000 /* 0x40028000 - 0x40029fff: Ethernet */
+ /* 0x40030000 - 0x4fffffff: Reserved */
/* Peripheral BB base */
-#define STM32_PERIPHBB_BASE 0x42000000
+#define STM32_PERIPHBB_BASE 0x42000000
/* Flexible SRAM controller (FSMC) */
-#define STM32_FSMC_BANK1 0x60000000 /* 0x60000000-0x6fffffff: 256Mb NOR/SRAM */
-#define STM32_FSMC_BANK2 0x70000000 /* 0x70000000-0x7fffffff: 256Mb NAND FLASH */
-#define STM32_FSMC_BANK3 0x80000000 /* 0x80000000-0x8fffffff: 256Mb NAND FLASH */
-#define STM32_FSMC_BANK4 0x90000000 /* 0x90000000-0x9fffffff: 256Mb PC CARD*/
-#define STM32_IS_EXTSRAM(a) ((((uint32_t)(a)) & STM32_REGION_MASK) == STM32_FSMC_BANK1)
+#define STM32_FSMC_BANK1 0x60000000 /* 0x60000000-0x6fffffff: 256Mb NOR/SRAM */
+#define STM32_FSMC_BANK2 0x70000000 /* 0x70000000-0x7fffffff: 256Mb NAND FLASH */
+#define STM32_FSMC_BANK3 0x80000000 /* 0x80000000-0x8fffffff: 256Mb NAND FLASH */
+#define STM32_FSMC_BANK4 0x90000000 /* 0x90000000-0x9fffffff: 256Mb PC CARD*/
+#define STM32_IS_EXTSRAM(a) ((((uint32_t)(a)) & STM32_REGION_MASK) == STM32_FSMC_BANK1)
-#define STM32_FSMC_BASE 0xa0000000 /* 0xa0000000-0xbfffffff: 512Mb FSMC register block */
+#define STM32_FSMC_BASE 0xa0000000 /* 0xa0000000-0xbfffffff: 512Mb FSMC register block */
/* Other registers -- see armv7-m/nvic.h for standard Cortex-M3 registers in this
* address range
*/
-#define STM32_SCS_BASE 0xe000e000
-#define STM32_DEBUGMCU_BASE 0xe0042000
+#define STM32_SCS_BASE 0xe000e000
+#define STM32_DEBUGMCU_BASE 0xe0042000
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F10XXX_MEMORYMAP_H */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h
index 60365b921..1a792b7eb 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_rcc.h
@@ -163,7 +163,9 @@
# define RCC_CFGR_PLLMUL_CLKx14 (12 << RCC_CFGR_PLLMUL_SHIFT) /* 1100: PLL input clock x 14 */
# define RCC_CFGR_PLLMUL_CLKx15 (13 << RCC_CFGR_PLLMUL_SHIFT) /* 1101: PLL input clock x 15 */
# define RCC_CFGR_PLLMUL_CLKx16 (14 << RCC_CFGR_PLLMUL_SHIFT) /* 111x: PLL input clock x 16 */
-#define RCC_CFGR_USBPRE (1 << 22) /* Bit 22: USB prescaler */
+#ifndef CONFIG_STM32_VALUELINE
+# define RCC_CFGR_USBPRE (1 << 22) /* Bit 22: USB prescaler */
+#endif
#define RCC_CFGR_MCO_SHIFT (24) /* Bits 26-24: Microcontroller Clock Output */
#define RCC_CFGR_MCO_MASK (0x0f << RCC_CFGR_MCO_SHIFT)
# define RCC_CFGR_NOCLK (0 << RCC_CFGR_MCO_SHIFT) /* 0xx: No clock */
@@ -207,12 +209,22 @@
#define TCC_APB2RSTR_IOPFRST (1 << 7) /* Bit 7: IO port F reset */
#define TCC_APB2RSTR_IOPGRST (1 << 8) /* Bit 8: IO port G reset */
#define RCC_APB2RSTR_ADC1RST (1 << 9) /* Bit 9: ADC 1 interface reset */
-#define RCC_APB2RSTR_ADC2RST (1 << 10) /* Bit 10: ADC 2 interface reset */
+#ifndef CONFIG_STM32_VALUELINE
+# define RCC_APB2RSTR_ADC2RST (1 << 10) /* Bit 10: ADC 2 interface reset */
+#endif
#define RCC_APB2RSTR_TIM1RST (1 << 11) /* Bit 11: TIM1 Timer reset */
#define RCC_APB2RSTR_SPI1RST (1 << 12) /* Bit 12: SPI 1 reset */
-#define RCC_APB2RSTR_TIM8RST (1 << 13) /* Bit 13: TIM8 Timer reset */
+#ifndef CONFIG_STM32_VALUELINE
+# define RCC_APB2RSTR_TIM8RST (1 << 13) /* Bit 13: TIM8 Timer reset */
+#endif
#define RCC_APB2RSTR_USART1RST (1 << 14) /* Bit 14: USART1 reset */
-#define RCC_APB2RSTR_ADC3RST (1 << 15) /* Bit 15: ADC3 interface reset */
+#ifndef CONFIG_STM32_VALUELINE
+# define RCC_APB2RSTR_ADC3RST (1 << 15) /* Bit 15: ADC3 interface reset */
+#else
+# define RCC_APB2RSTR_TIM15RST (1 << 16) /* Bit 16: TIM15 reset */
+# define RCC_APB2RSTR_TIM16RST (1 << 17) /* Bit 17: TIM16 reset */
+# define RCC_APB2RSTR_TIM17RST (1 << 18) /* Bit 18: TIM17 reset */
+#endif
/* APB1 Peripheral reset register */
@@ -222,6 +234,11 @@
#define RCC_APB1RSTR_TIM5RST (1 << 3) /* Bit 3: Timer 5 reset */
#define RCC_APB1RSTR_TIM6RST (1 << 4) /* Bit 4: Timer 6 reset */
#define RCC_APB1RSTR_TIM7RST (1 << 5) /* Bit 5: Timer 7 reset */
+#ifdef CONFIG_STM32_VALUELINE
+# define RCC_APB1RSTR_TIM12RST (1 << 6) /* Bit 6: TIM12 reset */
+# define RCC_APB1RSTR_TIM13RST (1 << 7) /* Bit 7: TIM13 reset */
+# define RCC_APB1RSTR_TIM14RST (1 << 8) /* Bit 8: TIM14 reset */
+#endif
#define RCC_APB1RSTR_WWDGRST (1 << 11) /* Bit 11: Window Watchdog reset */
#define RCC_APB1RSTR_SPI2RST (1 << 14) /* Bit 14: SPI 2 reset */
#define RCC_APB1RSTR_SPI3RST (1 << 15) /* Bit 15: SPI 3 reset */
@@ -231,12 +248,17 @@
#define RCC_APB1RSTR_UART5RST (1 << 20) /* Bit 18: UART 5 reset */
#define RCC_APB1RSTR_I2C1RST (1 << 21) /* Bit 21: I2C 1 reset */
#define RCC_APB1RSTR_I2C2RST (1 << 22) /* Bit 22: I2C 2 reset */
-#define RCC_APB1RSTR_USBRST (1 << 23) /* Bit 23: USB reset */
-#define RCC_APB1RSTR_CAN1RST (1 << 25) /* Bit 25: CAN1 reset */
-#define RCC_APB1RSTR_CAN2RST (1 << 26) /* Bit 26: CAN2 reset */
+#ifndef CONFIG_STM32_VALUELINE
+# define RCC_APB1RSTR_USBRST (1 << 23) /* Bit 23: USB reset */
+# define RCC_APB1RSTR_CAN1RST (1 << 25) /* Bit 25: CAN1 reset */
+# define RCC_APB1RSTR_CAN2RST (1 << 26) /* Bit 26: CAN2 reset */
+#endif
#define RCC_APB1RSTR_BKPRST (1 << 27) /* Bit 27: Backup interface reset */
#define RCC_APB1RSTR_PWRRST (1 << 28) /* Bit 28: Power interface reset */
#define RCC_APB1RSTR_DACRST (1 << 29) /* Bit 29: DAC interface reset */
+#ifdef CONFIG_STM32_VALUELINE
+# define RCC_APB1RSTR_CECRST (1 << 30) /* Bit 30: CEC reset */
+#endif
/* AHB Peripheral Clock enable register */
@@ -246,7 +268,9 @@
#define RCC_AHBENR_FLITFEN (1 << 4) /* Bit 4: FLITF clock enable */
#define RCC_AHBENR_CRCEN (1 << 6) /* Bit 6: CRC clock enable */
#define RCC_AHBENR_FSMCEN (1 << 8) /* Bit 8: FSMC clock enable */
-#define RCC_AHBENR_SDIOEN (1 << 10) /* Bit 10: SDIO clock enable */
+#ifndef CONFIG_STM32_VALUELINE
+# define RCC_AHBENR_SDIOEN (1 << 10) /* Bit 10: SDIO clock enable */
+#endif
#ifdef CONFIG_STM32_CONNECTIVITYLINE
# define RCC_AHBENR_ETHMACEN (1 << 14) /* Bit 14: Ethernet MAC clock enable */
# define RCC_AHBENR_ETHMACTXEN (1 << 15) /* Bit 15: Ethernet MAC TX clock enable */
@@ -272,12 +296,22 @@
#define RCC_APB2ENR_IOPFEN (1 << 7) /* Bit 7: I/O port F clock enable */
#define RCC_APB2ENR_IOPGEN (1 << 8) /* Bit 8: I/O port G clock enable */
#define RCC_APB2ENR_ADC1EN (1 << 9) /* Bit 9: ADC 1 interface clock enable */
-#define RCC_APB2ENR_ADC2EN (1 << 10) /* Bit 10: ADC 2 interface clock enable */
+#ifndef CONFIG_STM32_VALUELINE
+# define RCC_APB2ENR_ADC2EN (1 << 10) /* Bit 10: ADC 2 interface clock enable */
+#endif
#define RCC_APB2ENR_TIM1EN (1 << 11) /* Bit 11: TIM1 Timer clock enable */
#define RCC_APB2ENR_SPI1EN (1 << 12) /* Bit 12: SPI 1 clock enable */
-#define RCC_APB2ENR_TIM8EN (1 << 13) /* Bit 13: TIM8 Timer clock enable */
+#ifndef CONFIG_STM32_VALUELINE
+# define RCC_APB2ENR_TIM8EN (1 << 13) /* Bit 13: TIM8 Timer clock enable */
+#endif
#define RCC_APB2ENR_USART1EN (1 << 14) /* Bit 14: USART1 clock enable */
-#define RCC_APB2ENR_ADC3EN (1 << 15) /* Bit 14: ADC3 interface clock enable */
+#ifndef CONFIG_STM32_VALUELINE
+# define RCC_APB2ENR_ADC3EN (1 << 15) /* Bit 14: ADC3 interface clock enable */
+#else
+# define RCC_APB2ENR_TIM15EN (1 << 16) /* Bit 16: TIM15 clock enable */
+# define RCC_APB2ENR_TIM16EN (1 << 17) /* Bit 17: TIM16 clock enable */
+# define RCC_APB2ENR_TIM17EN (1 << 18) /* Bit 18: TIM17 clock enable */
+#endif
/* APB1 Peripheral Clock enable register */
@@ -287,6 +321,11 @@
#define RCC_APB1ENR_TIM5EN (1 << 3) /* Bit 3: Timer 5 clock enable */
#define RCC_APB1ENR_TIM6EN (1 << 4) /* Bit 4: Timer 6 clock enable */
#define RCC_APB1ENR_TIM7EN (1 << 5) /* Bit 5: Timer 7 clock enable */
+#ifdef CONFIG_STM32_VALUELINE
+# define RCC_APB1ENR_TIM12EN (1 << 6) /* Bit 6: Timer 12 clock enable */
+# define RCC_APB1ENR_TIM13EN (1 << 7) /* Bit 7: Timer 13 clock enable */
+# define RCC_APB1ENR_TIM14EN (1 << 8) /* Bit 8: Timer 14 clock enable */
+#endif
#define RCC_APB1ENR_WWDGEN (1 << 11) /* Bit 11: Window Watchdog clock enable */
#define RCC_APB1ENR_SPI2EN (1 << 14) /* Bit 14: SPI 2 clock enable */
#define RCC_APB1ENR_SPI3EN (1 << 15) /* Bit 15: SPI 3 clock enable */
@@ -296,12 +335,17 @@
#define RCC_APB1ENR_UART5EN (1 << 20) /* Bit 20: UART 5 clock enable */
#define RCC_APB1ENR_I2C1EN (1 << 21) /* Bit 21: I2C 1 clock enable */
#define RCC_APB1ENR_I2C2EN (1 << 22) /* Bit 22: I2C 2 clock enable */
-#define RCC_APB1ENR_USBEN (1 << 23) /* Bit 23: USB clock enable */
-#define RCC_APB1ENR_CAN1EN (1 << 25) /* Bit 25: CAN1 clock enable */
-#define RCC_APB1ENR_CAN2EN (1 << 26) /* Bit 25: CAN2 clock enable */
+#ifndef CONFIG_STM32_VALUELINE
+# define RCC_APB1ENR_USBEN (1 << 23) /* Bit 23: USB clock enable */
+# define RCC_APB1ENR_CAN1EN (1 << 25) /* Bit 25: CAN1 clock enable */
+# define RCC_APB1ENR_CAN2EN (1 << 26) /* Bit 25: CAN2 clock enable */
+#endif
#define RCC_APB1ENR_BKPEN (1 << 27) /* Bit 27: Backup interface clock enable */
#define RCC_APB1ENR_PWREN (1 << 28) /* Bit 28: Power interface clock enable */
#define RCC_APB1ENR_DACEN (1 << 29) /* Bit 29: DAC interface clock enable */
+#ifdef CONFIG_STM32_VALUELINE
+# define RCC_APB1ENR_CECEN (1 << 30) /* Bit 30: CEC clock enable */
+#endif
/* Backup domain control register */
@@ -331,7 +375,7 @@
#if defined(CONFIG_STM32_VALUELINE) || defined(CONFIG_STM32_CONNECTIVITYLINE)
-/* Clock configuration register 2 (For connectivity line only) */
+/* Clock configuration register 2 (For value line and connectivity line only) */
#define RCC_CFGR2_PREDIV1_SHIFT (0)
#define RCC_CFGR2_PREDIV1_MASK (0x0f << RCC_CFGR2_PREDIV1_SHIFT)
@@ -352,6 +396,10 @@
# define RCC_CFGR2_PREDIV1d15 (14 << RCC_CFGR2_PREDIV1_SHIFT)
# define RCC_CFGR2_PREDIV1d16 (15 << RCC_CFGR2_PREDIV1_SHIFT)
+#endif
+
+#ifdef CONFIG_STM32_CONNECTIVITYLINE
+
#define RCC_CFGR2_PREDIV2_SHIFT (4)
#define RCC_CFGR2_PREDIV2_MASK (0x0f << RCC_CFGR2_PREDIV2_SHIFT)
# define RCC_CFGR2_PREDIV2d1 (0 << RCC_CFGR2_PREDIV2_SHIFT)
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h
index b8d71799f..24822c37d 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f10xxx_vectors.h
@@ -49,15 +49,77 @@
* definition that provides the number of supported vectors.
*/
-#ifdef CONFIG_ARMV7M_CMNVECTOR
+# ifdef CONFIG_ARMV7M_CMNVECTOR
-/* Reserve 60 interrupt table entries for I/O interrupts. */
+/* Reserve 61 interrupt table entries for I/O interrupts. */
-# define ARMV7M_PERIPHERAL_INTERRUPTS 60
+# define ARMV7M_PERIPHERAL_INTERRUPTS 61
#else
-# error This target requires CONFIG_ARMV7M_CMNVECTOR
-#endif /* CONFIG_ARMV7M_CMNVECTOR */
+
+VECTOR(stm32_wwdg, STM32_IRQ_WWDG) /* Vector 16+0: Window Watchdog interrupt */
+VECTOR(stm32_pvd, STM32_IRQ_PVD) /* Vector 16+1: PVD through EXTI Line detection interrupt */
+VECTOR(stm32_tamper, STM32_IRQ_TAMPER) /* Vector 16+2: Tamper interrupt */
+VECTOR(stm32_rtc, STM32_IRQ_RTC) /* Vector 16+3: RTC Wakeup through EXTI line interrupt */
+VECTOR(stm32_flash, STM32_IRQ_FLASH) /* Vector 16+4: Flash global interrupt */
+VECTOR(stm32_rcc, STM32_IRQ_RCC) /* Vector 16+5: RCC global interrupt */
+VECTOR(stm32_exti0, STM32_IRQ_EXTI0) /* Vector 16+6: EXTI Line 0 interrupt */
+VECTOR(stm32_exti1, STM32_IRQ_EXTI1) /* Vector 16+7: EXTI Line 1 interrupt */
+VECTOR(stm32_exti2, STM32_IRQ_EXTI2) /* Vector 16+8: EXTI Line 2 interrupt */
+VECTOR(stm32_exti3, STM32_IRQ_EXTI3) /* Vector 16+9: EXTI Line 3 interrupt */
+VECTOR(stm32_exti4, STM32_IRQ_EXTI4) /* Vector 16+10: EXTI Line 4 interrupt */
+VECTOR(stm32_dma1ch1, STM32_IRQ_DMA1CH1) /* Vector 16+11: DMA1 Channel 1 global interrupt */
+VECTOR(stm32_dma1ch2, STM32_IRQ_DMA1CH2) /* Vector 16+12: DMA1 Channel 2 global interrupt */
+VECTOR(stm32_dma1ch3, STM32_IRQ_DMA1CH3) /* Vector 16+13: DMA1 Channel 3 global interrupt */
+VECTOR(stm32_dma1ch4, STM32_IRQ_DMA1CH4) /* Vector 16+14: DMA1 Channel 4 global interrupt */
+VECTOR(stm32_dma1ch5, STM32_IRQ_DMA1CH5) /* Vector 16+15: DMA1 Channel 5 global interrupt */
+VECTOR(stm32_dma1ch6, STM32_IRQ_DMA1CH6) /* Vector 16+16: DMA1 Channel 6 global interrupt */
+VECTOR(stm32_dma1ch7, STM32_IRQ_DMA1CH7) /* Vector 16+17: DMA1 Channel 7 global interrupt */
+VECTOR(stm32_adc1, STM32_IRQ_ADC1) /* Vector 16+18: ADC1 global interrupt */
+UNUSED(STM32_IRQ_RESERVED0) /* Vector 16+19: Reserved 0 */
+UNUSED(STM32_IRQ_RESERVED1) /* Vector 16+20: Reserved 1 */
+UNUSED(STM32_IRQ_RESERVED2) /* Vector 16+21: Reserved 2 */
+UNUSED(STM32_IRQ_RESERVED3) /* Vector 16+22: Reserved 3 */
+VECTOR(stm32_exti95, STM32_IRQ_EXTI95) /* Vector 16+23: EXTI Line[9:5] interrupts */
+VECTOR(stm32_tim1brk, STM32_IRQ_TIM1BRK) /* Vector 16+24: TIM1 Break interrupt; TIM15 global interrupt */
+VECTOR(stm32_tim1up, STM32_IRQ_TIM1UP) /* Vector 16+25: TIM1 Update interrupt; TIM16 global interrupt */
+VECTOR(stm32_tim1trgcom, STM32_IRQ_TIM1TRGCOM) /* Vector 16+26: TIM1 Trigger and Commutation interrupts; TIM17 global interrupt */
+VECTOR(stm32_tim1cc, STM32_IRQ_TIM1CC) /* Vector 16+27: TIM1 Capture Compare interrupt */
+VECTOR(stm32_tim2, STM32_IRQ_TIM2) /* Vector 16+28: TIM2 global interrupt */
+VECTOR(stm32_tim3, STM32_IRQ_TIM3) /* Vector 16+29: TIM3 global interrupt */
+VECTOR(stm32_tim4, STM32_IRQ_TIM4) /* Vector 16+30: TIM4 global interrupt */
+VECTOR(stm32_i2c1ev, STM32_IRQ_I2C1EV) /* Vector 16+31: I2C1 event interrupt */
+VECTOR(stm32_i2c1er, STM32_IRQ_I2C1ER) /* Vector 16+32: I2C1 error interrupt */
+VECTOR(stm32_i2c2ev, STM32_IRQ_I2C2EV) /* Vector 16+33: I2C2 event interrupt */
+VECTOR(stm32_i2c2er, STM32_IRQ_I2C2ER) /* Vector 16+34: I2C2 error interrupt */
+VECTOR(stm32_spi1, STM32_IRQ_SPI1) /* Vector 16+35: SPI1 global interrupt */
+VECTOR(stm32_spi2, STM32_IRQ_SPI2) /* Vector 16+36: SPI2 global interrupt */
+VECTOR(stm32_usart1, STM32_IRQ_USART1) /* Vector 16+37: USART1 global interrupt */
+VECTOR(stm32_usart2, STM32_IRQ_USART2) /* Vector 16+38: USART2 global interrupt */
+VECTOR(stm32_usart3, STM32_IRQ_USART3) /* Vector 16+39: USART3 global interrupt */
+VECTOR(stm32_exti1510, STM32_IRQ_EXTI1510) /* Vector 16+40: EXTI Line[15:10] interrupts */
+VECTOR(stm32_rtcalr, STM32_IRQ_RTCALR) /* Vector 16+41: RTC alarms (A and B) through EXTI line interrupt */
+VECTOR(stm32_cec, STM32_IRQ_CEC) /* Vector 16+42: CEC global interrupt */
+VECTOR(stm32_tim12, STM32_IRQ_TIM12) /* Vector 16+43: TIM12 global interrupt */
+VECTOR(stm32_tim13, STM32_IRQ_TIM13) /* Vector 16+44: TIM13 global interrupt */
+VECTOR(stm32_tim14, STM32_IRQ_TIM14) /* Vector 16+45: TIM14 global interrupt */
+UNUSED(STM32_IRQ_RESERVED4) /* Vector 16+46: Reserved 4 */
+UNUSED(STM32_IRQ_RESERVED5) /* Vector 16+47: Reserved 5 */
+VECTOR(stm32_fsmc, STM32_IRQ_FSMC) /* Vector 16+48: FSMC global interrupt */
+UNUSED(STM32_IRQ_RESERVED6) /* Vector 16+49: Reserved 6 */
+VECTOR(stm32_tim5, STM32_IRQ_TIM5) /* Vector 16+50: TIM5 global interrupt */
+VECTOR(stm32_spi3, STM32_IRQ_SPI3) /* Vector 16+51: SPI3 global interrupt */
+VECTOR(stm32_uart4, STM32_IRQ_UART4) /* Vector 16+52: USART2 global interrupt */
+VECTOR(stm32_uart5, STM32_IRQ_UART5) /* Vector 16+53: USART5 global interrupt */
+VECTOR(stm32_tim6, STM32_IRQ_TIM6) /* Vector 16+54: TIM6 global interrupt */
+VECTOR(stm32_tim7, STM32_IRQ_TIM7) /* Vector 16+55: TIM7 global interrupt */
+VECTOR(stm32_dma2ch1, STM32_IRQ_DMA2CH1) /* Vector 16+56: DMA2 Channel 1 global interrupt */
+VECTOR(stm32_dma2ch2, STM32_IRQ_DMA2CH2) /* Vector 16+57: DMA2 Channel 2 global interrupt */
+VECTOR(stm32_dma2ch3, STM32_IRQ_DMA2CH3) /* Vector 16+58: DMA2 Channel 3 global interrupt */
+VECTOR(stm32_dma2ch45, STM32_IRQ_DMA2CH45) /* Vector 16+59: DMA2 Channel 4 and 5 global interrupt */
+VECTOR(stm32_dma2ch5, STM32_IRQ_DMA2CH5) /* Vector 16+60: DMA2 Channel 5 global interrupt */
+
+# endif /* CONFIG_ARMV7M_CMNVECTOR */
#elif defined(CONFIG_STM32_CONNECTIVITYLINE)
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h
index 817e747f7..699ca4fdc 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h
@@ -222,7 +222,7 @@
#define GPIO_ETH_MII_TX_EN_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11)
#define GPIO_ETH_PPS_OUT_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5)
#define GPIO_ETH_PPS_OUT_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN8)
-#define GPIO_ETH_RMII_CRS_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULLGPIO_PORTA|GPIO_PIN7)
+#define GPIO_ETH_RMII_CRS_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7)
#define GPIO_ETH_RMII_REF_CLK (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1)
#define GPIO_ETH_RMII_RXD0 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN4)
#define GPIO_ETH_RMII_RXD1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN5)
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
index ae2436a70..31e51caf0 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
@@ -222,7 +222,7 @@
#define GPIO_ETH_MII_TX_EN_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11)
#define GPIO_ETH_PPS_OUT_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5)
#define GPIO_ETH_PPS_OUT_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN8)
-#define GPIO_ETH_RMII_CRS_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULLGPIO_PORTA|GPIO_PIN7)
+#define GPIO_ETH_RMII_CRS_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7)
#define GPIO_ETH_RMII_REF_CLK (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1)
#define GPIO_ETH_RMII_RXD0 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN4)
#define GPIO_ETH_RMII_RXD1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN5)
diff --git a/nuttx/arch/arm/src/stm32/stm32_adc.h b/nuttx/arch/arm/src/stm32/stm32_adc.h
index c25da3830..7b6c13b33 100644
--- a/nuttx/arch/arm/src/stm32/stm32_adc.h
+++ b/nuttx/arch/arm/src/stm32/stm32_adc.h
@@ -281,7 +281,7 @@
#if defined(ADC1_HAVE_TIMER) || defined(ADC2_HAVE_TIMER) || defined(ADC3_HAVE_TIMER)
# define ADC_HAVE_TIMER 1
-# if defined(CONFIG_STM32_STM32F10XX) && defined(CONFIG_STM32_FORCEPOWER)
+# if defined(CONFIG_STM32_STM32F10XX) && !defined(CONFIG_STM32_FORCEPOWER)
# warning "CONFIG_STM32_FORCEPOWER must be defined to enable the timer(s)"
# endif
#else
diff --git a/nuttx/arch/arm/src/stm32/stm32_eth.c b/nuttx/arch/arm/src/stm32/stm32_eth.c
index 3054142ce..006f67142 100644
--- a/nuttx/arch/arm/src/stm32/stm32_eth.c
+++ b/nuttx/arch/arm/src/stm32/stm32_eth.c
@@ -2594,6 +2594,17 @@ static int stm32_phyinit(FAR struct stm32_ethmac_s *priv)
}
up_mdelay(PHY_RESET_DELAY);
+ /* Perform any necessary, board-specific PHY initialization */
+
+#ifdef CONFIG_STM32_PHYINIT
+ ret = stm32_phy_boardinitialize(0);
+ if (ret < 0)
+ {
+ ndbg("Failed to initialize the PHY: %d\n", ret);
+ return ret;
+ }
+#endif
+
/* Special workaround for the Davicom DM9161 PHY is required. */
#ifdef CONFIG_PHY_DM9161
diff --git a/nuttx/arch/arm/src/stm32/stm32_eth.h b/nuttx/arch/arm/src/stm32/stm32_eth.h
index f0c14b5b1..4501712b1 100644
--- a/nuttx/arch/arm/src/stm32/stm32_eth.h
+++ b/nuttx/arch/arm/src/stm32/stm32_eth.h
@@ -66,14 +66,13 @@ extern "C" {
* Function: stm32_ethinitialize
*
* Description:
- * Initialize the Ethernet driver for one interface. If the STM32 chip
- * supports multiple Ethernet controllers, then board specific logic
- * must implement up_netinitialize() and call this function to initialize
- * the desired interfaces.
+ * Initialize the Ethernet driver for one interface. If the STM32 chip supports
+ * multiple Ethernet controllers, then board specific logic must implement
+ * up_netinitialize() and call this function to initialize the desired interfaces.
*
* Parameters:
- * intf - In the case where there are multiple EMACs, this value
- * identifies which EMAC is to be initialized.
+ * intf - In the case where there are multiple EMACs, this value identifies which
+ * EMAC is to be initialized.
*
* Returned Value:
* OK on success; Negated errno on failure.
@@ -86,6 +85,30 @@ extern "C" {
EXTERN int stm32_ethinitialize(int intf);
#endif
+/************************************************************************************
+ * Function: stm32_phy_boardinitialize
+ *
+ * Description:
+ * Some boards require specialized initialization of the PHY before it can be used.
+ * This may include such things as configuring GPIOs, resetting the PHY, etc. If
+ * CONFIG_STM32_PHYINIT is defined in the configuration then the board specific
+ * logic must provide stm32_phyinitialize(); The STM32 Ethernet driver will call
+ * this function one time before it first uses the PHY.
+ *
+ * Parameters:
+ * intf - Always zero for now.
+ *
+ * Returned Value:
+ * OK on success; Negated errno on failure.
+ *
+ * Assumptions:
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_PHYINIT
+EXTERN int stm32_phy_boardinitialize(int intf);
+#endif
+
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/arch/arm/src/stm32/stm32_i2c.c b/nuttx/arch/arm/src/stm32/stm32_i2c.c
index a4b10b55c..fd682cd5d 100644
--- a/nuttx/arch/arm/src/stm32/stm32_i2c.c
+++ b/nuttx/arch/arm/src/stm32/stm32_i2c.c
@@ -107,17 +107,23 @@
#if !defined(CONFIG_STM32_I2CTIMEOSEC) && !defined(CONFIG_STM32_I2CTIMEOMS)
# define CONFIG_STM32_I2CTIMEOSEC 0
-# define CONFIG_STM32_I2CTIMEOMS 500 /* Default is 500 milliseconds */
+# define CONFIG_STM32_I2CTIMEOMS 500 /* Default is 500 milliseconds */
#elif !defined(CONFIG_STM32_I2CTIMEOSEC)
# define CONFIG_STM32_I2CTIMEOSEC 0 /* User provided milliseconds */
#elif !defined(CONFIG_STM32_I2CTIMEOMS)
-# define CONFIG_STM32_I2CTIMEOMS 0 /* User provided seconds */
+# define CONFIG_STM32_I2CTIMEOMS 0 /* User provided seconds */
#endif
/* Interrupt wait time timeout in system timer ticks */
-#define CONFIG_STM32_I2CTIMEOTICKS \
- (SEC2TICK(CONFIG_STM32_I2CTIMEOSEC) + MSEC2TICK(CONFIG_STM32_I2CTIMEOMS))
+#ifndef CONFIG_STM32_I2CTIMEOTICKS
+# define CONFIG_STM32_I2CTIMEOTICKS \
+ (SEC2TICK(CONFIG_STM32_I2CTIMEOSEC) + MSEC2TICK(CONFIG_STM32_I2CTIMEOMS))
+#endif
+
+#ifndef CONFIG_STM32_I2C_DYNTIMEO_STARTSTOP
+# define CONFIG_STM32_I2C_DYNTIMEO_STARTSTOP TICK2USEC(CONFIG_STM32_I2CTIMEOTICKS)
+#endif
/* On the STM32F103ZE, there is an internal conflict between I2C1 and FSMC. In that
* case, it is necessary to disable FSMC before each I2C1 access and re-enable FSMC
@@ -129,6 +135,18 @@
# define I2C1_FSMC_CONFLICT
#endif
+/* Macros to convert a I2C pin to a GPIO output */
+
+#if defined(CONFIG_STM32_STM32F10XX)
+# define I2C_OUTPUT (GPIO_OUTPUT | GPIO_OUTPUT_SET | GPIO_CNF_OUTOD | \
+ GPIO_MODE_50MHz)
+#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
+# define I2C_OUTPUT (GPIO_OUTPUT | GPIO_FLOAT | GPIO_OPENDRAIN |\
+ GPIO_SPEED_50MHz | GPIO_OUTPUT_SET)
+#endif
+
+#define MKI2C_OUTPUT(p) (((p) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | I2C_OUTPUT)
+
/* Debug ****************************************************************************/
/* CONFIG_DEBUG_I2C + CONFIG_DEBUG enables general I2C debug output. */
@@ -200,18 +218,16 @@ struct stm32_trace_s
struct stm32_i2c_config_s
{
- uint32_t base; /* I2C base address */
+ uint32_t base; /* I2C base address */
+ uint32_t clk_bit; /* Clock enable bit */
+ uint32_t reset_bit; /* Reset bit */
+ uint32_t scl_pin; /* GPIO configuration for SCL as SCL */
+ uint32_t sda_pin; /* GPIO configuration for SDA as SDA */
#ifndef CONFIG_I2C_POLLED
- int ( *isr)(int, void *); /* Interrupt handler */
+ int (*isr)(int, void *); /* Interrupt handler */
+ uint32_t ev_irq; /* Event IRQ */
+ uint32_t er_irq; /* Error IRQ */
#endif
- uint32_t clk_bit; /* Clock enable bit */
- uint32_t reset_bit; /* Reset bit */
- uint32_t scl_pin; /* GPIO configuration for SCL as SCL */
- uint32_t scl_gpio; /* GPIO configuration for SCL as a GPIO */
- uint32_t sda_pin; /* GPIO configuration for SDA as SDA */
- uint32_t sda_gpio; /* GPIO configuration for SDA as a GPIO */
- uint32_t ev_irq; /* Event IRQ */
- uint32_t er_irq; /* Error IRQ */
};
/* I2C Device Private Data */
@@ -219,31 +235,31 @@ struct stm32_i2c_config_s
struct stm32_i2c_priv_s
{
const struct stm32_i2c_config_s *config; /* Port configuration */
- int refs; /* Referernce count */
- sem_t sem_excl; /* Mutual exclusion semaphore */
+ int refs; /* Referernce count */
+ sem_t sem_excl; /* Mutual exclusion semaphore */
#ifndef CONFIG_I2C_POLLED
- sem_t sem_isr; /* Interrupt wait semaphore */
+ sem_t sem_isr; /* Interrupt wait semaphore */
#endif
- volatile uint8_t intstate; /* Interrupt handshake (see enum stm32_intstate_e) */
+ volatile uint8_t intstate; /* Interrupt handshake (see enum stm32_intstate_e) */
- uint8_t msgc; /* Message count */
- struct i2c_msg_s *msgv; /* Message list */
- uint8_t *ptr; /* Current message buffer */
- int dcnt; /* Current message length */
- uint16_t flags; /* Current message flags */
+ uint8_t msgc; /* Message count */
+ struct i2c_msg_s *msgv; /* Message list */
+ uint8_t *ptr; /* Current message buffer */
+ int dcnt; /* Current message length */
+ uint16_t flags; /* Current message flags */
/* I2C trace support */
#ifdef CONFIG_I2C_TRACE
- int tndx; /* Trace array index */
- uint32_t start_time; /* Time when the trace was started */
+ int tndx; /* Trace array index */
+ uint32_t start_time; /* Time when the trace was started */
/* The actual trace data */
struct stm32_trace_s trace[CONFIG_I2C_NTRACE];
#endif
- uint32_t status; /* End of transfer SR2|SR1 status */
+ uint32_t status; /* End of transfer SR2|SR1 status */
};
/* I2C Device, Instance */
@@ -270,8 +286,11 @@ static inline void stm32_i2c_modifyreg(FAR struct stm32_i2c_priv_s *priv,
uint8_t offset, uint16_t clearbits,
uint16_t setbits);
static inline void stm32_i2c_sem_wait(FAR struct i2c_dev_s *dev);
-static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv, int timeout_us);
-static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv, int timeout_us);
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+static useconds_t stm32_i2c_tousecs(int msgc, FAR struct i2c_msg_s *msgs);
+#endif /* CONFIG_STM32_I2C_DYNTIMEO */
+static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv);
+static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv);
static inline void stm32_i2c_sem_post(FAR struct i2c_dev_s *dev);
static inline void stm32_i2c_sem_init(FAR struct i2c_dev_s *dev);
static inline void stm32_i2c_sem_destroy(FAR struct i2c_dev_s *dev);
@@ -281,7 +300,7 @@ static void stm32_i2c_tracenew(FAR struct stm32_i2c_priv_s *priv, uint32_t statu
static void stm32_i2c_traceevent(FAR struct stm32_i2c_priv_s *priv,
enum stm32_trace_e event, uint32_t parm);
static void stm32_i2c_tracedump(FAR struct stm32_i2c_priv_s *priv);
-#endif
+#endif /* CONFIG_I2C_TRACE */
static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv,
uint32_t frequency);
static inline void stm32_i2c_sendstart(FAR struct stm32_i2c_priv_s *priv);
@@ -291,7 +310,7 @@ static inline uint32_t stm32_i2c_getstatus(FAR struct stm32_i2c_priv_s *priv);
#ifdef I2C1_FSMC_CONFLICT
static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv);
static inline void stm32_i2c_enablefsmc(uint32_t ahbenr);
-#endif
+#endif /* I2C1_FSMC_CONFLICT */
static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv);
#ifndef CONFIG_I2C_POLLED
#ifdef CONFIG_STM32_I2C1
@@ -329,27 +348,18 @@ static int stm32_i2c_transfer(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *m
************************************************************************************/
#ifdef CONFIG_STM32_I2C1
-# ifndef GPIO_I2C1_SCL_GPIO
-# define GPIO_I2C1_SCL_GPIO 0
-# endif
-# ifndef GPIO_I2C1_SDA_GPIO
-# define GPIO_I2C1_SDA_GPIO 0
-# endif
-
static const struct stm32_i2c_config_s stm32_i2c1_config =
{
.base = STM32_I2C1_BASE,
-#ifndef CONFIG_I2C_POLLED
- .isr = stm32_i2c1_isr,
-#endif
.clk_bit = RCC_APB1ENR_I2C1EN,
.reset_bit = RCC_APB1RSTR_I2C1RST,
.scl_pin = GPIO_I2C1_SCL,
- .scl_gpio = GPIO_I2C1_SCL_GPIO,
.sda_pin = GPIO_I2C1_SDA,
- .sda_gpio = GPIO_I2C1_SDA_GPIO,
+#ifndef CONFIG_I2C_POLLED
+ .isr = stm32_i2c1_isr,
.ev_irq = STM32_IRQ_I2C1EV,
.er_irq = STM32_IRQ_I2C1ER
+#endif
};
struct stm32_i2c_priv_s stm32_i2c1_priv =
@@ -367,27 +377,18 @@ struct stm32_i2c_priv_s stm32_i2c1_priv =
#endif
#ifdef CONFIG_STM32_I2C2
-# ifndef GPIO_I2C2_SCL_GPIO
-# define GPIO_I2C2_SCL_GPIO 0
-# endif
-# ifndef GPIO_I2C2_SDA_GPIO
-# define GPIO_I2C2_SDA_GPIO 0
-# endif
-
static const struct stm32_i2c_config_s stm32_i2c2_config =
{
.base = STM32_I2C2_BASE,
-#ifndef CONFIG_I2C_POLLED
- .isr = stm32_i2c2_isr,
-#endif
.clk_bit = RCC_APB1ENR_I2C2EN,
.reset_bit = RCC_APB1RSTR_I2C2RST,
.scl_pin = GPIO_I2C2_SCL,
- .scl_gpio = GPIO_I2C2_SCL_GPIO,
.sda_pin = GPIO_I2C2_SDA,
- .sda_gpio = GPIO_I2C2_SDA_GPIO,
+#ifndef CONFIG_I2C_POLLED
+ .isr = stm32_i2c2_isr,
.ev_irq = STM32_IRQ_I2C2EV,
.er_irq = STM32_IRQ_I2C2ER
+#endif
};
struct stm32_i2c_priv_s stm32_i2c2_priv =
@@ -405,27 +406,18 @@ struct stm32_i2c_priv_s stm32_i2c2_priv =
#endif
#ifdef CONFIG_STM32_I2C3
-# ifndef GPIO_I2C3_SCL_GPIO
-# define GPIO_I2C3_SCL_GPIO 0
-# endif
-# ifndef GPIO_I2C3_SDA_GPIO
-# define GPIO_I2C3_SDA_GPIO 0
-# endif
-
static const struct stm32_i2c_config_s stm32_i2c3_config =
{
.base = STM32_I2C3_BASE,
-#ifndef CONFIG_I2C_POLLED
- .isr = stm32_i2c3_isr,
-#endif
.clk_bit = RCC_APB1ENR_I2C3EN,
.reset_bit = RCC_APB1RSTR_I2C3RST,
.scl_pin = GPIO_I2C3_SCL,
- .scl_gpio = GPIO_I2C3_SCL_GPIO,
.sda_pin = GPIO_I2C3_SDA,
- .sda_gpio = GPIO_I2C3_SDA_GPIO,
+#ifndef CONFIG_I2C_POLLED
+ .isr = stm32_i2c3_isr,
.ev_irq = STM32_IRQ_I2C3EV,
.er_irq = STM32_IRQ_I2C3ER
+#endif
};
struct stm32_i2c_priv_s stm32_i2c3_priv =
@@ -526,6 +518,35 @@ static inline void stm32_i2c_sem_wait(FAR struct i2c_dev_s *dev)
}
/************************************************************************************
+ * Name: stm32_i2c_tousecs
+ *
+ * Description:
+ * Return a micro-second delay based on the number of bytes left to be processed.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+static useconds_t stm32_i2c_tousecs(int msgc, FAR struct i2c_msg_s *msgs)
+{
+ size_t bytecount = 0;
+ int i;
+
+ /* Count the number of bytes left to process */
+
+ for (i = 0; i < msgc; i++)
+ {
+ bytecount += msgs[i].length;
+ }
+
+ /* Then return a number of microseconds based on a user provided scaling
+ * factor.
+ */
+
+ return (useconds_t)(CONFIG_STM32_I2C_DYNTIMEO_USECPERBYTE * bytecount);
+}
+#endif
+
+/************************************************************************************
* Name: stm32_i2c_sem_waitdone
*
* Description:
@@ -534,7 +555,7 @@ static inline void stm32_i2c_sem_wait(FAR struct i2c_dev_s *dev)
************************************************************************************/
#ifndef CONFIG_I2C_POLLED
-static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv, int timeout_us)
+static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
{
struct timespec abstime;
irqstate_t flags;
@@ -566,31 +587,24 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv, int
#if CONFIG_STM32_I2CTIMEOSEC > 0
abstime.tv_sec += CONFIG_STM32_I2CTIMEOSEC;
#endif
-#if CONFIG_STM32_I2CTIMEOUS_PER_BYTE > 0
- /* Count the number of bytes left to process */
- int i;
- int bytecount = 0;
- for (i = 0; i < priv->msgc; i++)
+ /* Add a value proportional to the number of bytes in the transfer */
+
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+ abstime.tv_nsec += 1000 * stm32_i2c_tousecs(priv->msgc, priv->msgv);
+ if (abstime.tv_nsec > 1000 * 1000 * 1000)
{
- bytecount += priv->msgv[i].length;
+ abstime.tv_sec++;
+ abstime.tv_nsec -= 1000 * 1000 * 1000;
}
- abstime.tv_nsec += (CONFIG_STM32_I2CTIMEOUS_PER_BYTE * bytecount) * 1000;
+#elif CONFIG_STM32_I2CTIMEOMS > 0
+ abstime.tv_nsec += CONFIG_STM32_I2CTIMEOMS * 1000 * 1000;
if (abstime.tv_nsec > 1000 * 1000 * 1000)
{
abstime.tv_sec++;
abstime.tv_nsec -= 1000 * 1000 * 1000;
}
-#else
- #if CONFIG_STM32_I2CTIMEOMS > 0
- abstime.tv_nsec += CONFIG_STM32_I2CTIMEOMS * 1000 * 1000;
- if (abstime.tv_nsec > 1000 * 1000 * 1000)
- {
- abstime.tv_sec++;
- abstime.tv_nsec -= 1000 * 1000 * 1000;
- }
- #endif
#endif
/* Wait until either the transfer is complete or the timeout expires */
@@ -624,12 +638,21 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv, int
return ret;
}
#else
-static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv, int timeout_us)
+static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
{
+ uint32_t timeout;
uint32_t start;
uint32_t elapsed;
int ret;
+ /* Get the timeout value */
+
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+ timeout = USEC2TICK(stm32_i2c_tousecs(priv->msgc, priv->msgv));
+#else
+ timeout = CONFIG_STM32_I2CTIMEOTICKS;
+#endif
+
/* Signal the interrupt handler that we are waiting. NOTE: Interrupts
* are currently disabled but will be temporarily re-enabled below when
* sem_timedwait() sleeps.
@@ -652,10 +675,11 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv, int
}
/* Loop until the transfer is complete. */
- while (priv->intstate != INTSTATE_DONE && elapsed < USEC2TICK(timeout_us));
+
+ while (priv->intstate != INTSTATE_DONE && elapsed < timeout);
i2cvdbg("intstate: %d elapsed: %d threshold: %d status: %08x\n",
- priv->intstate, elapsed, USEC2TICK(timeout_us), priv->status);
+ priv->intstate, elapsed, timeout, priv->status);
/* Set the interrupt state back to IDLE */
@@ -673,13 +697,22 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv, int
*
************************************************************************************/
-static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv, int timeout_us)
+static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
{
uint32_t start;
uint32_t elapsed;
+ uint32_t timeout;
uint32_t cr1;
uint32_t sr1;
+ /* Select a timeout */
+
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+ timeout = USEC2TICK(CONFIG_STM32_I2C_DYNTIMEO_STARTSTOP);
+#else
+ timeout = CONFIG_STM32_I2CTIMEOTICKS;
+#endif
+
/* Wait as stop might still be in progress; but stop might also
* be set because of a timeout error: "The [STOP] bit is set and
* cleared by software, cleared by hardware when a Stop condition is
@@ -712,7 +745,7 @@ static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv, int
/* Loop until the stop is complete or a timeout occurs. */
- while (elapsed < USEC2TICK(timeout_us));
+ while (elapsed < timeout);
/* If we get here then a timeout occurred with the STOP condition
* still pending.
@@ -932,7 +965,7 @@ static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv, uint32_t frequ
{
/* Fast mode speed calculation with Tlow/Thigh = 16/9 */
-#ifdef CONFIG_I2C_DUTY16_9
+#ifdef CONFIG_STM32_I2C_DUTY16_9
speed = (uint16_t)(STM32_PCLK1_FREQUENCY / (frequency * 25));
/* Set DUTY and fast speed bits */
@@ -1071,7 +1104,7 @@ static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv)
/* Is this I2C1 */
-#ifdef CONFIG_STM32_I2C2
+#if defined(CONFIG_STM32_I2C2) || defined(CONFIG_STM32_I2C3)
if (priv->config->base == STM32_I2C1_BASE)
#endif
{
@@ -1198,10 +1231,14 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv)
{
stm32_i2c_traceevent(priv, I2CEVENT_RCVBYTE, priv->dcnt);
+ /* No interrupts or context switches may occur in the following
+ * sequence. Otherwise, additional bytes may be sent by the
+ * device.
+ */
+
#ifdef CONFIG_I2C_POLLED
irqstate_t state = irqsave();
#endif
-
/* Receive a byte */
*priv->ptr++ = stm32_i2c_getreg(priv, STM32_I2C_DR_OFFSET);
@@ -1217,7 +1254,6 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv)
#ifdef CONFIG_I2C_POLLED
irqrestore(state);
#endif
-
}
}
@@ -1408,7 +1444,6 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv)
/* Enable power and reset the peripheral */
modifyreg32(STM32_RCC_APB1ENR, 0, priv->config->clk_bit);
-
modifyreg32(STM32_RCC_APB1RSTR, 0, priv->config->reset_bit);
modifyreg32(STM32_RCC_APB1RSTR, priv->config->reset_bit, 0);
@@ -1428,10 +1463,10 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv)
/* Attach ISRs */
#ifndef CONFIG_I2C_POLLED
- irq_attach(priv->config->ev_irq, priv->config->isr);
- irq_attach(priv->config->er_irq, priv->config->isr);
- up_enable_irq(priv->config->ev_irq);
- up_enable_irq(priv->config->er_irq);
+ irq_attach(priv->config->ev_irq, priv->config->isr);
+ irq_attach(priv->config->er_irq, priv->config->isr);
+ up_enable_irq(priv->config->ev_irq);
+ up_enable_irq(priv->config->er_irq);
#endif
/* Set peripheral frequency, where it must be at least 2 MHz for 100 kHz
@@ -1461,17 +1496,23 @@ static int stm32_i2c_deinit(FAR struct stm32_i2c_priv_s *priv)
stm32_i2c_putreg(priv, STM32_I2C_CR1_OFFSET, 0);
+ /* Unconfigure GPIO pins */
+
stm32_unconfiggpio(priv->config->scl_pin);
stm32_unconfiggpio(priv->config->sda_pin);
+ /* Disable and detach interrupts */
+
#ifndef CONFIG_I2C_POLLED
up_disable_irq(priv->config->ev_irq);
up_disable_irq(priv->config->er_irq);
irq_detach(priv->config->ev_irq);
irq_detach(priv->config->er_irq);
#endif
- modifyreg32(STM32_RCC_APB1ENR, priv->config->clk_bit, 0);
+ /* Disable clocking */
+
+ modifyreg32(STM32_RCC_APB1ENR, priv->config->clk_bit, 0);
return OK;
}
@@ -1533,14 +1574,14 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
struct stm32_i2c_inst_s *inst = (struct stm32_i2c_inst_s *)dev;
FAR struct stm32_i2c_priv_s *priv = inst->priv;
uint32_t status = 0;
- //uint32_t ahbenr;
+ uint32_t ahbenr;
int errval = 0;
ASSERT(count);
/* Disable FSMC that shares a pin with I2C1 (LBAR) */
- (void)stm32_i2c_disablefsmc(priv);
+ ahbenr = stm32_i2c_disablefsmc(priv);
/* Wait for any STOP in progress. NOTE: If we have to disable the FSMC
* then we cannot do this at the top of the loop, unfortunately. The STOP
@@ -1548,11 +1589,7 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
*/
#ifndef I2C1_FSMC_CONFLICT
- #if CONFIG_STM32_I2CTIMEOUS_START_STOP > 0
- stm32_i2c_sem_waitstop(priv, CONFIG_STM32_I2CTIMEOUS_START_STOP);
- #else
- stm32_i2c_sem_waitstop(priv, CONFIG_STM32_I2CTIMEOMS + CONFIG_STM32_I2CTIMEOSEC * 1000000);
- #endif
+ stm32_i2c_sem_waitstop(priv);
#endif
/* Clear any pending error interrupts */
@@ -1573,22 +1610,6 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
priv->msgv = msgs;
priv->msgc = count;
- /* Calculate timeout values */
- int timeout_us = 0;
- #if CONFIG_STM32_I2CTIMEOUS_PER_BYTE > 0
- /* Count the number of bytes left to process */
- int i;
- int bytecount = 10;
- for (i = 0; i < count; i++)
- {
- bytecount += msgs[i].length;
- }
- timeout_us = CONFIG_STM32_I2CTIMEOUS_PER_BYTE * bytecount;
- //i2cvdbg("i2c wait: %d\n", timeout_us);
- #else
- timeout_us = CONFIG_STM32_I2CTIMEOMS + CONFIG_STM32_I2CTIMEOSEC * 1000000;
- #endif
-
/* Reset I2C trace logic */
stm32_i2c_tracereset(priv);
@@ -1608,7 +1629,7 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
* the BUSY flag.
*/
- if (stm32_i2c_sem_waitdone(priv, timeout_us) < 0)
+ if (stm32_i2c_sem_waitdone(priv) < 0)
{
status = stm32_i2c_getstatus(priv);
errval = ETIMEDOUT;
@@ -1623,7 +1644,9 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
*/
stm32_i2c_clrstart(priv);
- // XXX also clear busy flag in case of timeout
+
+ /* Clear busy flag in case of timeout */
+
status = priv->status & 0xffff;
}
else
@@ -1953,11 +1976,14 @@ int up_i2cuninitialize(FAR struct i2c_dev_s * dev)
*
************************************************************************************/
+#ifdef CONFIG_I2C_RESET
int up_i2creset(FAR struct i2c_dev_s * dev)
{
struct stm32_i2c_priv_s * priv;
- unsigned clock_count;
- unsigned stretch_count;
+ unsigned int clock_count;
+ unsigned int stretch_count;
+ uint32_t scl_gpio;
+ uint32_t sda_gpio;
int ret = ERROR;
irqstate_t state;
@@ -1979,83 +2005,70 @@ int up_i2creset(FAR struct i2c_dev_s * dev)
stm32_i2c_deinit(priv);
- /* If possible, use GPIO configuration to un-wedge the bus */
+ /* Use GPIO configuration to un-wedge the bus */
- if ((priv->config->scl_gpio != 0) && (priv->config->sda_gpio != 0))
+ scl_gpio = MKI2C_OUTPUT(priv->config->scl_pin);
+ sda_gpio = MKI2C_OUTPUT(priv->config->sda_pin);
+
+ /* Clock the bus until any slaves currently driving it let it go. */
+
+ clock_count = 0;
+ while (!stm32_gpioread(sda_gpio))
{
- stm32_configgpio(priv->config->scl_gpio);
- stm32_configgpio(priv->config->sda_gpio);
+ /* Give up if we have tried too hard */
- /*
- * Clock the bus until any slaves currently driving it let it go.
- */
+ if (clock_count++ > 1000)
+ {
+ goto out;
+ }
- clock_count = 0;
- while (!stm32_gpioread(priv->config->sda_gpio))
- {
+ /* Sniff to make sure that clock stretching has finished.
+ *
+ * If the bus never relaxes, the reset has failed.
+ */
+ stretch_count = 0;
+ while (!stm32_gpioread(scl_gpio))
+ {
/* Give up if we have tried too hard */
- if (clock_count++ > 1000)
+ if (stretch_count++ > 1000)
{
goto out;
}
- /*
- * Sniff to make sure that clock stretching has finished.
- *
- * If the bus never relaxes, the reset has failed.
- */
-
- stretch_count = 0;
- while (!stm32_gpioread(priv->config->scl_gpio))
- {
-
- /* Give up if we have tried too hard */
-
- if (stretch_count++ > 1000)
- {
- goto out;
- }
-
- up_udelay(10);
-
- }
-
- /* Drive SCL low */
-
- stm32_gpiowrite(priv->config->scl_gpio, 0);
- up_udelay(10);
-
- /* Drive SCL high again */
-
- stm32_gpiowrite(priv->config->scl_gpio, 1);
- up_udelay(10);
-
+ up_udelay(10);
}
- /*
- * Generate a start followed by a stop to reset slave
- * state machines.
- */
+ /* Drive SCL low */
- stm32_gpiowrite(priv->config->sda_gpio, 0);
- up_udelay(10);
- stm32_gpiowrite(priv->config->scl_gpio, 0);
- up_udelay(10);
- stm32_gpiowrite(priv->config->scl_gpio, 1);
- up_udelay(10);
- stm32_gpiowrite(priv->config->sda_gpio, 1);
+ stm32_gpiowrite(scl_gpio, 0);
up_udelay(10);
- /*
- * Revert the GPIO configuration.
- */
- stm32_unconfiggpio(priv->config->sda_gpio);
- stm32_unconfiggpio(priv->config->scl_gpio);
+ /* Drive SCL high again */
+ stm32_gpiowrite(scl_gpio, 1);
+ up_udelay(10);
}
+ /* Generate a start followed by a stop to reset slave
+ * state machines.
+ */
+
+ stm32_gpiowrite(sda_gpio, 0);
+ up_udelay(10);
+ stm32_gpiowrite(scl_gpio, 0);
+ up_udelay(10);
+ stm32_gpiowrite(scl_gpio, 1);
+ up_udelay(10);
+ stm32_gpiowrite(sda_gpio, 1);
+ up_udelay(10);
+
+ /* Revert the GPIO configuration. */
+
+ stm32_unconfiggpio(sda_gpio);
+ stm32_unconfiggpio(scl_gpio);
+
/* Re-init the port */
stm32_i2c_init(priv);
@@ -2063,11 +2076,11 @@ int up_i2creset(FAR struct i2c_dev_s * dev)
out:
- /* release the port for re-use by other clients */
+ /* Release the port for re-use by other clients */
stm32_i2c_sem_post(dev);
-
return ret;
}
+#endif /* CONFIG_I2C_RESET */
-#endif /* defined(CONFIG_STM32_I2C1) || defined(CONFIG_STM32_I2C2) || defined(CONFIG_STM32_I2C3) */
+#endif /* CONFIG_STM32_I2C1 || CONFIG_STM32_I2C2 || CONFIG_STM32_I2C3 */
diff --git a/nuttx/arch/arm/src/stm32/stm32_lowputc.c b/nuttx/arch/arm/src/stm32/stm32_lowputc.c
index 7f7205672..6cb07dad9 100644
--- a/nuttx/arch/arm/src/stm32/stm32_lowputc.c
+++ b/nuttx/arch/arm/src/stm32/stm32_lowputc.c
@@ -67,6 +67,14 @@
# define STM32_CONSOLE_2STOP CONFIG_USART1_2STOP
# define STM32_CONSOLE_TX GPIO_USART1_TX
# define STM32_CONSOLE_RX GPIO_USART1_RX
+# ifdef CONFIG_USART1_RS485
+# define STM32_CONSOLE_RS485_DIR GPIO_USART1_RS485_DIR
+# if (CONFIG_USART1_RS485_DIR_POLARITY == 0)
+# define STM32_CONSOLE_RS485_DIR_POLARITY false
+# else
+# define STM32_CONSOLE_RS485_DIR_POLARITY true
+# endif
+# endif
#elif defined(CONFIG_USART2_SERIAL_CONSOLE)
# define STM32_CONSOLE_BASE STM32_USART2_BASE
# define STM32_APBCLOCK STM32_PCLK1_FREQUENCY
@@ -76,6 +84,14 @@
# define STM32_CONSOLE_2STOP CONFIG_USART2_2STOP
# define STM32_CONSOLE_TX GPIO_USART2_TX
# define STM32_CONSOLE_RX GPIO_USART2_RX
+# ifdef CONFIG_USART2_RS485
+# define STM32_CONSOLE_RS485_DIR GPIO_USART2_RS485_DIR
+# if (CONFIG_USART2_RS485_DIR_POLARITY == 0)
+# define STM32_CONSOLE_RS485_DIR_POLARITY false
+# else
+# define STM32_CONSOLE_RS485_DIR_POLARITY true
+# endif
+# endif
#elif defined(CONFIG_USART3_SERIAL_CONSOLE)
# define STM32_CONSOLE_BASE STM32_USART3_BASE
# define STM32_APBCLOCK STM32_PCLK1_FREQUENCY
@@ -85,6 +101,14 @@
# define STM32_CONSOLE_2STOP CONFIG_USART3_2STOP
# define STM32_CONSOLE_TX GPIO_USART3_TX
# define STM32_CONSOLE_RX GPIO_USART3_RX
+# ifdef CONFIG_USART3_RS485
+# define STM32_CONSOLE_RS485_DIR GPIO_USART3_RS485_DIR
+# if (CONFIG_USART3_RS485_DIR_POLARITY == 0)
+# define STM32_CONSOLE_RS485_DIR_POLARITY false
+# else
+# define STM32_CONSOLE_RS485_DIR_POLARITY true
+# endif
+# endif
#elif defined(CONFIG_UART4_SERIAL_CONSOLE)
# define STM32_CONSOLE_BASE STM32_UART4_BASE
# define STM32_APBCLOCK STM32_PCLK1_FREQUENCY
@@ -94,6 +118,14 @@
# define STM32_CONSOLE_2STOP CONFIG_UART4_2STOP
# define STM32_CONSOLE_TX GPIO_UART4_TX
# define STM32_CONSOLE_RX GPIO_UART4_RX
+# ifdef CONFIG_UART4_RS485
+# define STM32_CONSOLE_RS485_DIR GPIO_UART4_RS485_DIR
+# if (CONFIG_UART4_RS485_DIR_POLARITY == 0)
+# define STM32_CONSOLE_RS485_DIR_POLARITY false
+# else
+# define STM32_CONSOLE_RS485_DIR_POLARITY true
+# endif
+# endif
#elif defined(CONFIG_UART5_SERIAL_CONSOLE)
# define STM32_CONSOLE_BASE STM32_UART5_BASE
# define STM32_APBCLOCK STM32_PCLK1_FREQUENCY
@@ -103,6 +135,14 @@
# define STM32_CONSOLE_2STOP CONFIG_UART5_2STOP
# define STM32_CONSOLE_TX GPIO_UART5_TX
# define STM32_CONSOLE_RX GPIO_UART5_RX
+# ifdef CONFIG_UART5_RS485
+# define STM32_CONSOLE_RS485_DIR GPIO_UART5_RS485_DIR
+# if (CONFIG_UART5_RS485_DIR_POLARITY == 0)
+# define STM32_CONSOLE_RS485_DIR_POLARITY false
+# else
+# define STM32_CONSOLE_RS485_DIR_POLARITY true
+# endif
+# endif
#elif defined(CONFIG_USART6_SERIAL_CONSOLE)
# define STM32_CONSOLE_BASE STM32_USART6_BASE
# define STM32_APBCLOCK STM32_PCLK2_FREQUENCY
@@ -112,6 +152,14 @@
# define STM32_CONSOLE_2STOP CONFIG_USART6_2STOP
# define STM32_CONSOLE_TX GPIO_USART6_TX
# define STM32_CONSOLE_RX GPIO_USART6_RX
+# ifdef CONFIG_USART6_RS485
+# define STM32_CONSOLE_RS485_DIR GPIO_USART6_RS485_DIR
+# if (CONFIG_USART6_RS485_DIR_POLARITY == 0)
+# define STM32_CONSOLE_RS485_DIR_POLARITY false
+# else
+# define STM32_CONSOLE_RS485_DIR_POLARITY true
+# endif
+# endif
#endif
/* CR1 settings */
@@ -230,10 +278,19 @@ void up_lowputc(char ch)
/* Wait until the TX data register is empty */
while ((getreg32(STM32_CONSOLE_BASE + STM32_USART_SR_OFFSET) & USART_SR_TXE) == 0);
+#if STM32_CONSOLE_RS485_DIR
+ stm32_gpiowrite(STM32_CONSOLE_RS485_DIR, STM32_CONSOLE_RS485_DIR_POLARITY);
+#endif
/* Then send the character */
putreg32((uint32_t)ch, STM32_CONSOLE_BASE + STM32_USART_DR_OFFSET);
+
+#if STM32_CONSOLE_RS485_DIR
+ while ((getreg32(STM32_CONSOLE_BASE + STM32_USART_SR_OFFSET) & USART_SR_TC) == 0);
+ stm32_gpiowrite(STM32_CONSOLE_RS485_DIR, !STM32_CONSOLE_RS485_DIR_POLARITY);
+#endif
+
#endif
}
@@ -328,7 +385,14 @@ void stm32_lowsetup(void)
#ifdef STM32_CONSOLE_TX
stm32_configgpio(STM32_CONSOLE_TX);
- stm32_configgpio(STM32_CONSOLE_TX);
+#endif
+#ifdef STM32_CONSOLE_RX
+ stm32_configgpio(STM32_CONSOLE_RX);
+#endif
+
+#if STM32_CONSOLE_RS485_DIR
+ stm32_configgpio(STM32_CONSOLE_RS485_DIR);
+ stm32_gpiowrite(STM32_CONSOLE_RS485_DIR, !STM32_CONSOLE_RS485_DIR_POLARITY);
#endif
/* Enable and configure the selected console device */
@@ -382,7 +446,14 @@ void stm32_lowsetup(void)
#ifdef STM32_CONSOLE_TX
stm32_configgpio(STM32_CONSOLE_TX);
- stm32_configgpio(STM32_CONSOLE_TX);
+#endif
+#ifdef STM32_CONSOLE_RX
+ stm32_configgpio(STM32_CONSOLE_RX);
+#endif
+
+#if STM32_CONSOLE_RS485_DIR
+ stm32_configgpio(STM32_CONSOLE_RS485_DIR);
+ stm32_gpiowrite(STM32_CONSOLE_RS485_DIR, !STM32_CONSOLE_RS485_DIR_POLARITY);
#endif
/* Enable and configure the selected console device */
diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
index 461d500ad..94772b693 100644
--- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
+++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
@@ -3651,10 +3651,14 @@ static int stm32_epout_configure(FAR struct stm32_ep_s *privep, uint8_t eptype,
regval = stm32_getreg(regaddr);
if ((regval & OTGFS_DOEPCTL_USBAEP) == 0)
{
- regval &= ~(OTGFS_DOEPCTL_MPSIZ_MASK | OTGFS_DIEPCTL_EPTYP_MASK | OTGFS_DIEPCTL_TXFNUM_MASK);
+ if (regval & OTGFS_DOEPCTL_NAKSTS)
+ {
+ regval |= OTGFS_DOEPCTL_CNAK;
+ }
+
+ regval &= ~(OTGFS_DOEPCTL_MPSIZ_MASK | OTGFS_DOEPCTL_EPTYP_MASK);
regval |= mpsiz;
regval |= (eptype << OTGFS_DOEPCTL_EPTYP_SHIFT);
- regval |= (eptype << OTGFS_DIEPCTL_TXFNUM_SHIFT);
regval |= (OTGFS_DOEPCTL_SD0PID | OTGFS_DOEPCTL_USBAEP);
stm32_putreg(regval, regaddr);
@@ -3743,6 +3747,11 @@ static int stm32_epin_configure(FAR struct stm32_ep_s *privep, uint8_t eptype,
regval = stm32_getreg(regaddr);
if ((regval & OTGFS_DIEPCTL_USBAEP) == 0)
{
+ if (regval & OTGFS_DIEPCTL_NAKSTS)
+ {
+ regval |= OTGFS_DIEPCTL_CNAK;
+ }
+
regval &= ~(OTGFS_DIEPCTL_MPSIZ_MASK | OTGFS_DIEPCTL_EPTYP_MASK | OTGFS_DIEPCTL_TXFNUM_MASK);
regval |= mpsiz;
regval |= (eptype << OTGFS_DIEPCTL_EPTYP_SHIFT);
@@ -3900,7 +3909,7 @@ static void stm32_epout_disable(FAR struct stm32_ep_s *privep)
* Name: stm32_epin_disable
*
* Description:
- * Diable an IN endpoint will no longer be used
+ * Disable an IN endpoint when it will no longer be used
*
*******************************************************************************/
@@ -3912,6 +3921,17 @@ static void stm32_epin_disable(FAR struct stm32_ep_s *privep)
usbtrace(TRACE_EPDISABLE, privep->epphy);
+ /* After USB reset, the endpoint will already be deactivated by the
+ * hardware. Trying to disable again will just hang in the wait.
+ */
+
+ regaddr = STM32_OTGFS_DIEPCTL(privep->epphy);
+ regval = stm32_getreg(regaddr);
+ if ((regval & OTGFS_DIEPCTL_USBAEP) == 0)
+ {
+ return;
+ }
+
/* Make sure that there is no pending IPEPNE interrupt (because we are
* to poll this bit below).
*/
diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfshost.c b/nuttx/arch/arm/src/stm32/stm32_otgfshost.c
index 02b12ec87..80a9392dc 100644
--- a/nuttx/arch/arm/src/stm32/stm32_otgfshost.c
+++ b/nuttx/arch/arm/src/stm32/stm32_otgfshost.c
@@ -51,6 +51,7 @@
#include <nuttx/arch.h>
#include <nuttx/kmalloc.h>
+#include <nuttx/clock.h>
#include <nuttx/usb/usb.h>
#include <nuttx/usb/usbhost.h>
@@ -149,8 +150,8 @@
#define STM32_READY_DELAY 200000 /* In loop counts */
#define STM32_FLUSH_DELAY 200000 /* In loop counts */
-#define STM32_SETUP_DELAY 5000 /* In frames */
-#define STM32_DATANAK_DELAY 5000 /* In frames */
+#define STM32_SETUP_DELAY (5000 / MSEC_PER_TICK) /* 5 seconds in system ticks */
+#define STM32_DATANAK_DELAY (5000 / MSEC_PER_TICK) /* 5 seconds in system ticks */
/* Ever-present MIN/MAX macros */
@@ -305,7 +306,9 @@ static void stm32_chan_wakeup(FAR struct stm32_usbhost_s *priv,
/* Control/data transfer logic *************************************************/
static void stm32_transfer_start(FAR struct stm32_usbhost_s *priv, int chidx);
+#if 0 /* Not used */
static inline uint16_t stm32_getframe(void);
+#endif
static int stm32_ctrl_sendsetup(FAR struct stm32_usbhost_s *priv,
FAR const struct usb_ctrlreq_s *req);
static int stm32_ctrl_senddata(FAR struct stm32_usbhost_s *priv,
@@ -1182,14 +1185,18 @@ static void stm32_transfer_start(FAR struct stm32_usbhost_s *priv, int chidx)
* Name: stm32_getframe
*
* Description:
- * Get the current frame number.
+ * Get the current frame number. The frame number (FRNUM) field increments
+ * when a new SOF is transmitted on the USB, and is cleared to 0 when it
+ * reaches 0x3fff.
*
*******************************************************************************/
+#if 0 /* Not used */
static inline uint16_t stm32_getframe(void)
{
return (uint16_t)(stm32_getreg(STM32_OTGFS_HFNUM) & OTGFS_HFNUM_FRNUM_MASK);
}
+#endif
/*******************************************************************************
* Name: stm32_ctrl_sendsetup
@@ -1203,14 +1210,14 @@ static int stm32_ctrl_sendsetup(FAR struct stm32_usbhost_s *priv,
FAR const struct usb_ctrlreq_s *req)
{
FAR struct stm32_chan_s *chan;
- uint16_t start;
- uint16_t elapsed;
+ uint32_t start;
+ uint32_t elapsed;
int ret;
/* Loop while the device reports NAK (and a timeout is not exceeded */
chan = &priv->chan[priv->ep0out];
- start = stm32_getframe();
+ start = clock_systimer();
do
{
@@ -1258,7 +1265,7 @@ static int stm32_ctrl_sendsetup(FAR struct stm32_usbhost_s *priv,
/* Get the elapsed time (in frames) */
- elapsed = stm32_getframe() - start;
+ elapsed = clock_systimer() - start;
}
while (elapsed < STM32_SETUP_DELAY);
@@ -1367,8 +1374,8 @@ static int stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx,
FAR uint8_t *buffer, size_t buflen)
{
FAR struct stm32_chan_s *chan;
- uint16_t start;
- uint16_t elapsed;
+ uint32_t start;
+ uint32_t elapsed;
int ret = OK;
/* Loop until the transfer completes (i.e., buflen is decremented to zero)
@@ -1379,7 +1386,7 @@ static int stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx,
chan->buffer = buffer;
chan->buflen = buflen;
- start = stm32_getframe();
+ start = clock_systimer();
while (chan->buflen > 0)
{
/* Set up for the wait BEFORE starting the transfer */
@@ -1447,7 +1454,7 @@ static int stm32_in_transfer(FAR struct stm32_usbhost_s *priv, int chidx,
* buffer pointer and buffer size will be unaltered.
*/
- elapsed = stm32_getframe() - start;
+ elapsed = clock_systimer() - start;
if (ret != -EAGAIN || /* Not a NAK condition OR */
elapsed >= STM32_DATANAK_DELAY || /* Timeout has elapsed OR */
chan->buflen != buflen) /* Data has been partially transferred */
@@ -1474,8 +1481,8 @@ static int stm32_out_transfer(FAR struct stm32_usbhost_s *priv, int chidx,
FAR uint8_t *buffer, size_t buflen)
{
FAR struct stm32_chan_s *chan;
- uint16_t start;
- uint16_t elapsed;
+ uint32_t start;
+ uint32_t elapsed;
size_t xfrlen;
int ret = OK;
@@ -1484,7 +1491,7 @@ static int stm32_out_transfer(FAR struct stm32_usbhost_s *priv, int chidx,
*/
chan = &priv->chan[chidx];
- start = stm32_getframe();
+ start = clock_systimer();
while (buflen > 0)
{
@@ -1569,7 +1576,7 @@ static int stm32_out_transfer(FAR struct stm32_usbhost_s *priv, int chidx,
* buffer pointer and buffer size will be unaltered.
*/
- elapsed = stm32_getframe() - start;
+ elapsed = clock_systimer() - start;
if (ret != -EAGAIN || /* Not a NAK condition OR */
elapsed >= STM32_DATANAK_DELAY || /* Timeout has elapsed OR */
chan->buflen != xfrlen) /* Data has been partially transferred */
@@ -3540,8 +3547,8 @@ static int stm32_ctrlin(FAR struct usbhost_driver_s *drvr,
{
struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
uint16_t buflen;
- uint16_t start;
- uint16_t elapsed;
+ uint32_t start;
+ uint32_t elapsed;
int retries;
int ret;
@@ -3573,7 +3580,7 @@ static int stm32_ctrlin(FAR struct usbhost_driver_s *drvr,
/* Get the start time. Loop again until the timeout expires */
- start = stm32_getframe();
+ start = clock_systimer();
do
{
/* Handle the IN data phase (if any) */
@@ -3606,7 +3613,7 @@ static int stm32_ctrlin(FAR struct usbhost_driver_s *drvr,
/* Get the elapsed time (in frames) */
- elapsed = stm32_getframe() - start;
+ elapsed = clock_systimer() - start;
}
while (elapsed < STM32_DATANAK_DELAY);
}
@@ -3623,8 +3630,8 @@ static int stm32_ctrlout(FAR struct usbhost_driver_s *drvr,
{
struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
uint16_t buflen;
- uint16_t start;
- uint16_t elapsed;
+ uint32_t start;
+ uint32_t elapsed;
int retries;
int ret;
@@ -3658,7 +3665,7 @@ static int stm32_ctrlout(FAR struct usbhost_driver_s *drvr,
/* Get the start time. Loop again until the timeout expires */
- start = stm32_getframe();
+ start = clock_systimer();
do
{
/* Handle the data OUT phase (if any) */
@@ -3693,7 +3700,7 @@ static int stm32_ctrlout(FAR struct usbhost_driver_s *drvr,
/* Get the elapsed time (in frames) */
- elapsed = stm32_getframe() - start;
+ elapsed = clock_systimer() - start;
}
while (elapsed < STM32_DATANAK_DELAY);
}
diff --git a/nuttx/arch/arm/src/stm32/stm32_qencoder.c b/nuttx/arch/arm/src/stm32/stm32_qencoder.c
index 8553296f9..d37614c03 100644
--- a/nuttx/arch/arm/src/stm32/stm32_qencoder.c
+++ b/nuttx/arch/arm/src/stm32/stm32_qencoder.c
@@ -607,6 +607,7 @@ static FAR struct stm32_lowerhalf_s *stm32_tim2lower(int tim)
#endif
#ifdef CONFIG_STM32_TIM3_QE
case 3:
+ return &g_tim3lower;
#endif
#ifdef CONFIG_STM32_TIM4_QE
case 4:
diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c
index 0868c3cd3..aa46a8987 100644
--- a/nuttx/arch/arm/src/stm32/stm32_serial.c
+++ b/nuttx/arch/arm/src/stm32/stm32_serial.c
@@ -96,6 +96,19 @@
# endif
# endif
+/* Currently RS-485 support cannot be enabled when RXDMA is in use due to lack
+ * of testing - RS-485 support was developed on STM32F1x
+ */
+
+# if (defined(CONFIG_USART1_RXDMA) && defined(CONFIG_USART1_RS485)) || \
+ (defined(CONFIG_USART2_RXDMA) && defined(CONFIG_USART2_RS485)) || \
+ (defined(CONFIG_USART3_RXDMA) && defined(CONFIG_USART3_RS485)) || \
+ (defined(CONFIG_UART4_RXDMA) && defined(CONFIG_UART4_RS485)) || \
+ (defined(CONFIG_UART5_RXDMA) && defined(CONFIG_UART5_RS485)) || \
+ (defined(CONFIG_USART6_RXDMA) && defined(CONFIG_USART6_RS485))
+# error "RXDMA and RS-485 cannot be enabled at the same time for the same U[S]ART"
+# endif
+
/* For the F4, there are alternate DMA channels for USART1 and 6.
* Logic in the board.h file make the DMA channel selection by defining
* the following in the board.h file.
@@ -219,6 +232,11 @@ struct up_dev_s
uint32_t rxdmanext; /* Next byte in the DMA buffer to be read */
char *const rxfifo; /* Receive DMA buffer */
#endif
+
+#ifdef HAVE_RS485
+ const uint32_t rs485_dir_gpio; /* U[S]ART RS-485 DIR GPIO pin configuration */
+ const bool rs485_dir_polarity; /* U[S]ART RS-485 DIR pin state for TX enabled */
+#endif
};
/****************************************************************************
@@ -415,6 +433,15 @@ static struct up_dev_s g_usart1priv =
.rxfifo = g_usart1rxfifo,
#endif
.vector = up_interrupt_usart1,
+
+#ifdef CONFIG_USART1_RS485
+ .rs485_dir_gpio = GPIO_USART1_RS485_DIR,
+# if (CONFIG_USART1_RS485_DIR_POLARITY == 0)
+ .rs485_dir_polarity = false,
+# else
+ .rs485_dir_polarity = true,
+# endif
+#endif
};
#endif
@@ -468,6 +495,15 @@ static struct up_dev_s g_usart2priv =
.rxfifo = g_usart2rxfifo,
#endif
.vector = up_interrupt_usart2,
+
+#ifdef CONFIG_USART2_RS485
+ .rs485_dir_gpio = GPIO_USART2_RS485_DIR,
+# if (CONFIG_USART2_RS485_DIR_POLARITY == 0)
+ .rs485_dir_polarity = false,
+# else
+ .rs485_dir_polarity = true,
+# endif
+#endif
};
#endif
@@ -521,6 +557,15 @@ static struct up_dev_s g_usart3priv =
.rxfifo = g_usart3rxfifo,
#endif
.vector = up_interrupt_usart3,
+
+#ifdef CONFIG_USART3_RS485
+ .rs485_dir_gpio = GPIO_USART3_RS485_DIR,
+# if (CONFIG_USART3_RS485_DIR_POLARITY == 0)
+ .rs485_dir_polarity = false,
+# else
+ .rs485_dir_polarity = true,
+# endif
+#endif
};
#endif
@@ -570,6 +615,15 @@ static struct up_dev_s g_uart4priv =
.rxfifo = g_uart4rxfifo,
#endif
.vector = up_interrupt_uart4,
+
+#ifdef CONFIG_UART4_RS485
+ .rs485_dir_gpio = GPIO_UART4_RS485_DIR,
+# if (CONFIG_UART4_RS485_DIR_POLARITY == 0)
+ .rs485_dir_polarity = false,
+# else
+ .rs485_dir_polarity = true,
+# endif
+#endif
};
#endif
@@ -619,6 +673,15 @@ static struct up_dev_s g_uart5priv =
.rxfifo = g_uart5rxfifo,
#endif
.vector = up_interrupt_uart5,
+
+#ifdef CONFIG_UART5_RS485
+ .rs485_dir_gpio = GPIO_UART5_RS485_DIR,
+# if (CONFIG_UART5_RS485_DIR_POLARITY == 0)
+ .rs485_dir_polarity = false,
+# else
+ .rs485_dir_polarity = true,
+# endif
+#endif
};
#endif
@@ -672,6 +735,15 @@ static struct up_dev_s g_usart6priv =
.rxfifo = g_usart6rxfifo,
#endif
.vector = up_interrupt_usart6,
+
+#ifdef CONFIG_USART6_RS485
+ .rs485_dir_gpio = GPIO_USART6_RS485_DIR,
+# if (CONFIG_USART6_RS485_DIR_POLARITY == 0)
+ .rs485_dir_polarity = false,
+# else
+ .rs485_dir_polarity = true,
+# endif
+#endif
};
#endif
@@ -744,8 +816,8 @@ static void up_restoreusartint(struct up_dev_s *priv, uint16_t ie)
/* And restore the interrupt state (see the interrupt enable/usage table above) */
cr = up_serialin(priv, STM32_USART_CR1_OFFSET);
- cr &= ~(USART_CR1_RXNEIE|USART_CR1_TXEIE|USART_CR1_PEIE);
- cr |= (ie & (USART_CR1_RXNEIE|USART_CR1_TXEIE|USART_CR1_PEIE));
+ cr &= ~(USART_CR1_USED_INTS);
+ cr |= (ie & (USART_CR1_USED_INTS));
up_serialout(priv, STM32_USART_CR1_OFFSET, cr);
cr = up_serialin(priv, STM32_USART_CR3_OFFSET);
@@ -772,7 +844,7 @@ static inline void up_disableusartint(struct up_dev_s *priv, uint16_t *ie)
* USART_CR1_IDLEIE 4 USART_SR_IDLE Idle Line Detected (not used)
* USART_CR1_RXNEIE 5 USART_SR_RXNE Received Data Ready to be Read
* " " USART_SR_ORE Overrun Error Detected
- * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (not used)
+ * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (used only for RS-485)
* USART_CR1_TXEIE 7 USART_SR_TXE Transmit Data Register Empty
* USART_CR1_PEIE 8 USART_SR_PE Parity Error
*
@@ -791,7 +863,7 @@ static inline void up_disableusartint(struct up_dev_s *priv, uint16_t *ie)
* overlap. This logic would fail if we needed the break interrupt!
*/
- *ie = (cr1 & (USART_CR1_RXNEIE|USART_CR1_TXEIE|USART_CR1_PEIE)) | (cr3 & USART_CR3_EIE);
+ *ie = (cr1 & (USART_CR1_USED_INTS)) | (cr3 & USART_CR3_EIE);
}
/* Disable all interrupts */
@@ -853,18 +925,18 @@ static void up_set_format(struct uart_dev_s *dev)
* usartdiv32 = 32 * usartdiv = fCK / (baud/2)
*/
- usartdiv32 = priv->apbclock / (priv->baud >> 1);
+ usartdiv32 = priv->apbclock / (priv->baud >> 1);
- /* The mantissa part is then */
+ /* The mantissa part is then */
- mantissa = usartdiv32 >> 5;
- brr = mantissa << USART_BRR_MANT_SHIFT;
+ mantissa = usartdiv32 >> 5;
+ brr = mantissa << USART_BRR_MANT_SHIFT;
- /* The fractional remainder (with rounding) */
+ /* The fractional remainder (with rounding) */
- fraction = (usartdiv32 - (mantissa << 5) + 1) >> 1;
- brr |= fraction << USART_BRR_FRAC_SHIFT;
- up_serialout(priv, STM32_USART_BRR_OFFSET, brr);
+ fraction = (usartdiv32 - (mantissa << 5) + 1) >> 1;
+ brr |= fraction << USART_BRR_FRAC_SHIFT;
+ up_serialout(priv, STM32_USART_BRR_OFFSET, brr);
/* Configure parity mode */
@@ -946,6 +1018,14 @@ static int up_setup(struct uart_dev_s *dev)
stm32_configgpio(priv->rts_gpio);
}
+#if HAVE_RS485
+ if (priv->rs485_dir_gpio != 0)
+ {
+ stm32_configgpio(priv->rs485_dir_gpio);
+ stm32_gpiowrite(priv->rs485_dir_gpio, !priv->rs485_dir_polarity);
+ }
+#endif
+
/* Configure CR2 */
/* Clear CLKEN, CPOL, CPHA, LBCL, and interrupt enable bits */
@@ -990,13 +1070,11 @@ static int up_setup(struct uart_dev_s *dev)
regval = up_serialin(priv, STM32_USART_CR1_OFFSET);
regval |= (USART_CR1_UE|USART_CR1_TE|USART_CR1_RE);
up_serialout(priv, STM32_USART_CR1_OFFSET, regval);
-
-#endif /* CONFIG_SUPPRESS_UART_CONFIG */
+#endif
/* Set up the cached interrupt enables value */
- up_restoreusartint(priv, 0);
-
+ priv->ie = 0;
return OK;
}
@@ -1217,7 +1295,7 @@ static int up_interrupt_common(struct up_dev_s *priv)
* USART_CR1_IDLEIE 4 USART_SR_IDLE Idle Line Detected (not used)
* USART_CR1_RXNEIE 5 USART_SR_RXNE Received Data Ready to be Read
* " " USART_SR_ORE Overrun Error Detected
- * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (not used)
+ * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (used only for RS-485)
* USART_CR1_TXEIE 7 USART_SR_TXE Transmit Data Register Empty
* USART_CR1_PEIE 8 USART_SR_PE Parity Error
*
@@ -1232,6 +1310,21 @@ static int up_interrupt_common(struct up_dev_s *priv)
* being used.
*/
+#ifdef HAVE_RS485
+ /* Transmission of whole buffer is over - TC is set, TXEIE is cleared.
+ * Note - this should be first, to have the most recent TC bit value from
+ * SR register - sending data affects TC, but without refresh we will not
+ * know that...
+ */
+
+ if ((priv->sr & USART_SR_TC) != 0 && (priv->ie & USART_CR1_TCIE) != 0 &&
+ (priv->ie & USART_CR1_TXEIE) == 0)
+ {
+ stm32_gpiowrite(priv->rs485_dir_gpio, !priv->rs485_dir_polarity);
+ up_restoreusartint(priv, priv->ie & ~USART_CR1_TCIE);
+ }
+#endif
+
/* Handle incoming, receive bytes. */
if ((priv->sr & USART_SR_RXNE) != 0 && (priv->ie & USART_CR1_RXNEIE) != 0)
@@ -1265,13 +1358,14 @@ static int up_interrupt_common(struct up_dev_s *priv)
if ((priv->sr & USART_SR_TXE) != 0 && (priv->ie & USART_CR1_TXEIE) != 0)
{
- /* Transmit data regiser empty ... process outgoing bytes */
+ /* Transmit data register empty ... process outgoing bytes */
uart_xmitchars(&priv->dev);
handled = true;
}
}
- return OK;
+
+ return OK;
}
/****************************************************************************
@@ -1611,6 +1705,10 @@ static bool up_dma_rxavailable(struct uart_dev_s *dev)
static void up_send(struct uart_dev_s *dev, int ch)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+#ifdef HAVE_RS485
+ if (priv->rs485_dir_gpio != 0)
+ stm32_gpiowrite(priv->rs485_dir_gpio, priv->rs485_dir_polarity);
+#endif
up_serialout(priv, STM32_USART_DR_OFFSET, (uint32_t)ch);
}
@@ -1631,7 +1729,7 @@ static void up_txint(struct uart_dev_s *dev, bool enable)
*
* Enable Bit Status Meaning Usage
* ------------------ --- --------------- ---------------------------- ----------
- * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (not used)
+ * USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (used only for RS-485)
* USART_CR1_TXEIE 7 USART_SR_TXE Transmit Data Register Empty
* USART_CR3_CTSIE 10 USART_SR_CTS CTS flag (not used)
*/
@@ -1642,7 +1740,20 @@ static void up_txint(struct uart_dev_s *dev, bool enable)
/* Set to receive an interrupt when the TX data register is empty */
#ifndef CONFIG_SUPPRESS_SERIAL_INTS
- up_restoreusartint(priv, priv->ie | USART_CR1_TXEIE);
+ uint16_t ie = priv->ie | USART_CR1_TXEIE;
+
+ /* If RS-485 is supported on this U[S]ART, then also enable the
+ * transmission complete interrupt.
+ */
+
+# ifdef HAVE_RS485
+ if (priv->rs485_dir_gpio != 0)
+ {
+ ie |= USART_CR1_TCIE;
+ }
+# endif
+
+ up_restoreusartint(priv, ie);
/* Fake a TX interrupt here by just calling uart_xmitchars() with
* interrupts disabled (note this may recurse).
@@ -1657,6 +1768,7 @@ static void up_txint(struct uart_dev_s *dev, bool enable)
up_restoreusartint(priv, priv->ie & ~USART_CR1_TXEIE);
}
+
irqrestore(flags);
}
diff --git a/nuttx/arch/arm/src/stm32/stm32_uart.h b/nuttx/arch/arm/src/stm32/stm32_uart.h
index a70923cbf..8ff6a9975 100644
--- a/nuttx/arch/arm/src/stm32/stm32_uart.h
+++ b/nuttx/arch/arm/src/stm32/stm32_uart.h
@@ -223,6 +223,20 @@
# undef SERIAL_HAVE_ONLY_DMA
#endif
+/* Is RS-485 used? */
+
+#if defined(CONFIG_USART1_RS485) || defined(CONFIG_USART2_RS485) || \
+ defined(CONFIG_USART3_RS485) || defined(CONFIG_UART4_RS485) || \
+ defined(CONFIG_UART5_RS485) || defined(CONFIG_USART6_RS485)
+# define HAVE_RS485 1
+#endif
+
+#ifdef HAVE_RS485
+# define USART_CR1_USED_INTS (USART_CR1_RXNEIE | USART_CR1_TXEIE | USART_CR1_PEIE | USART_CR1_TCIE)
+#else
+# define USART_CR1_USED_INTS (USART_CR1_RXNEIE | USART_CR1_TXEIE | USART_CR1_PEIE)
+#endif
+
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c
index 47ed5e016..ae3fa516e 100644
--- a/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32f10xxx_rcc.c
@@ -92,7 +92,11 @@ static inline void rcc_reset(void)
putreg32(regval, STM32_RCC_CR);
regval = getreg32(STM32_RCC_CFGR); /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE bits */
- regval &= ~(RCC_CFGR_PLLSRC|RCC_CFGR_PLLXTPRE|RCC_CFGR_PLLMUL_MASK|RCC_CFGR_USBPRE);
+ regval &= ~(RCC_CFGR_PLLSRC|RCC_CFGR_PLLXTPRE|RCC_CFGR_PLLMUL_MASK
+#ifndef CONFIG_STM32_VALUELINE
+ |RCC_CFGR_USBPRE
+#endif
+ );
putreg32(regval, STM32_RCC_CFGR);
putreg32(0, STM32_RCC_CIR); /* Disable all interrupts */
@@ -224,6 +228,27 @@ static inline void rcc_enableapb1(void)
#endif
#endif
+#ifdef CONFIG_STM32_TIM12
+ /* Timer 12 clock enable */
+#ifdef CONFIG_STM32_FORCEPOWER
+ regval |= RCC_APB1ENR_TIM12EN;
+#endif
+#endif
+
+#ifdef CONFIG_STM32_TIM13
+ /* Timer 13 clock enable */
+#ifdef CONFIG_STM32_FORCEPOWER
+ regval |= RCC_APB1ENR_TIM13EN;
+#endif
+#endif
+
+#ifdef CONFIG_STM32_TIM14
+ /* Timer 14 clock enable */
+#ifdef CONFIG_STM32_FORCEPOWER
+ regval |= RCC_APB1ENR_TIM14EN;
+#endif
+#endif
+
#ifdef CONFIG_STM32_WWDG
/* Window Watchdog clock enable */
@@ -315,6 +340,13 @@ static inline void rcc_enableapb1(void)
regval |= RCC_APB1ENR_DACEN;
#endif
+
+#ifdef CONFIG_STM32_CEC
+ /* CEC clock enable */
+
+ regval |= RCC_APB1ENR_CECEN;
+#endif
+
putreg32(regval, STM32_RCC_APB1ENR);
}
@@ -404,6 +436,28 @@ static inline void rcc_enableapb2(void)
regval |= RCC_APB2ENR_ADC3EN;
#endif
+
+#ifdef CONFIG_STM32_TIM15
+ /* TIM15 Timer clock enable */
+#ifdef CONFIG_STM32_FORCEPOWER
+ regval |= RCC_APB2ENR_TIM15EN;
+#endif
+#endif
+
+#ifdef CONFIG_STM32_TIM16
+ /* TIM16 Timer clock enable */
+#ifdef CONFIG_STM32_FORCEPOWER
+ regval |= RCC_APB2ENR_TIM16EN;
+#endif
+#endif
+
+#ifdef CONFIG_STM32_TIM17
+ /* TIM17 Timer clock enable */
+#ifdef CONFIG_STM32_FORCEPOWER
+ regval |= RCC_APB2ENR_TIM17EN;
+#endif
+#endif
+
putreg32(regval, STM32_RCC_APB2ENR);
}
diff --git a/nuttx/arch/arm/src/stm32/stm32f20xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f20xxx_rcc.c
index 335992524..ac72fb60b 100644
--- a/nuttx/arch/arm/src/stm32/stm32f20xxx_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32f20xxx_rcc.c
@@ -631,7 +631,11 @@ static void stm32_stdclockconfig(void)
/* Enable FLASH prefetch, instruction cache, data cache, and 5 wait states */
+#ifdef STM32_FLASH_PREFETCH
+ regval = (FLASH_ACR_LATENCY_5 | FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_PRFTEN);
+#else
regval = (FLASH_ACR_LATENCY_5 | FLASH_ACR_ICEN | FLASH_ACR_DCEN);
+#endif
putreg32(regval, STM32_FLASH_ACR);
/* Select the main PLL as system clock source */
diff --git a/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
index 45980f288..c6c0b2382 100644
--- a/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
@@ -633,7 +633,11 @@ static void stm32_stdclockconfig(void)
/* Enable FLASH prefetch, instruction cache, data cache, and 5 wait states */
+#ifdef STM32_FLASH_PREFETCH
+ regval = (FLASH_ACR_LATENCY_5 | FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_PRFTEN);
+#else
regval = (FLASH_ACR_LATENCY_5 | FLASH_ACR_ICEN | FLASH_ACR_DCEN);
+#endif
putreg32(regval, STM32_FLASH_ACR);
/* Select the main PLL as system clock source */