summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-06-07 14:59:33 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-06-07 14:59:33 -0600
commit475ae9953007c007e4f6f8e4f5763d25665e9c38 (patch)
tree1fbd61ead1f3984ae63d6f8a656766f941324fdf
parent7e11572f8aef6160484ac81a9df4edc2c7cdd2b9 (diff)
downloadpx4-nuttx-475ae9953007c007e4f6f8e4f5763d25665e9c38.tar.gz
px4-nuttx-475ae9953007c007e4f6f8e4f5763d25665e9c38.tar.bz2
px4-nuttx-475ae9953007c007e4f6f8e4f5763d25665e9c38.zip
SAM4L: Add logic to enable selected peripherals on power up; Extend configuration so that each peripheral can be selected -- even though the drivers are not yet implemented
-rw-r--r--nuttx/arch/arm/src/sam34/Kconfig202
-rw-r--r--nuttx/arch/arm/src/sam34/chip/sam4l_pm.h2
-rw-r--r--nuttx/arch/arm/src/sam34/sam4l_clockconfig.c59
-rw-r--r--nuttx/arch/arm/src/sam34/sam4l_periphclks.c317
-rw-r--r--nuttx/arch/arm/src/sam34/sam4l_periphclks.h69
-rw-r--r--nuttx/configs/sam4l-xplained/README.txt54
-rw-r--r--nuttx/configs/sam4l-xplained/ostest/defconfig45
7 files changed, 655 insertions, 93 deletions
diff --git a/nuttx/arch/arm/src/sam34/Kconfig b/nuttx/arch/arm/src/sam34/Kconfig
index f46b33403..d2da85624 100644
--- a/nuttx/arch/arm/src/sam34/Kconfig
+++ b/nuttx/arch/arm/src/sam34/Kconfig
@@ -3,10 +3,10 @@
# see misc/tools/kconfig-language.txt.
#
-comment "AT91SAM3/SAM4 Configuration Options"
+comment "AT91SAM3/4 Configuration Options"
choice
- prompt "AT91SAM3 Chip Selection"
+ prompt "AT91SAM3/4 Chip Selection"
default ARCH_CHIP_AT91SAM3U4E
depends on ARCH_CHIP_SAM34
@@ -147,47 +147,223 @@ config SAM_PICOCACHE
depends on ARCH_CHIP_SAM4L
default y
-config SAM34_DMA
- bool "DMA"
+config SAM34_OCD
+ bool "On-chip DEBUG"
+ depends on ARCH_CHIP_SAM4L
+ default y if DEBUG_SYMBOLS
+ default n if !DEBUG_SYMBOLS
+
+config SAM34_APBA
+ bool "APBA bridge"
default n
- select ARCH_DMA
+ depends on ARCH_CHIP_SAM4L
-config SAM34_NAND
- bool "NAND support"
+config SAM34_AESA
+ bool "Advanced Encryption Standard"
default n
+ depends on ARCH_CHIP_SAM4L
-config SAM34_HSMCI
- bool "HSMCI"
+config SAM34_IISC
+ bool "Inter-IC Sound (I2S) Controller"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_SPI
+ bool "SPI"
default n
+config SAM34_TC0
+ bool "Timer/Counter 0"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_TC1
+ bool "Timer/Counter 1"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_TWIM0
+ bool "Two-wire Master Interface 0"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_TWIS0
+ bool "Two-wire Slave Interface 0"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_TWIM1
+ bool "Two-wire Master Interface 1"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_TWIS1
+ bool "Two-wire Slave Interface 1"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_TWIM2
+ bool "Two-wire Master Interface 2"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_TWIM3
+ bool "Two-wire Master Interface 3"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
config SAM34_UART
bool "UART"
default y
+ depends on ARCH_CHIP_SAM3U
+ select ARCH_HAVE_UART
+
+config SAM34_PICOUART
+ bool "PicoUART"
+ default n
+ depends on ARCH_CHIP_SAM4L
select ARCH_HAVE_UART
config SAM34_USART0
bool "USART0"
default n
+ select ARCH_HAVE_USART0
config SAM34_USART1
bool "USART1"
default n
+ select ARCH_HAVE_USART1
config SAM34_USART2
bool "USART2"
default n
+ select ARCH_HAVE_USART2
config SAM34_USART3
bool "USART3"
default n
+ select ARCH_HAVE_USART3
-config SAM34_SPI
- bool "SPI"
+config SAM34_ADCIFE
+ bool "ADC controller interface"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_DACC
+ bool "DAC Controller"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_ACIFC
+ bool "Analog Comparator Interface"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_GLOC
+ bool "GLOC"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_ABDACB
+ bool "Audio Bitstream DAC"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_TRNG
+ bool "True Random Number Generator"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_PARC
+ bool "Parallel Capture"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_CATB
+ bool "Capacitive Touch Module B"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_LCDCA
+ bool " LCD Controller A"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_HRAMC1
+ bool "HRAMC1 (picoCache RAM)"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_NAND
+ bool "NAND support"
+ default n
+ depends on ARCH_CHIP_SAM3U
+
+config SAM34_HMATRIX
+ bool "HMATRIX"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_PDCA
+ bool "Peripheral DMA controller"
+ default n
+ depends on ARCH_CHIP_SAM4L
+ select ARCH_DMA
+
+config SAM34_DMA
+ bool "DMA"
+ default n
+ depends on ARCH_CHIP_SAM3U
+ select ARCH_DMA
+
+config SAM34_CRCCU
+ bool "CRC Calculation Unit"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_USBC
+ bool "USB 2.0 Interface"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_PEVC
+ bool "Peripheral Event Controller"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_CHIPID
+ bool "Chip ID"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_FREQM
+ bool "Frequency Mete"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_AST
+ bool "Asynchronous Timer"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_WDT
+ bool "Watchdog Timer"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_EIC
+ bool "External Interrupt Controller"
+ default n
+ depends on ARCH_CHIP_SAM4L
+
+config SAM34_HSMCI
+ bool "HSMCI"
default n
+ depends on ARCH_CHIP_SAM3U
endmenu
-menu "AT91SAM3 UART Configuration"
+menu "AT91SAM3/4 USART Configuration"
config USART0_ISUART
bool "USART0 is a UART"
@@ -215,7 +391,7 @@ config USART3_ISUART
endmenu
-menu "AT91SAM3 GPIO Interrupt Configuration"
+menu "AT91SAM3/4 GPIO Interrupt Configuration"
config GPIOA_IRQ
bool "GPIOA interrupts"
diff --git a/nuttx/arch/arm/src/sam34/chip/sam4l_pm.h b/nuttx/arch/arm/src/sam34/chip/sam4l_pm.h
index ba78b3a95..86a55af8d 100644
--- a/nuttx/arch/arm/src/sam34/chip/sam4l_pm.h
+++ b/nuttx/arch/arm/src/sam34/chip/sam4l_pm.h
@@ -145,7 +145,7 @@
/* CPU Mask Register Bit-field Definitions */
-#define PM_CPUMASK_OCD (1 << 0) /* Bit 0: OCD */
+#define PM_CPUMASK_OCD (1 << 0) /* Bit 0: On-Chip Debug */
/* HSB Mask Register Bit-field Definitions */
diff --git a/nuttx/arch/arm/src/sam34/sam4l_clockconfig.c b/nuttx/arch/arm/src/sam34/sam4l_clockconfig.c
index d69dc7e8a..f49eecf79 100644
--- a/nuttx/arch/arm/src/sam34/sam4l_clockconfig.c
+++ b/nuttx/arch/arm/src/sam34/sam4l_clockconfig.c
@@ -53,6 +53,7 @@
#include "chip/sam4l_bscif.h"
#include "chip/sam4l_flashcalw.h"
+#include "sam_periphclks.h"
#include "sam_clockconfig.h"
/****************************************************************************
@@ -80,11 +81,11 @@
* either PLL0 or DFPLL. It might also be needed if OSC0 is the source
* clock for GCLK9.
*
- * By selecting CONFIG_SAM_OSC0, you can also force the clock to be enabled
+ * By selecting CONFIG_SAM34_OSC0, you can also force the clock to be enabled
* at boot time.
*/
-#if defined(CONFIG_SAM_OSC0) || defined(BOARD_SYSCLK_SOURCE_OSC0) || \
+#if defined(CONFIG_SAM34_OSC0) || defined(BOARD_SYSCLK_SOURCE_OSC0) || \
defined(BOARD_DFLL0_SOURCE_OSC0) || defined(BOARD_PLL0_SOURCE_OSC0) || \
defined(BOARD_GLCK9_SOURCE_OSC0)
# define NEED_OSC0 1
@@ -143,12 +144,12 @@
/* OSC32. The 32K oscillator may be the source clock for DFPLL0 or
* the source clock for GLK9 that might be used to driver PLL0.
*
- * By selecting CONFIG_SAM_OSC32K, you can also force the clock to be
+ * By selecting CONFIG_SAM34_OSC32K, you can also force the clock to be
* enabled at boot time. OSC32 may needed by other devices as well
* (AST, WDT, PICUART, RTC).
*/
-#if defined(CONFIG_SAM_OSC32K) || defined(BOARD_DFLL0_SOURCE_OSC32K) || \
+#if defined(CONFIG_SAM34_OSC32K) || defined(BOARD_DFLL0_SOURCE_OSC32K) || \
defined(BOARD_GLCK9_SOURCE_OSC32K)
# define NEED_OSC32K 1
#endif
@@ -190,58 +191,58 @@
/* RC80M. This might be the system clock or the source clock for the DFPLL
* or it could be the source for GCLK9 that drives PLL0.
*
- * By selecting CONFIG_SAM_RC80M, you can also force the clock to be enabled
+ * By selecting CONFIG_SAM34_RC80M, you can also force the clock to be enabled
* at boot time.
*/
-#if defined(CONFIG_SAM_RC80M) || defined(BOARD_SYSCLK_SOURCE_RC80M) || \
+#if defined(CONFIG_SAM34_RC80M) || defined(BOARD_SYSCLK_SOURCE_RC80M) || \
defined(BOARD_DFLL0_SOURCE_RC80M) || BOARD_GLCK9_SOURCE_RC80M
# define NEED_RC80M 1
#endif
/* RCFAST. The 12/8/4 fast RC oscillator may be used as the system clock
* or as the source for GLCK9 that drives PLL0.
- * If not then, it may be enabled by setting the CONFIG_SAM_RCFASTxM
+ * If not then, it may be enabled by setting the CONFIG_SAM34_RCFASTxM
* configuration variable.
*/
-#if defined(CONFIG_SAM_RCFAST12M)
-# undef CONFIG_SAM_RCFAST8M
-# undef CONFIG_SAM_RCFAST4M
-#elif defined(CONFIG_SAM_RCFAST8M)
-# undef CONFIG_SAM_RCFAST4M
+#if defined(CONFIG_SAM34_RCFAST12M)
+# undef CONFIG_SAM34_RCFAST8M
+# undef CONFIG_SAM34_RCFAST4M
+#elif defined(CONFIG_SAM34_RCFAST8M)
+# undef CONFIG_SAM34_RCFAST4M
#endif
#if defined(BOARD_SYSCLK_SOURCE_FCFAST12M)
-# if defined(CONFIG_SAM_RCFAST8M) || defined(CONFIG_SAM_RCFAST4M)
-# error BOARD_SYSCLK_SOURCE_FCFAST12M inconsistent with CONFIG_SAM_RCFAST8/4M
+# if defined(CONFIG_SAM34_RCFAST8M) || defined(CONFIG_SAM34_RCFAST4M)
+# error BOARD_SYSCLK_SOURCE_FCFAST12M inconsistent with CONFIG_SAM34_RCFAST8/4M
# endif
# define NEED_RCFAST 1
# define SAM_RCFAST_RANGE SCIF_RCFASTCFG_FRANGE_12MHZ
# define SAM_RCFAST_FREQUENCY SAM_RCFAST12M_FREQUENCY
#elif defined(BOARD_SYSCLK_SOURCE_FCFAST8M)
-# if defined(CONFIG_SAM_RCFAST12M) || defined(CONFIG_SAM_RCFAST4M)
-# error BOARD_SYSCLK_SOURCE_FCFAST8M inconsistent with CONFIG_SAM_RCFAST12/4M
+# if defined(CONFIG_SAM34_RCFAST12M) || defined(CONFIG_SAM34_RCFAST4M)
+# error BOARD_SYSCLK_SOURCE_FCFAST8M inconsistent with CONFIG_SAM34_RCFAST12/4M
# endif
# define NEED_RCFAST 1
# define SAM_RCFAST_RANGE SCIF_RCFASTCFG_FRANGE_8MHZ
# define SAM_RCFAST_FREQUENCY SAM_RCFAST8M_FREQUENCY
#elif defined(BOARD_SYSCLK_SOURCE_FCFAST4M)
-# if defined(CONFIG_SAM_RCFAST12M) || defined(CONFIG_SAM_RCFAST8M)
-# error BOARD_SYSCLK_SOURCE_FCFAST4M inconsistent with CONFIG_SAM_RCFAST12/8M
+# if defined(CONFIG_SAM34_RCFAST12M) || defined(CONFIG_SAM34_RCFAST8M)
+# error BOARD_SYSCLK_SOURCE_FCFAST4M inconsistent with CONFIG_SAM34_RCFAST12/8M
# endif
# define NEED_RCFAST 1
# define SAM_RCFAST_RANGE SCIF_RCFASTCFG_FRANGE_4MHZ
# define SAM_RCFAST_FREQUENCY SAM_RCFAST4M_FREQUENCY
-#elif defined(CONFIG_SAM_RCFAST12M)
+#elif defined(CONFIG_SAM34_RCFAST12M)
# define NEED_RCFAST 1
# define SAM_RCFAST_RANGE SCIF_RCFASTCFG_FRANGE_12MHZ
# define SAM_RCFAST_FREQUENCY SAM_RCFAST12M_FREQUENCY
-#elif defined(CONFIG_SAM_RCFAST8M)
+#elif defined(CONFIG_SAM34_RCFAST8M)
# define NEED_RCFAST 1
# define SAM_RCFAST_RANGE SCIF_RCFASTCFG_FRANGE_8MHZ
# define SAM_RCFAST_FREQUENCY SAM_RCFAST8M_FREQUENCY
-#elif defined(CONFIG_SAM_RCFAST4M)
+#elif defined(CONFIG_SAM34_RCFAST4M)
# define NEED_RCFAST 1
# define SAM_RCFAST_RANGE SCIF_RCFASTCFG_FRANGE_4MHZ
# define SAM_RCFAST_FREQUENCY SAM_RCFAST4M_FREQUENCY
@@ -250,11 +251,11 @@
/* RC1M. The 1M RC oscillator may be used as the system block or
* may be the source clock for GLCK9 that drives PLL0
*
- * By selecting CONFIG_SAM_RC1M, you can also force the clock to be
+ * By selecting CONFIG_SAM34_RC1M, you can also force the clock to be
* enabled at boot time.
*/
-#if defined(CONFIG_SAM_RC1M) || defined(BOARD_SYSCLK_SOURCE_RC1M) || \
+#if defined(CONFIG_SAM34_RC1M) || defined(BOARD_SYSCLK_SOURCE_RC1M) || \
defined(BOARD_GLCK9_SOURCE_RC1M)
# define NEED_RC1M 1
#endif
@@ -262,11 +263,11 @@
/* RC32K. The 32KHz RC oscillator may be used as the input to DFLL0
* or as the input to GCLK9 that drives PLL0.
*
- * By selecting CONFIG_SAM_RC32K, you can also force the clock to be
+ * By selecting CONFIG_SAM34_RC32K, you can also force the clock to be
* enabled at boot time.
*/
-#if defined(CONFIG_SAM_RC32K) || defined(BOARD_DFLL0_SOURCE_RC32K) || \
+#if defined(CONFIG_SAM34_RC32K) || defined(BOARD_DFLL0_SOURCE_RC32K) || \
defined(BOARD_GLCK9_SOURCE_RC32K)
# define NEED_RC32K 1
#endif
@@ -448,7 +449,7 @@
*
****************************************************************************/
-#ifdef CONFIG_SAM_PICOCACHE
+#ifdef CONFIG_SAM34_PICOCACHE
static inline void sam_picocache(void)
{
/* Enable clocking to the PICOCACHE */
@@ -1068,7 +1069,7 @@ void sam_clockconfig(void)
* ------- ---- ----- -------- ---------- ----------
*/
-#ifdef CONFIG_SAM_FLASH_HSEN
+#ifdef CONFIG_SAM34_FLASH_HSEN
/* The high speed FLASH mode has been enabled. Select power scaling
* mode 2, no fast wakeup.
*/
@@ -1238,6 +1239,10 @@ void sam_clockconfig(void)
sam_setpsm(psm);
+ /* Enable all selected peripheral cloks */
+
+ sam_init_periphclks();
+
#ifdef CONFIG_USBDEV
void sam_usbclock();
#endif
diff --git a/nuttx/arch/arm/src/sam34/sam4l_periphclks.c b/nuttx/arch/arm/src/sam34/sam4l_periphclks.c
index abd766695..ea11d2b0c 100644
--- a/nuttx/arch/arm/src/sam34/sam4l_periphclks.c
+++ b/nuttx/arch/arm/src/sam34/sam4l_periphclks.c
@@ -52,7 +52,7 @@
#include "sam4l_periphclks.h"
/****************************************************************************
- * Private Definitions
+ * Pre-processor Definitions
****************************************************************************/
/****************************************************************************
@@ -76,10 +76,316 @@
****************************************************************************/
/****************************************************************************
+ * Name: sam_init_cpumask
+ *
+ * Description:
+ * Called during boot to enable clocking on selected peripherals in the
+ * CPU mask register.
+ *
+ ****************************************************************************/
+
+static inline void sam_init_cpumask(void)
+{
+ uint32_t mask = 0;
+
+ /* OR in the user selected peripherals */
+
+#ifdef CONFIG_SAM34_OCD
+ mask |= PM_CPUMASK_OCD; /* On-Chip Debug */
+#endif
+
+ /* Save the new CPU mask */
+
+ putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(SAM_PM_CPUMASK_OFFSET),
+ SAM_PM_UNLOCK);
+ putreg32(mask, SAM_PM_CPUMASK);
+}
+
+/****************************************************************************
+ * Name: sam_init_hsbmask
+ *
+ * Description:
+ * Called during boot to enable clocking on selected peripherals in the
+ * HSB mask register.
+ *
+ ****************************************************************************/
+
+static inline void sam_init_hsbmask(void)
+{
+ /* Select the non-optional peripherals */
+
+ uint32_t mask = (PM_HSBMASK_FLASHCALW | PM_HSBMASK_APBB |
+ PM_HSBMASK_APBC | PM_HSBMASK_APBD)
+
+ /* OR in the user selected peripherals */
+
+#ifdef CONFIG_SAM34_PDCA
+ mask |= PM_HSBMASK_PDCA; /* PDCA */
+#endif
+#ifdef CONFIG_SAM34_HRAMC1
+ mask |= PM_HSBMASK_HRAMC1; /* HRAMC1 (picoCache RAM) */
+#endif
+#ifdef CONFIG_SAM34_USBC
+ mask |= PM_HSBMASK_USBC; /* USBC */
+#endif
+#ifdef CONFIG_SAM34_CRCCU
+ mask |= PM_HSBMASK_CRCCU; /* CRCCU */
+#endif
+#ifdef CONFIG_SAM34_APBA
+ mask |= PM_HSBMASK_APBA; /* APBA bridge */
+#endif
+#ifdef CONFIG_SAM34_AESA
+ mask |= PM_HSBMASK_AESA; /* AESA */
+#endif
+
+ /* Save the new HSB mask */
+
+ putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(SAM_PM_HSBMASK_OFFSET),
+ SAM_PM_UNLOCK);
+ putreg32(mask, SAM_PM_HSBMASK);
+}
+
+/****************************************************************************
+ * Name: sam_init_pbamask
+ *
+ * Description:
+ * Called during boot to enable clocking on selected peripherals in the
+ * PBA mask register.
+ *
+ ****************************************************************************/
+
+static inline void sam_init_pbamask(void)
+{
+ /* Select the non-optional peripherals */
+
+ uint32_t mask = 0;
+ uint32_t divmask = 0;
+
+ /* OR in the user selected peripherals */
+
+#ifdef CONFIG_SAM34_IISC
+ mask |= PM_PBAMASK_IISC; /* IISC */
+#endif
+#ifdef CONFIG_SAM34_SPI
+ mask |= PM_PBAMASK_SPI; /* SPI */
+#endif
+#ifdef CONFIG_SAM34_TC0
+ mask |= PM_PBAMASK_TC0; /* TC0 */
+ divmask |= PM_PBADIVMASK_TIMER_CLOCKS;
+#endif
+#ifdef CONFIG_SAM34_TC1
+ mask |= PM_PBAMASK_TC1; /* TC1 */
+ divmask |= PM_PBADIVMASK_TIMER_CLOCKS;
+#endif
+#ifdef CONFIG_SAM34_TWIM0
+ mask |= PM_PBAMASK_TWIM0; /* TWIM0 */
+#endif
+#ifdef CONFIG_SAM34_TWIS0
+ mask |= PM_PBAMASK_TWIS0; /* TWIS0 */
+#endif
+#ifdef CONFIG_SAM34_TWIM1
+ mask |= PM_PBAMASK_TWIM1; /* TWIM1 */
+#endif
+#ifdef CONFIG_SAM34_TWIS1
+ mask |= PM_PBAMASK_TWIS1; /* TWIS1 */
+#endif
+#ifdef CONFIG_SAM34_USART0
+ mask |= PM_PBAMASK_USART0; /* USART0 */
+ divmask |= PBA_DIVMASK_CLK_USART;
+#endif
+#ifdef CONFIG_SAM34_USART1
+ mask |= PM_PBAMASK_USART1; /* USART1 */
+ divmask |= PBA_DIVMASK_CLK_USART;
+#endif
+#ifdef CONFIG_SAM34_USART2
+ mask |= PM_PBAMASK_USART2; /* USART2 */
+ divmask |= PBA_DIVMASK_CLK_USART;
+#endif
+#ifdef CONFIG_SAM34_USART3
+ mask |= PM_PBAMASK_USART3; /* USART3 */
+ divmask |= PBA_DIVMASK_CLK_USART;
+#endif
+#ifdef CONFIG_SAM34_ADCIFE
+ mask |= PM_PBAMASK_ADCIFE; /* ADCIFE */
+#endif
+#ifdef CONFIG_SAM34_DACC
+ mask |= PM_PBAMASK_DACC; /* DACC */
+#endif
+#ifdef CONFIG_SAM34_ACIFC
+ mask |= PM_PBAMASK_ACIFC; /* ACIFC */
+#endif
+#ifdef CONFIG_SAM34_GLOC
+ mask |= PM_PBAMASK_GLOC; /* GLOC */
+#endif
+#ifdef CONFIG_SAM34_ABDACB
+ mask |= PM_PBAMASK_ABDACB; /* ABDACB */
+#endif
+#ifdef CONFIG_SAM34_TRNG
+ mask |= PM_PBAMASK_TRNG; /* TRNG */
+#endif
+#ifdef CONFIG_SAM34_PARC
+ mask |= PM_PBAMASK_PARC; /* PARC */
+#endif
+#ifdef CONFIG_SAM34_CATB
+ mask |= PM_PBAMASK_CATB; /* CATB */
+#endif
+#ifdef CONFIG_SAM34_TWIM2
+ mask |= PM_PBAMASK_TWIM2; /* TWIM2 */
+#endif
+#ifdef CONFIG_SAM34_TWIM3
+ mask |= PM_PBAMASK_TWIM3; /* TWIM3 */
+#endif
+#ifdef CONFIG_SAM34_LCDCA
+ mask |= PM_PBAMASK_LCDCA; /* LCDCA*/
+#endif
+
+ /* Save the new PBA mask */
+
+ putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(SAM_PM_PBAMASK_OFFSET),
+ SAM_PM_UNLOCK);
+ putreg32(mask, SAM_PM_PBAMASK);
+
+ /* Set the peripheral divider mask as necessary */
+
+ putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(SAM_PM_PBADIVMASK_OFFSET),
+ SAM_PM_UNLOCK);
+ putreg32(divmask, SAM_PM_PBADIVMASK);
+}
+
+/****************************************************************************
+ * Name: sam_init_pbbmask
+ *
+ * Description:
+ * Called during boot to enable clocking on selected peripherals in the
+ * PBB mask register.
+ *
+ ****************************************************************************/
+
+static inline void sam_init_pbbmask(void)
+{
+ /* Select the non-optional peripherals */
+
+ uint32_t mask = PM_PBBMASK_FLASHCALW;
+
+ /* OR in the user selected peripherals */
+
+#ifdef CONFIG_SAM34_HRAMC1
+ mask |= PM_PBBMASK_HRAMC1; /* HRAMC1 */
+#endif
+#ifdef CONFIG_SAM34_HMATRIX
+ mask |= PM_PBBMASK_HMATRIX; /* HMATRIX */
+#endif
+#ifdef CONFIG_SAM34_PDCA
+ mask |= PM_PBBMASK_PDCA; /* PDCA */
+#endif
+#ifdef CONFIG_SAM34_CRCCU
+ mask |= PM_PBBMASK_CRCCU; /* CRCCU */
+#endif
+#ifdef CONFIG_SAM34_USBC
+ mask |= PM_PBBMASK_USBC; /* USBC */
+#endif
+#ifdef CONFIG_SAM34_PEVC
+ mask |= PM_PBBMASK_PEVC; /* PEVC */
+#endif
+
+ /* Save the new PBB mask */
+
+ putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(SAM_PM_PBBMASK_OFFSET),
+ SAM_PM_UNLOCK);
+ putreg32(mask, SAM_PM_PBBMASK);
+}
+
+/****************************************************************************
+ * Name: sam_init_pbcmask
+ *
+ * Description:
+ * Called during boot to enable clocking on selected peripherals in the
+ * PBC mask register.
+ *
+ ****************************************************************************/
+
+static inline void sam_init_pbcmask(void)
+{
+ /* Select the non-optional peripherals */
+
+ uint32_t mask = (PM_PBCMASK_PM | PM_PBCMASK_SCIF | PM_PBCMASK_GPIO);
+
+ /* OR in the user selected peripherals */
+
+#ifdef CONFIG_SAM34_CHIPID
+ mask |= PM_PBCMASK_CHIPID; /* CHIPID */
+#endif
+#ifdef CONFIG_SAM34_FREQM
+ mask |= PM_PBCMASK_FREQM; /* FREQM */
+#endif
+
+ /* Save the new PBC mask */
+
+ putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(SAM_PM_PBCMASK_OFFSET),
+ SAM_PM_UNLOCK);
+ putreg32(mask, SAM_PM_PBCMASK);
+}
+
+/****************************************************************************
+ * Name: sam_init_pbdmask
+ *
+ * Description:
+ * Called during boot to enable clocking on selected peripherals in the
+ * PBD mask register.
+ *
+ ****************************************************************************/
+
+static inline void sam_init_pbdmask(void)
+{
+ /* Select the non-optional peripherals */
+
+ uint32_t mask = (PM_PBDMASK_BPM | PM_PBDMASK_BSCIF);
+
+ /* OR in the user selected peripherals */
+
+#ifdef CONFIG_SAM34_AST
+ mask |= PM_PBDMASK_AST; /* AST */
+#endif
+#ifdef CONFIG_SAM34_WDT
+ mask |= PM_PBDMASK_WDT; /* WDT */
+#endif
+#ifdef CONFIG_SAM34_EIC
+ mask |= PM_PBDMASK_EIC; /* EIC */
+#endif
+#ifdef CONFIG_SAM34_PICOUART
+ mask |= PM_PBDMASK_PICOUART; /* PICOUART */
+#endif
+
+ /* Save the new PBD mask */
+
+ putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(SAM_PM_PBDMASK_OFFSET),
+ SAM_PM_UNLOCK);
+ putreg32(mask, SAM_PM_PBDMASK);
+}
+
+/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
+ * Name: sam_init_periphclks
+ *
+ * Description:
+ * Called during boot to enable clocking on all selected peripherals.
+ *
+ ****************************************************************************/
+
+void sam_init_periphclks(void)
+{
+ sam_init_cpumask();
+ sam_init_hsbmask();
+ sam_init_pbamask();
+ sam_init_pbbmask();
+ sam_init_pbcmask();
+ sam_init_pbdmask();
+}
+
+/****************************************************************************
* Name: sam_modifyperipheral
*
* Description:
@@ -88,7 +394,8 @@
*
****************************************************************************/
-void sam_modifyperipheral(uintptr_t regaddr, uint32_t clrbits, uint32_t setbits)
+void sam_modifyperipheral(uintptr_t regaddr, uint32_t clrbits,
+ uint32_t setbits)
{
irqstate_t flags;
uint32_t regval;
@@ -102,7 +409,8 @@ void sam_modifyperipheral(uintptr_t regaddr, uint32_t clrbits, uint32_t setbits)
regval = getreg32(regaddr);
regval &= ~clrbits;
regval |= setbits;
- putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(regaddr - SAM_PM_BASE), SAM_PM_UNLOCK);
+ putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(regaddr - SAM_PM_BASE),
+ SAM_PM_UNLOCK);
putreg32(regval, regaddr);
irqrestore(flags);
@@ -131,7 +439,8 @@ void sam_pba_modifydivmask(uint32_t clrbits, uint32_t setbits)
regval = getreg32(SAM_PM_PBADIVMASK);
regval &= ~clrbits;
regval |= setbits;
- putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(SAM_PM_PBADIVMASK_OFFSET), SAM_PM_UNLOCK);
+ putreg32(PM_UNLOCK_KEY(0xaa) | PM_UNLOCK_ADDR(SAM_PM_PBADIVMASK_OFFSET),
+ SAM_PM_UNLOCK);
putreg32(regval, SAM_PM_PBADIVMASK);
irqrestore(flags);
diff --git a/nuttx/arch/arm/src/sam34/sam4l_periphclks.h b/nuttx/arch/arm/src/sam34/sam4l_periphclks.h
index 895556e5d..171e0dd8b 100644
--- a/nuttx/arch/arm/src/sam34/sam4l_periphclks.h
+++ b/nuttx/arch/arm/src/sam34/sam4l_periphclks.h
@@ -42,6 +42,8 @@
#include <nuttx/config.h>
+#ifdef CONFIG_ARCH_CHIP_SAM4L
+
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
@@ -262,83 +264,77 @@ extern "C"
* Public Function Prototypes
************************************************************************************/
-/****************************************************************************
+/************************************************************************************
+ * Name: sam_init_periphclks
+ *
+ * Description:
+ * Called during boot to enable clocking on all selected peripherals.
+ *
+ ************************************************************************************/
+
+void sam_init_periphclks(void);
+
+/************************************************************************************
* Name: sam_modifyperipheral
*
* Description:
- * This is a convenience function that is intended to be used to enable
- * or disable module clocking.
+ * This is a convenience function that is intended to be used to enable or disable
+ * module clocking.
*
- ****************************************************************************/
+ ************************************************************************************/
-#ifdef CONFIG_ARCH_CHIP_SAM4L
void sam_modifyperipheral(uintptr_t regaddr, uint32_t clrbits, uint32_t setbits);
-#endif
-/****************************************************************************
+/************************************************************************************
* Name: sam_pba_modifydivmask
*
* Description:
- * This is a convenience function that is intended to be used to modify
- * bits in the PBA divided clock (DIVMASK) register.
+ * This is a convenience function that is intended to be used to modify bits in
+ * the PBA divided clock (DIVMASK) register.
*
- ****************************************************************************/
+ ************************************************************************************/
-#ifdef CONFIG_ARCH_CHIP_SAM4L
void sam_pba_modifydivmask(uint32_t clrbits, uint32_t setbits);
-#endif
-/****************************************************************************
+/************************************************************************************
* Name: sam_pba_enableperipheral
*
* Description:
- * This is a convenience function to enable a peripheral on the APBA
- * bridge.
+ * This is a convenience function to enable a peripheral on the APBA bridge.
*
- ****************************************************************************/
+ ************************************************************************************/
-#ifdef CONFIG_ARCH_CHIP_SAM4L
void sam_pba_enableperipheral(uint32_t bitset);
-#endif
-/****************************************************************************
+/************************************************************************************
* Name: sam_pba_disableperipheral
*
* Description:
- * This is a convenience function to disable a peripheral on the APBA
- * bridge.
+ * This is a convenience function to disable a peripheral on the APBA bridge.
*
- ****************************************************************************/
+ ************************************************************************************/
-#ifdef CONFIG_ARCH_CHIP_SAM4L
void sam_pba_disableperipheral(uint32_t bitset);
-#endif
-/****************************************************************************
+/************************************************************************************
* Name: sam_pbb_enableperipheral
*
* Description:
- * This is a convenience function to enable a peripheral on the APBB
- * bridge.
+ * This is a convenience function to enable a peripheral on the APBB bridge.
*
- ****************************************************************************/
+ ************************************************************************************/
-#ifdef CONFIG_ARCH_CHIP_SAM4L
void sam_pbb_enableperipheral(uint32_t bitset);
-#endif
-/****************************************************************************
+/************************************************************************************
* Name: sam_pbb_disableperipheral
*
* Description:
- * This is a convenience function to disable a peripheral on the APBA
- * bridge.
+ * This is a convenience function to disable a peripheral on the APBA bridge.
*
- ****************************************************************************/
+ ************************************************************************************/
-#ifdef CONFIG_ARCH_CHIP_SAM4L
void sam_pbb_disableperipheral(uint32_t bitset);
-#endif
#undef EXTERN
#if defined(__cplusplus)
@@ -346,4 +342,5 @@ void sam_pbb_disableperipheral(uint32_t bitset);
#endif
#endif /* __ASSEMBLY__ */
+#endif /* CONFIG_ARCH_CHIP_SAM4L */
#endif /* __ARCH_ARM_SRC_SAM34_SAM4L_PERIPHCLKS_H */
diff --git a/nuttx/configs/sam4l-xplained/README.txt b/nuttx/configs/sam4l-xplained/README.txt
index ea97942f7..8d3784b3e 100644
--- a/nuttx/configs/sam4l-xplained/README.txt
+++ b/nuttx/configs/sam4l-xplained/README.txt
@@ -329,15 +329,61 @@ SAM4L Xplained Pro-specific Configuration Options
Individual subsystems can be enabled:
- CONFIG_SAM34_DMA
- CONFIG_SAM34_HSMCI
- CONFIG_SAM34_NAND
+ CPU
+ ---
+ CONFIG_SAM34_OCD
+
+ HSB
+ ---
+ CONFIG_SAM34_APBA
+ CONFIG_SAM34_AESA
+
+ PBA
+ ---
+ CONFIG_SAM34_IISC
CONFIG_SAM34_SPI
- CONFIG_SAM34_UART
+ CONFIG_SAM34_TC0
+ CONFIG_SAM34_TC1
+ CONFIG_SAM34_TWIM0
+ CONFIG_SAM34_TWIS0
+ CONFIG_SAM34_TWIM1
+ CONFIG_SAM34_TWIS1
CONFIG_SAM34_USART0
CONFIG_SAM34_USART1
CONFIG_SAM34_USART2
CONFIG_SAM34_USART3
+ CONFIG_SAM34_ADCIFE
+ CONFIG_SAM34_DACC
+ CONFIG_SAM34_ACIFC
+ CONFIG_SAM34_GLOC
+ CONFIG_SAM34_ABDACB
+ CONFIG_SAM34_TRNG
+ CONFIG_SAM34_PARC
+ CONFIG_SAM34_CATB
+ CONFIG_SAM34_TWIM2
+ CONFIG_SAM34_TWIM3
+ CONFIG_SAM34_LCDCA
+
+ PBB
+ ---
+ CONFIG_SAM34_HRAMC1
+ CONFIG_SAM34_HMATRIX
+ CONFIG_SAM34_PDCA
+ CONFIG_SAM34_CRCCU
+ CONFIG_SAM34_USBC
+ CONFIG_SAM34_PEVC
+
+ PBC
+ ---
+ CONFIG_SAM34_CHIPID
+ CONFIG_SAM34_FREQM
+
+ PBD
+ ---
+ CONFIG_SAM34_AST
+ CONFIG_SAM34_WDT
+ CONFIG_SAM34_EIC
+ CONFIG_SAM34_PICOUART
Some subsystems can be configured to operate in different ways. The drivers
need to know how to configure the subsystem.
diff --git a/nuttx/configs/sam4l-xplained/ostest/defconfig b/nuttx/configs/sam4l-xplained/ostest/defconfig
index a33d555fa..6d4bcab94 100644
--- a/nuttx/configs/sam4l-xplained/ostest/defconfig
+++ b/nuttx/configs/sam4l-xplained/ostest/defconfig
@@ -127,18 +127,47 @@ CONFIG_ARCH_CHIP_SAM4L=y
# AT91SAM3 Peripheral Support
#
CONFIG_SAM_PICOCACHE=y
-# CONFIG_SAM34_DMA is not set
-# CONFIG_SAM34_NAND is not set
-# CONFIG_SAM34_HSMCI is not set
-# CONFIG_SAM34_UART is not set
+# CONFIG_SAM34_OCD is not set
+# CONFIG_SAM34_APBA is not set
+# CONFIG_SAM34_AESA is not set
+# CONFIG_SAM34_IISC is not set
+# CONFIG_SAM34_SPI is not set
+# CONFIG_SAM34_TC0 is not set
+# CONFIG_SAM34_TC1 is not set
+# CONFIG_SAM34_TWIM0 is not set
+# CONFIG_SAM34_TWIS0 is not set
+# CONFIG_SAM34_TWIM1 is not set
+# CONFIG_SAM34_TWIS1 is not set
+# CONFIG_SAM34_TWIM2 is not set
+# CONFIG_SAM34_TWIM3 is not set
+# CONFIG_SAM34_PICOUART is not set
# CONFIG_SAM34_USART0 is not set
CONFIG_SAM34_USART1=y
# CONFIG_SAM34_USART2 is not set
# CONFIG_SAM34_USART3 is not set
-# CONFIG_SAM34_SPI is not set
-
-#
-# AT91SAM3 UART Configuration
+# CONFIG_SAM34_ADCIFE is not set
+# CONFIG_SAM34_DACC is not set
+# CONFIG_SAM34_ACIFC is not set
+# CONFIG_SAM34_GLOC is not set
+# CONFIG_SAM34_ABDACB is not set
+# CONFIG_SAM34_TRNG is not set
+# CONFIG_SAM34_PARC is not set
+# CONFIG_SAM34_CATB is not set
+# CONFIG_SAM34_LCDCA is not set
+# CONFIG_SAM34_HRAMC1 is not set
+# CONFIG_SAM34_HMATRIX is not set
+# CONFIG_SAM34_PDCA is not set
+# CONFIG_SAM34_CRCCU is not set
+# CONFIG_SAM34_USBC is not set
+# CONFIG_SAM34_PEVC is not set
+# CONFIG_SAM34_CHIPID is not set
+# CONFIG_SAM34_FREQM is not set
+# CONFIG_SAM34_AST is not set
+# CONFIG_SAM34_WDT is not set
+# CONFIG_SAM34_EIC is not set
+
+#
+# AT91SAM3/4 USART Configuration
#
CONFIG_USART1_ISUART=y