summaryrefslogtreecommitdiff
path: root/nuttx/arch/arm
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-25 17:33:41 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-25 17:33:41 +0000
commit27c3eb5b66089e278ebace37fe2392a190f8edde (patch)
tree0b7f8e8de7f36736f82b89b3b40f92bdaa7ed547 /nuttx/arch/arm
parent0f0ce3d8b2dfd3d7a8642c203f249dcd38738592 (diff)
downloadpx4-nuttx-27c3eb5b66089e278ebace37fe2392a190f8edde.tar.gz
px4-nuttx-27c3eb5b66089e278ebace37fe2392a190f8edde.tar.bz2
px4-nuttx-27c3eb5b66089e278ebace37fe2392a190f8edde.zip
convert Kwikstik K40 configurations to use kconfig-frontends tools
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5784 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/arm')
-rw-r--r--nuttx/arch/arm/src/common/up_internal.h2
-rw-r--r--nuttx/arch/arm/src/kinetis/Kconfig472
-rw-r--r--nuttx/arch/arm/src/kinetis/kinetis_internal.h126
-rw-r--r--nuttx/arch/arm/src/lm/Kconfig40
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_lcd.h64
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc17_pwm.h166
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_pwm.h166
7 files changed, 758 insertions, 278 deletions
diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h
index 1a7c1e304..5f3f5e63b 100644
--- a/nuttx/arch/arm/src/common/up_internal.h
+++ b/nuttx/arch/arm/src/common/up_internal.h
@@ -211,7 +211,7 @@ extern uint32_t _ebss; /* End+1 of .bss */
#ifdef CONFIG_ARCH_RAMFUNCS
-# define __ramfunc__ __attribute__ ((section(".ramfunc")))
+# define __ramfunc__ __attribute__ ((section(".ramfunc"),long_call))
/* Functions decleared in the .ramfunc section will be packaged together
* by the linker script and stored in FLASH. During boot-up, the start
diff --git a/nuttx/arch/arm/src/kinetis/Kconfig b/nuttx/arch/arm/src/kinetis/Kconfig
index 210683f59..6c1e36425 100644
--- a/nuttx/arch/arm/src/kinetis/Kconfig
+++ b/nuttx/arch/arm/src/kinetis/Kconfig
@@ -4,3 +4,475 @@
#
comment "Kinetis Configuration Options"
+
+choice
+ prompt "Kinetis Chip Selection"
+ default ARCH_CHIP_MK60N512VMD100
+ depends on ARCH_CHIP_KINETIS
+
+config ARCH_CHIP_MK40N512VLQ100
+ bool "MK40N512VLQ100"
+ select ARCH_FAMILY_K40
+
+config ARCH_CHIP_MK40N512VMD100
+ bool "MK40N512VMD100"
+ select ARCH_FAMILY_K40
+
+config ARCH_CHIP_MK40X128VLQ100
+ bool "MK40X128VLQ100"
+ select ARCH_FAMILY_K40
+
+config ARCH_CHIP_MK40X128VMD100
+ bool "MK40X128VMD100"
+ select ARCH_FAMILY_K40
+
+config ARCH_CHIP_MK40X256VLQ100
+ bool "MK40X256VLQ100"
+ select ARCH_FAMILY_K40
+
+config ARCH_CHIP_MK40X256VMD100
+ bool "MK40X256VMD100"
+ select ARCH_FAMILY_K40
+
+config ARCH_CHIP_MK60N256VLQ100
+ bool "MK60N256VLQ100"
+ select ARCH_FAMILY_K60
+
+config ARCH_CHIP_MK60N256VMD100
+ bool "MK60N256VMD100"
+ select ARCH_FAMILY_K60
+
+config ARCH_CHIP_MK60N512VLQ100
+ bool "MK60N512VLQ100"
+ select ARCH_FAMILY_K60
+
+config ARCH_CHIP_MK60N512VMD100
+ bool "MK60N512VMD100"
+ select ARCH_FAMILY_K60
+
+config ARCH_CHIP_MK60X256VLQ100
+ bool "MK60X256VLQ100"
+ select ARCH_FAMILY_K60
+
+config ARCH_CHIP_MK60X256VMD100
+ bool "MK60X256VMD100"
+ select ARCH_FAMILY_K60
+
+endchoice
+
+# Chip families
+
+config ARCH_FAMILY_K40
+ bool
+ default n
+
+config ARCH_FAMILY_K60
+ bool
+ default n
+
+menu "Kinetis Peripheral Support"
+
+config KINETIS_TRACE
+ bool "Trace"
+ default n
+ ---help---
+ Enable trace clocking on power up.
+
+config KINETIS_FLEXBUS
+ bool "FlexBus"
+ default n
+ ---help---
+ Enable flexbus clocking on power up.
+
+config KINETIS_UART0
+ bool "UART0"
+ default n
+ select ARCH_HAVE_UART0
+ ---help---
+ Support UART0
+
+config KINETIS_UART1
+ bool "UART1"
+ default n
+ select ARCH_HAVE_UART1
+ ---help---
+ Support UART1
+
+config KINETIS_UART2
+ bool "UART2"
+ default n
+ select ARCH_HAVE_UART2
+ ---help---
+ Support UART2
+
+config KINETIS_UART3
+ bool "UART3"
+ default n
+ select ARCH_HAVE_UART3
+ ---help---
+ Support UART3
+
+config KINETIS_UART4
+ bool "UART4"
+ default n
+ select ARCH_HAVE_UART4
+ ---help---
+ Support UART4
+
+config KINETIS_UART5
+ bool "UART5"
+ default n
+ select ARCH_HAVE_UART5
+ ---help---
+ Support UART5
+
+config KINETIS_ENET
+ bool "Ethernet"
+ default n
+ depends on ARCH_FAMILY_K60
+ select NET
+ ---help---
+ Support Ethernet (K60 only)
+
+config KINETIS_RNGB
+ bool "Random number generator"
+ default n
+ depends on ARCH_FAMILY_K60
+ ---help---
+ Support the random number generator(K60 only)
+
+config KINETIS_FLEXCAN0
+ bool "FlexCAN0"
+ default n
+ ---help---
+ Support FlexCAN0
+
+config KINETIS_FLEXCAN1
+ bool "FlexCAN1"
+ default n
+ ---help---
+ Support FlexCAN1
+
+config KINETIS_SPI0
+ bool "SPI0"
+ default n
+ ---help---
+ Support SPI0
+
+config KINETIS_SPI1
+ bool "SPI1"
+ default n
+ ---help---
+ Support SPI1
+
+config KINETIS_SPI2
+ bool "SPI2"
+ default n
+ ---help---
+ Support SPI2
+
+config KINETIS_I2C0
+ bool "I2C0"
+ default n
+ ---help---
+ Support I2C0
+
+config KINETIS_I2C1
+ bool "I2C1"
+ default n
+ ---help---
+ Support I2C1
+
+config KINETIS_I2S
+ bool "I2S"
+ default n
+ ---help---
+ Support I2S
+
+config KINETIS_DAC0
+ bool "DAC0"
+ default n
+ ---help---
+ Support DAC0
+
+config KINETIS_DAC1
+ bool "DAC1"
+ default n
+ ---help---
+ Support DAC1
+
+config KINETIS_ADC0
+ bool "ADC0"
+ default n
+ ---help---
+ Support ADC0
+
+config KINETIS_ADC1
+ bool "ADC1"
+ default n
+ ---help---
+ Support ADC1
+
+config KINETIS_CMP
+ bool "CMP"
+ default n
+ ---help---
+ Support CMP
+
+config KINETIS_VREF
+ bool "VREF"
+ default n
+ ---help---
+ Support VREF
+
+config KINETIS_SDHC
+ bool "SDHC"
+ default n
+ select MMCSD_SDIO
+ ---help---
+ Support SD host controller
+
+config KINETIS_FTM0
+ bool "FTM0"
+ default n
+ ---help---
+ Support FlexTimer 0
+
+config KINETIS_FTM1
+ bool "FTM1"
+ default n
+ ---help---
+ Support FlexTimer 1
+
+config KINETIS_FTM2
+ bool "FTM2"
+ default n
+ ---help---
+ Support FlexTimer 2
+
+config KINETIS_LPTIMER
+ bool "Low power timer (LPTIMER)"
+ default n
+ ---help---
+ Support the low power timer
+
+config KINETIS_RTC
+ bool "RTC"
+ default n
+ ---help---
+ Support RTC
+
+config KINETIS_SLCD
+ bool "Segment LCD (SLCD)"
+ default n
+ depends on ARCH_FAMILY_K40
+ ---help---
+ Support the segment LCD (K40 only)
+
+config KINETIS_EWM
+ bool "External watchdog (WVM)"
+ default n
+ ---help---
+ Support the external watchdog
+
+config KINETIS_CMT
+ bool "Carrier modulator transmitter (CMT)"
+ default n
+ ---help---
+ Support Carrier Modulator Transmitter
+
+config KINETIS_USBOTG
+ bool "USB OTG"
+ default n
+ ---help---
+ Support USB OTG (see also USBHOST and USBDEV)
+
+config KINETIS_USBDCD
+ bool "USB device controller"
+ default n
+ ---help---
+ Support the USB Device Charger Detection module
+
+config KINETIS_LLWU
+ bool "Low leakage wake-up unit (LLWU)"
+ default n
+ ---help---
+ Support the Low Leakage Wake-Up Unit
+
+config KINETIS_TSI
+ bool "Touchscreen interface (TSI)"
+ default n
+ ---help---
+ Support the touch screeen interface
+
+config KINETIS_FTFL
+ bool "FLASH (FTFL)"
+ default n
+ ---help---
+ Support FLASH
+
+config KINETIS_DMA
+ bool "DMA"
+ default n
+ ---help---
+ Support DMA
+
+config KINETIS_CRC
+ bool "CRC"
+ default n
+ ---help---
+ Support CRC
+
+config KINETIS_PDB
+ bool "Programmable delay block (PDB)"
+ default n
+ ---help---
+ Support the Programmable Delay Block
+
+config KINETIS_PIT
+ bool "Programmable interval timer (PIT)"
+ default n
+ ---help---
+ Support Programmable Interval Timers
+
+endmenu
+
+comment "Kinetis GPIO Interrupt Configuration"
+
+config GPIO_IRQ
+ bool "GPIO interrupts"
+ ---help---
+ Enable support for interrupt GPIO pins
+
+if GPIO_IRQ
+
+config KINETIS_PORTAINTS
+ bool "GPIOA interrupts"
+ ---help---
+ Enable support for interrupts from GPIO port A pins
+
+config KINETIS_PORTBINTS
+ bool "GPIOB interrupts"
+ ---help---
+ Enable support for interrupts from GPIO port B pins
+
+config KINETIS_PORTCINTS
+ bool "GPIOC interrupts"
+ ---help---
+ Enable support for interrupts from GPIO port C pins
+
+config KINETIS_PORTDINTS
+ bool "GPIOD interrupts"
+ ---help---
+ Enable support for interrupts from GPIO port D pins
+
+config KINETIS_PORTEINTS
+ bool "GPIOE interrupts"
+ ---help---
+ Enable support for interrupts from GPIO port E pins
+
+endif
+
+if KINETIS_ENET
+
+comment "Kinetis Ethernet Configuration"
+
+config ENET_ENHANCEDBD
+ bool "Use enhanced buffer descriptors"
+ default n
+ ---help---
+ Use enhanced, 32-byte buffer descriptors
+
+config ENET_NETHIFS
+ int "Number of Ethernet interfaces"
+ default 1
+ ---help---
+ Number of Ethernet interfaces supported by the hardware. Must be
+ one for now.
+
+config ENET_NRXBUFFERS
+ int "Number of Ethernet Rx buffers"
+ default 6
+ ---help---
+ Number of Ethernet Rx buffers to use.
+
+config ENET_NTXBUFFERS
+ int "Number of Ethernet Tx buffers"
+ default 2
+ ---help---
+ Number of Ethernet Tx buffers to use.
+
+config ENET_PHYADDR
+ int "PHY address"
+ default 1
+ ---help---
+ MII/RMII address of the PHY
+
+config ENET_USEMII
+ bool "Use MII interface"
+ default n
+ ---help---
+ The the MII PHY interface. Default: Use RMII interface
+
+endif
+
+if KINETIS_SDHC
+
+comment "Kinetis SDHC Configuration"
+
+config KINETIS_SDHC_ABSFREQ
+ bool "Custom transfer frequencies"
+ default n
+ ---help---
+ Select SDCLK frequencies corresponding to various modes of operation.
+ These values may be provided in either the NuttX configuration file
+ or in the board.h file
+
+ NOTE: These settings are not currently used. Since there are only
+ four frequencies, it makes more sense to just "can" the fixed
+ frequency prescaler and divider values.
+
+if KINETIS_SDHC_ABSFREQ
+
+config KINETIS_IDMODE_FREQ
+ int "ID mode frequency"
+ default 400000
+ ---help---
+ Initial, ID mode SD frequency
+
+config KINETIS_MMCXFR_FREQ
+ int "MMC transfer frequency"
+ default 20000000
+ ---help---
+ Frequency to use for transferring data to/from an MMC card
+
+config KINETIS_SD1BIT_FREQ
+ int "SD 1-bit transfer frequency"
+ default 20000000
+ depends on CONFIG_SDIO_WIDTH_D1_ONLY
+ ---help---
+ Frequency to use for transferring data to/from an SD card using on a single data liune.
+
+config KINETIS_SD4BIT_FREQ
+ int "SD 4-bit transfer frequency"
+ default 20000000
+ depends on !CONFIG_SDIO_WIDTH_D1_ONLY
+ ---help---
+ Frequency to use for transferring data to/from an SD card using all four data lines.
+
+endif
+
+config KINETIS_SDHC_DMAPRIO
+ int "SDHC DMA priority"
+ depends on SDIO_DMA
+ ---help---
+ SDHC DMA priority
+
+endif
+
+comment "Kinetis UART Configuration"
+
+config KINETIS_UARTFIFOS
+ bool "Enable UART0 FIFO"
+ default n
+ depends on KINETIS_UART0
diff --git a/nuttx/arch/arm/src/kinetis/kinetis_internal.h b/nuttx/arch/arm/src/kinetis/kinetis_internal.h
index 8d7baaaf1..79cb542cc 100644
--- a/nuttx/arch/arm/src/kinetis/kinetis_internal.h
+++ b/nuttx/arch/arm/src/kinetis/kinetis_internal.h
@@ -344,7 +344,8 @@ struct kinetis_dmaregs_s
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
@@ -363,7 +364,7 @@ extern "C" {
*
************************************************************************************/
-EXTERN void kinetis_clockconfig(void);
+void kinetis_clockconfig(void);
/************************************************************************************
* Name: kinetis_lowsetup
@@ -375,7 +376,7 @@ EXTERN void kinetis_clockconfig(void);
*
************************************************************************************/
-EXTERN void kinetis_lowsetup(void);
+void kinetis_lowsetup(void);
/******************************************************************************
* Name: kinetis_uartreset
@@ -386,7 +387,7 @@ EXTERN void kinetis_lowsetup(void);
******************************************************************************/
#ifdef HAVE_UART_DEVICE
-EXTERN void kinetis_uartreset(uintptr_t uart_base);
+void kinetis_uartreset(uintptr_t uart_base);
#endif
/******************************************************************************
@@ -398,9 +399,8 @@ EXTERN void kinetis_uartreset(uintptr_t uart_base);
******************************************************************************/
#ifdef HAVE_UART_DEVICE
-EXTERN void kinetis_uartconfigure(uintptr_t uart_base, uint32_t baud,
- uint32_t clock, unsigned int parity,
- unsigned int nbits);
+void kinetis_uartconfigure(uintptr_t uart_base, uint32_t baud, uint32_t clock,
+ unsigned int parity, unsigned int nbits);
#endif
/************************************************************************************
@@ -411,7 +411,7 @@ EXTERN void kinetis_uartconfigure(uintptr_t uart_base, uint32_t baud,
*
************************************************************************************/
-EXTERN void kinetis_wddisable(void);
+void kinetis_wddisable(void);
/************************************************************************************
* Name: kinetis_pinconfig
@@ -421,7 +421,7 @@ EXTERN void kinetis_wddisable(void);
*
************************************************************************************/
-EXTERN int kinetis_pinconfig(uint32_t cfgset);
+int kinetis_pinconfig(uint32_t cfgset);
/************************************************************************************
* Name: kinetis_pinfilter
@@ -438,7 +438,7 @@ EXTERN int kinetis_pinconfig(uint32_t cfgset);
*
************************************************************************************/
-EXTERN int kinetis_pinfilter(unsigned int port, bool lpo, unsigned int width);
+int kinetis_pinfilter(unsigned int port, bool lpo, unsigned int width);
/************************************************************************************
* Name: kinetis_gpiowrite
@@ -448,7 +448,7 @@ EXTERN int kinetis_pinfilter(unsigned int port, bool lpo, unsigned int width);
*
************************************************************************************/
-EXTERN void kinetis_gpiowrite(uint32_t pinset, bool value);
+void kinetis_gpiowrite(uint32_t pinset, bool value);
/************************************************************************************
* Name: kinetis_gpioread
@@ -458,7 +458,7 @@ EXTERN void kinetis_gpiowrite(uint32_t pinset, bool value);
*
************************************************************************************/
-EXTERN bool kinetis_gpioread(uint32_t pinset);
+bool kinetis_gpioread(uint32_t pinset);
/************************************************************************************
* Name: kinetis_pinirqinitialize
@@ -469,7 +469,7 @@ EXTERN bool kinetis_gpioread(uint32_t pinset);
************************************************************************************/
#ifdef CONFIG_GPIO_IRQ
-EXTERN void kinetis_pinirqinitialize(void);
+void kinetis_pinirqinitialize(void);
#else
# define kinetis_pinirqinitialize()
#endif
@@ -496,7 +496,7 @@ EXTERN void kinetis_pinirqinitialize(void);
*
************************************************************************************/
-EXTERN xcpt_t kinetis_pinirqattach(uint32_t pinset, xcpt_t pinisr);
+xcpt_t kinetis_pinirqattach(uint32_t pinset, xcpt_t pinisr);
/************************************************************************************
* Name: kinetis_pinirqenable
@@ -507,7 +507,7 @@ EXTERN xcpt_t kinetis_pinirqattach(uint32_t pinset, xcpt_t pinisr);
************************************************************************************/
#ifdef CONFIG_GPIO_IRQ
-EXTERN void kinetis_pinirqenable(uint32_t pinset);
+void kinetis_pinirqenable(uint32_t pinset);
#else
# define kinetis_pinirqenable(pinset)
#endif
@@ -521,7 +521,7 @@ EXTERN void kinetis_pinirqenable(uint32_t pinset);
************************************************************************************/
#ifdef CONFIG_GPIO_IRQ
-EXTERN void kinetis_pinirqdisable(uint32_t pinset);
+void kinetis_pinirqdisable(uint32_t pinset);
#else
# define kinetis_pinirqdisable(pinset)
#endif
@@ -535,7 +535,7 @@ EXTERN void kinetis_pinirqdisable(uint32_t pinset);
************************************************************************************/
#ifdef CONFIG_KINETIS_DMA
-EXTERN void kinetis_pindmaenable(uint32_t pinset);
+void kinetis_pindmaenable(uint32_t pinset);
#endif
/************************************************************************************
@@ -547,7 +547,7 @@ EXTERN void kinetis_pindmaenable(uint32_t pinset);
************************************************************************************/
#ifdef CONFIG_KINETIS_DMA
-EXTERN void kinetis_pindmadisable(uint32_t pinset);
+void kinetis_pindmadisable(uint32_t pinset);
#endif
/************************************************************************************
@@ -559,7 +559,7 @@ EXTERN void kinetis_pindmadisable(uint32_t pinset);
************************************************************************************/
#ifdef CONFIG_DEBUG_GPIO
-EXTERN int kinetis_pindump(uint32_t pinset, const char *msg);
+int kinetis_pindump(uint32_t pinset, const char *msg);
#else
# define kinetis_pindump(p,m)
#endif
@@ -573,11 +573,10 @@ EXTERN int kinetis_pindump(uint32_t pinset, const char *msg);
*
************************************************************************************/
-EXTERN void kinetis_clrpend(int irq);
+void kinetis_clrpend(int irq);
/************************************************************************************
- * Name: kinetis_spi/ssp0/ssp1select, kinetis_spi/ssp0/ssp1status, and
- * kinetis_spi/ssp0/ssp1cmddata
+ * Name: kinetis_spi[n]select, kinetis_spi[n]status, and kinetis_spi[n]cmddata
*
* Description:
* These external functions must be provided by board-specific logic. They are
@@ -586,13 +585,13 @@ EXTERN void kinetis_clrpend(int irq);
* including up_spiinitialize()) are provided by common Kinetis logic. To use
* this common SPI logic on your board:
*
- * 1. Provide logic in kinetis_boardinitialize() to configure SPI/SSP chip select
+ * 1. Provide logic in kinetis_boardinitialize() to configure SPI chip select
* pins.
- * 2. Provide kinetis_spi/ssp0/ssp1select() and kinetis_spi/ssp0/ssp1status() functions
+ * 2. Provide kinetis_spi[n]select() and kinetis_spi[n]status() functions
* in your board-specific logic. These functions will perform chip selection
* and status operations using GPIOs in the way your board is configured.
* 2. If CONFIG_SPI_CMDDATA is defined in the NuttX configuration, provide
- * kinetis_spi/ssp0/ssp1cmddata() functions in your board-specific logic. These
+ * kinetis_spi[n]cmddata() functions in your board-specific logic. These
* functions will perform cmd/data selection operations using GPIOs in the way
* your board is configured.
* 3. Add a call to up_spiinitialize() in your low level application
@@ -607,25 +606,25 @@ EXTERN void kinetis_clrpend(int irq);
struct spi_dev_s;
enum spi_dev_e;
-#ifdef CONFIG_KINETIS_SPI
-EXTERN void kinetis_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
-EXTERN uint8_t kinetis_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
+#ifdef CONFIG_KINETIS_SPI0
+void kinetis_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
+uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
#ifdef CONFIG_SPI_CMDDATA
-EXTERN int kinetis_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
+int kinetis_spi0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
#endif
#endif
-#ifdef CONFIG_KINETIS_SSP0
-EXTERN void kinetis_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
-EXTERN uint8_t kinetis_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
+#ifdef CONFIG_KINETIS_SPI1
+void kinetis_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
+uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
#ifdef CONFIG_SPI_CMDDATA
-EXTERN int kinetis_ssp0cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
+int kinetis_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
#endif
#endif
-#ifdef CONFIG_KINETIS_SSP1
-EXTERN void kinetis_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
-EXTERN uint8_t kinetis_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
+#ifdef CONFIG_KINETIS_SPI2
+void kinetis_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
+uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
#ifdef CONFIG_SPI_CMDDATA
-EXTERN int kinetis_ssp1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
+int kinetis_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
#endif
#endif
@@ -634,7 +633,7 @@ EXTERN int kinetis_ssp1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
*
* Description:
* Flush and discard any words left in the RX fifo. This can be called
- * from ssp0/1select after a device is deselected (if you worry about such
+ * from spi[n]select after a device is deselected (if you worry about such
* things).
*
* Input Parameters:
@@ -645,12 +644,9 @@ EXTERN int kinetis_ssp1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
*
****************************************************************************/
+#if defined(CONFIG_KINETIS_SPI0) || defined(CONFIG_KINETIS_SPI0) || defined(CONFIG_KINETIS_SPI2)
struct spi_dev_s;
-#ifdef CONFIG_KINETIS_SPI
-EXTERN void spi_flush(FAR struct spi_dev_s *dev);
-#endif
-#if defined(CONFIG_KINETIS_SSP0) || defined(CONFIG_KINETIS_SSP1)
-EXTERN void ssp_flush(FAR struct spi_dev_s *dev);
+void spi_flush(FAR struct spi_dev_s *dev);
#endif
/****************************************************************************
@@ -664,8 +660,8 @@ EXTERN void ssp_flush(FAR struct spi_dev_s *dev);
*
****************************************************************************/
-#ifdef CONFIG_KINETIS_GPDMA
-EXTERN void kinetis_dmainitilaize(void);
+#ifdef CONFIG_KINETIS_DMA
+void kinetis_dmainitilaize(void);
#endif
/****************************************************************************
@@ -682,8 +678,8 @@ EXTERN void kinetis_dmainitilaize(void);
*
****************************************************************************/
-#ifdef CONFIG_KINETIS_GPDMA
-EXTERN DMA_HANDLE kinetis_dmachannel(void);
+#ifdef CONFIG_KINETIS_DMA
+DMA_HANDLE kinetis_dmachannel(void);
#endif
/****************************************************************************
@@ -699,8 +695,8 @@ EXTERN DMA_HANDLE kinetis_dmachannel(void);
*
****************************************************************************/
-#ifdef CONFIG_KINETIS_GPDMA
-EXTERN void kinetis_dmafree(DMA_HANDLE handle);
+#ifdef CONFIG_KINETIS_DMA
+void kinetis_dmafree(DMA_HANDLE handle);
#endif
/****************************************************************************
@@ -711,11 +707,9 @@ EXTERN void kinetis_dmafree(DMA_HANDLE handle);
*
****************************************************************************/
-#ifdef CONFIG_KINETIS_GPDMA
-EXTERN int kinetis_dmarxsetup(DMA_HANDLE handle,
- uint32_t control, uint32_t config,
- uint32_t srcaddr, uint32_t destaddr,
- size_t nbytes);
+#ifdef CONFIG_KINETIS_DMA
+int kinetis_dmarxsetup(DMA_HANDLE handle, uint32_t control, uint32_t config,
+ uint32_t srcaddr, uint32_t destaddr, size_t nbytes);
#endif
/****************************************************************************
@@ -726,8 +720,8 @@ EXTERN int kinetis_dmarxsetup(DMA_HANDLE handle,
*
****************************************************************************/
-#ifdef CONFIG_KINETIS_GPDMA
-EXTERN int kinetis_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg);
+#ifdef CONFIG_KINETIS_DMA
+int kinetis_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg);
#endif
/****************************************************************************
@@ -740,8 +734,8 @@ EXTERN int kinetis_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *ar
*
****************************************************************************/
-#ifdef CONFIG_KINETIS_GPDMA
-EXTERN void kinetis_dmastop(DMA_HANDLE handle);
+#ifdef CONFIG_KINETIS_DMA
+void kinetis_dmastop(DMA_HANDLE handle);
#endif
/****************************************************************************
@@ -752,9 +746,9 @@ EXTERN void kinetis_dmastop(DMA_HANDLE handle);
*
****************************************************************************/
-#ifdef CONFIG_KINETIS_GPDMA
+#ifdef CONFIG_KINETIS_DMA
#ifdef CONFIG_DEBUG_DMA
-EXTERN void kinetis_dmasample(DMA_HANDLE handle, struct kinetis_dmaregs_s *regs);
+void kinetis_dmasample(DMA_HANDLE handle, struct kinetis_dmaregs_s *regs);
#else
# define kinetis_dmasample(handle,regs)
#endif
@@ -768,10 +762,10 @@ EXTERN void kinetis_dmasample(DMA_HANDLE handle, struct kinetis_dmaregs_s *regs)
*
****************************************************************************/
-#ifdef CONFIG_KINETIS_GPDMA
+#ifdef CONFIG_KINETIS_DMA
#ifdef CONFIG_DEBUG_DMA
-EXTERN void kinetis_dmadump(DMA_HANDLE handle, const struct kinetis_dmaregs_s *regs,
- const char *msg);
+void kinetis_dmadump(DMA_HANDLE handle, const struct kinetis_dmaregs_s *regs,
+ const char *msg);
#else
# define kinetis_dmadump(handle,regs,msg)
#endif
@@ -793,7 +787,7 @@ EXTERN void kinetis_dmadump(DMA_HANDLE handle, const struct kinetis_dmaregs_s *r
#ifdef CONFIG_KINETIS_SDHC
struct sdio_dev_s;
-EXTERN FAR struct sdio_dev_s *sdhc_initialize(int slotno);
+FAR struct sdio_dev_s *sdhc_initialize(int slotno);
#endif
/****************************************************************************
@@ -816,7 +810,7 @@ EXTERN FAR struct sdio_dev_s *sdhc_initialize(int slotno);
****************************************************************************/
#ifdef CONFIG_KINETIS_SDHC
-EXTERN void sdhc_mediachange(FAR struct sdio_dev_s *dev, bool cardinslot);
+void sdhc_mediachange(FAR struct sdio_dev_s *dev, bool cardinslot);
#endif
/****************************************************************************
@@ -836,7 +830,7 @@ EXTERN void sdhc_mediachange(FAR struct sdio_dev_s *dev, bool cardinslot);
****************************************************************************/
#ifdef CONFIG_KINETIS_SDHC
-EXTERN void sdhc_wrprotect(FAR struct sdio_dev_s *dev, bool wrprotect);
+void sdhc_wrprotect(FAR struct sdio_dev_s *dev, bool wrprotect);
#endif
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/arch/arm/src/lm/Kconfig b/nuttx/arch/arm/src/lm/Kconfig
index b2786c265..676773d69 100644
--- a/nuttx/arch/arm/src/lm/Kconfig
+++ b/nuttx/arch/arm/src/lm/Kconfig
@@ -73,6 +73,41 @@ config LM_UART1
select ARCH_HAVE_UART1
default n
+config LM_UART2
+ bool "UART2"
+ select ARCH_HAVE_UART2
+ default n
+
+config LM_UART3
+ bool "UART3"
+ default n
+ depends on ARCH_CHIP_LM4F
+ select ARCH_HAVE_UART3
+
+config LM_UART4
+ bool "UART4"
+ default n
+ depends on ARCH_CHIP_LM4F
+ select ARCH_HAVE_UART4
+
+config LM_UART5
+ bool "UART5"
+ default n
+ depends on ARCH_CHIP_LM4F
+ select ARCH_HAVE_UART5
+
+config LM_UART6
+ bool "UART6"
+ default n
+ depends on ARCH_CHIP_LM4F
+ select ARCH_HAVE_UART6
+
+config LM_UART7
+ bool "UART7"
+ default n
+ depends on ARCH_CHIP_LM4F
+ select ARCH_HAVE_UART7
+
config SSI0_DISABLE
bool "Disable SSI0"
default y
@@ -81,11 +116,6 @@ config SSI1_DISABLE
bool "Disable SSI1"
default y
-config LM_UART2
- bool "UART2"
- select ARCH_HAVE_UART2
- default n
-
config LM_ETHERNET
bool "Stellaris Ethernet"
default n
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_lcd.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_lcd.h
index 065dee9b5..0485db388 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_lcd.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_lcd.h
@@ -49,7 +49,7 @@
* Pre-processor Definitions
************************************************************************************************/
-/* Register offsets *****************************************************************/
+/* Register offsets *****************************************************************************/
#define LPC17_LCD_TIMH_OFFSET (0x0000) /* Horizontal Timing Control register */
#define LPC17_LCD_TIMV_OFFSET (0x0004) /* Vertical Timing Control register */
@@ -64,15 +64,14 @@
#define LPC17_LCD_INTCLR_OFFSET (0x0028) /* Interrupt Clear register */
#define LPC17_LCD_UPCURR_OFFSET (0x002c) /* Upper Panel Current Address Value register */
#define LPC17_LCD_LPCURR_OFFSET (0x0030) /* Lower Panel Current Address Value register */
-#define LPC17_LCD_PAL0_OFFSET (0x0200) /* 256x16bit Color Palette registers */
-#define LPC17_LCD_PAL1_OFFSET (0x0200) /* */
-***
-#define LPC17_LCD_PAL127_OFFSET (0x03fc) /* */
-#define LPC17_LCD_CRSR_IMG0_OFFSET (0x0800) /* Cursor Image registers */
-#define LPC17_LCD_CRSR_IMG1_OFFSET (0x0800) /* Cursor Image registers */
-***
-#define LPC17_LCD_CRSR_IMG255_OFFSET (0x0bfc) /* Cursor Image registers */
+/* 256x16-bit Color Palette registers, n=0-127 */
+
+#define LPC17_LCD_PAL_OFFSET(n) (0x0200 + ((n) << 2))
+
+/* Cursor Image registers, n=0-255 */
+
+#define LPC17_LCD_CRSR_IMG_OFFSET(n) (0x0800 + ((n) << 2))
#define LPC17_LCD_CRSR_CRTL_OFFSET (0x0c00) /* Cursor Control register */
#define LPC17_LCD_CRSR_CFG_OFFSET (0x0c04) /* Cursor Configuration register */
@@ -85,29 +84,24 @@
#define LPC17_LCD_CRSR_INTRAW_OFFSET (0x0c28) /* Cursor Raw Interrupt Status register */
#define LPC17_LCD_CRSR_INTSTAT_OFFSET (0x0c2c) /* Cursor Masked Interrupt Status register */
-/* Register Addresses */
+/* Register Addresses ***************************************************************************/
#define LPC17_LCD_TIMH (LPC17_LCD_BASE+LPC17_LCD_TIMH_OFFSET)
#define LPC17_LCD_TIMV (LPC17_LCD_BASE+LPC17_LCD_TIMV_OFFSET)
#define LPC17_LCD_POL (LPC17_LCD_BASE+LPC17_LCD_POL_OFFSET)
-#define LPC17_LCD_LE_OFFSET (LPC17_LCD_BASE+LPC17_LCD_LE_OFFSET)
-#define LPC17_LCD_UPBASE_OFFSET (LPC17_LCD_BASE+LPC17_LCD_UPBASE_OFFSET)
-#define LPC17_LCD_LPBASE_OFFSET (LPC17_LCD_BASE+LPC17_LCD_LPBASE_OFFSET)
-#define LPC17_LCD_CTRL_OFFSET (LPC17_LCD_BASE+LPC17_LCD_CTRL_OFFSET)
-#define LPC17_LCD_INTMSK_OFFSET (LPC17_LCD_BASE+LPC17_LCD_INTMSK_OFFSET)
-#define LPC17_LCD_INTRAW_OFFSET (LPC17_LCD_BASE+LPC17_LCD_INTRAW_OFFSET)
-#define LPC17_LCD_INTSTAT_OFFSET (LPC17_LCD_BASE+LPC17_LCD_INTSTAT_OFFSET)
-#define LPC17_LCD_INTCLR_OFFSET (LPC17_LCD_BASE+ LPC17_LCD_INTCLR_OFFSET)
-#define LPC17_LCD_UPCURR_OFFSET (LPC17_LCD_BASE+LPC17_LCD_UPCURR_OFFSET)
-#define LPC17_LCD_LPCURR_OFFSET (LPC17_LCD_BASE+LPC17_LCD_LPCURR_OFFSET)
-***
-#define LPC17_LCD_PAL0_OFFSET (LPC17_LCD_BASE+LPC17_LCD_PAL0_OFFSET)
-#define LPC17_LCD_PAL1_OFFSET (LPC17_LCD_BASE+LPC17_LCD_PAL1_OFFSET)
-#define LPC17_LCD_PAL127_OFFSET (LPC17_LCD_BASE+LPC17_LCD_PAL127_OFFSET)
-***
-#define LPC17_LCD_CRSR_IMG0 (LPC17_LCD_BASE+LPC17_LCD_CRSR_IMG0_OFFSET)
-#define LPC17_LCD_CRSR_IMG1 (LPC17_LCD_BASE+LPC17_LCD_CRSR_IMG1_OFFSET)
-#define LPC17_LCD_CRSR_IMG255 (LPC17_LCD_BASE+LPC17_LCD_CRSR_IMG255_OFFSET)
+#define LPC17_LCD_LE (LPC17_LCD_BASE+LPC17_LCD_LE_OFFSET)
+#define LPC17_LCD_UPBASE (LPC17_LCD_BASE+LPC17_LCD_UPBASE_OFFSET)
+#define LPC17_LCD_LPBASE (LPC17_LCD_BASE+LPC17_LCD_LPBASE_OFFSET)
+#define LPC17_LCD_CTRL (LPC17_LCD_BASE+LPC17_LCD_CTRL_OFFSET)
+#define LPC17_LCD_INTMSK (LPC17_LCD_BASE+LPC17_LCD_INTMSK_OFFSET)
+#define LPC17_LCD_INTRAW (LPC17_LCD_BASE+LPC17_LCD_INTRAW_OFFSET)
+#define LPC17_LCD_INTSTAT (LPC17_LCD_BASE+LPC17_LCD_INTSTAT_OFFSET)
+#define LPC17_LCD_INTCLR (LPC17_LCD_BASE+ LPC17_LCD_INTCLR_OFFSET)
+#define LPC17_LCD_UPCURR (LPC17_LCD_BASE+LPC17_LCD_UPCURR_OFFSET)
+#define LPC17_LCD_LPCURR (LPC17_LCD_BASE+LPC17_LCD_LPCURR_OFFSET)
+
+#define LPC17_LCD_PAL(n) (LPC17_LCD_BASE+LPC17_LCD_PAL_OFFSET(n))
+#define LPC17_LCD_CRSR_IMG(n) (LPC17_LCD_BASE+LPC17_LCD_CRSR_IMG_OFFSET(n))
#define LPC17_LCD_CRSR_CRTL (LPC17_LCD_BASE+LPC17_LCD_CRSR_CRTL_OFFSET)
#define LPC17_LCD_CRSR_CFG (LPC17_LCD_BASE+LPC17_LCD_CRSR_CFG_OFFSET)
@@ -120,10 +114,9 @@
#define LPC17_LCD_CRSR_INTRAW (LPC17_LCD_BASE+LPC17_LCD_CRSR_INTRAW_OFFSET)
#define LPC17_LCD_CRSR_INTSTAT (LPC17_LCD_BASE+LPC17_LCD_CRSR_INTSTAT_OFFSET)
-/* Register Bitfield Definitions */
+/* Register Bitfield Definitions ****************************************************************/
/* LCD_TIMH - Horizontal Timing Register */
-
/* Bits 0-1: Reserved */
#define LCD_TIMH_PPL_SHIFT (2) /* Bits 2-7: Pixels Per Line - 16-1024ppl */
#define LCD_TIMH_PPL_MASK (0x3f << LCD_TIMH_PPL_SHIFT)
@@ -177,7 +170,6 @@
#define LCD_LE_LEE_SHIFT (16) /* Bit16: LCD line end enable */
#define LCD_LE_LEE_MASK (1 << LCD_LE_LEE_SHIFT)
/* Bit 17-31: Reserved */
-
/* LCD_UPBASE - Upper Panel Frame Base Address Register */
/* Bits 0-2: Reserved */
#define LCD_UPBASE_LCDUPBASE_SHIFT (3) /* Bits 3-31: LCD upper panel base address */
@@ -216,7 +208,6 @@
#define LCD_CTRL_WATERMARK_SHIFT (16) /* Bit 16: LCD DMA FIFO watermark level */
#define LCD_CTRL_WATERMARK_MASK (1 << LCD_CTRL_WATERMARK_SHIFT)
/* Bits 17-31: Reserved */
-
/* LCD_INTMSK - Interrupt Mask Register */
/* Bits 0: Reserved */
#define LCD_INTMSK_FUFIM_SHIFT (1) /* Bit 1: FIFO underflow interrupt enable */
@@ -228,7 +219,6 @@
#define LCD_INTMSK_BERIM_SHIFT (4) /* Bit 4: AHB Master error interrupt enable */
#define LCD_INTMSK_BERIM_MASK (1 << LCD_INTMSK_BERIM_SHIFT)
/* Bits 5-31: Reserved */
-
/* LCD_INTRAW - Raw Interrupt Status Register */
/* Bits 0: Reserved */
#define LCD_INTRAW_FUFRIS_SHIFT (1) /* Bit 1: FIFO Undeflow raw interrupt status */
@@ -240,7 +230,6 @@
#define LCD_INTRAW_BERRAW_SHIFT (4) /* Bit 4: AHB Master bus error interrupt status */
#define LCD_INTRAW_BERRAW_MASK (1 << LCD_INTRAW_BERRAW_SHIFT)
/* Bits 5-31: Reserved */
-
/* LCD_INTSTAT - Masked Interrupt Status Register */
/* Bits 0: Reserved */
#define LCD_INTSTAT_FUFMIS_SHIFT (1) /* Bit 1: FIFO Undeflow raw interrupt status */
@@ -265,7 +254,7 @@
/* Bits 15-31: Reserved */
/* Upper and Lower Panel Address register has no bitfields */
- /*
+/*
* Upper Panel Current Address register (LCDUPCURR)
* Lower Panel Current Address register (LCDLPCURR)
*/
@@ -339,7 +328,6 @@
#define LCD_CRSR_PAL1_BLUE_SHIFT (16) /* Bits 16-23: Blue color component */
#define LCD_CRSR_PAL1_BLUE_MASK (0xff << LCD_CRSR_PAL1_BLUE_SHIFT)
/* Bit 24-31: Reserved */
-
/* LCD CRSR_XY - Cursor XY Position Register */
#define LCD_CRSR_CRSRX_SHIFT (0) /* Bits 0-9: X ordinate */
@@ -348,7 +336,6 @@
#define LCD_CRSR_CRSRY_SHIFT (16) /* Bits 16-25: Y ordinate */
#define LCD_CRSR_CRSRY_MASK (0x3ff << LCD_CRSR_CRSRY_SHIFT)
/* Bit 26-31: Reserved */
-
/* LCD CRSR_CLIP - Cursor Clip Position Register */
#define LCD_CRSR_CRSRCLIPX_SHIFT (0) /* Bits 0-5: X clip position */
@@ -357,13 +344,11 @@
#define LCD_CRSR_CRSRCLIPY_SHIFT (8) /* Bits 8-13: Reserved */
#define LCD_CRSR_CRSRCLIPY_MASK (0x3f << LCD_CRSR_CRSRCLIPY_SHIFT)
/* Bit 14-31: Reserved */
-
/* LCD CRSR_INTMSK - Cursor Interrrupt Mask Register */
#define LCD_CRSR_INTMSK_CRSRIM_SHIFT (0) /* Bit 0: Cursor interrupt mask */
#define LCD_CRSR_INTMSK_CRSRIM_MASK (1 << LCD_CRSR_INTMSK_CRSRIM_SHIFT)
/* Bit 1-31: Reserved */
-
/* LCD CRSR_INTCLR - Cursor Interrrupt Clear Register */
#define LCD_CRSR_INTCLR_CRSRIC_SHIFT (0) /* Bit 0: Cursor interrupt clear */
@@ -375,7 +360,6 @@
#define LCD_CRSR_INTRAW_CRSRRIS_SHIFT (0) /* Bit 0: Cursor raw interrupt status */
#define LCD_CRSR_INTRAW_CRSRRIS_MASK (1 << LCD_CRSR_INTRAW_CRSRRIS_SHIFT)
/* Bit 1-31: Reserved */
-
/* LCD CRSR_INTSTAT - Mask Interrrupt Status Register */
#define LCD_CRSR_INTSTAT_CRSRMIS_SHIFT (0) /* Bit 0: Cursor mask interrupt status */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_pwm.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_pwm.h
index 8a7931104..49440a682 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc17_pwm.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc17_pwm.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/lpc17xx/chip/lpc17_pwm.h
*
- * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -41,13 +41,173 @@
************************************************************************************/
#include <nuttx/config.h>
-#include "chip/lpc17_pwm.h"
-#include "chip/lpc17_mcpwm.h"
+
+#include "chip.h"
+#include "chip/lpc17_memorymap.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
+/* Register offsets *****************************************************************/
+
+#define LPC17_PWM_IR_OFFSET 0x0000 /* Interrupt Register */
+#define LPC17_PWM_TCR_OFFSET 0x0004 /* Timer Control Register */
+#define LPC17_PWM_TC_OFFSET 0x0008 /* Timer Counter */
+#define LPC17_PWM_PR_OFFSET 0x000c /* Prescale Register */
+#define LPC17_PWM_PC_OFFSET 0x0010 /* Prescale Counter */
+#define LPC17_PWM_MCR_OFFSET 0x0014 /* Match Control Register */
+#define LPC17_PWM_MR0_OFFSET 0x0018 /* Match Register 0 */
+#define LPC17_PWM_MR1_OFFSET 0x001c /* Match Register 1 */
+#define LPC17_PWM_MR2_OFFSET 0x0020 /* Match Register 2 */
+#define LPC17_PWM_MR3_OFFSET 0x0024 /* Match Register 3 */
+#define LPC17_PWM_CCR_OFFSET 0x0028 /* Capture Control Register */
+#define LPC17_PWM_CR0_OFFSET 0x002c /* Capture Register 0 */
+#define LPC17_PWM_CR1_OFFSET 0x0030 /* Capture Register 1 */
+#define LPC17_PWM_CR2_OFFSET 0x0034 /* Capture Register 2 */
+#define LPC17_PWM_CR3_OFFSET 0x0038 /* Capture Register 3 */
+#define LPC17_PWM_MR4_OFFSET 0x0040 /* Match Register 4 */
+#define LPC17_PWM_MR5_OFFSET 0x0044 /* Match Register 5 */
+#define LPC17_PWM_MR6_OFFSET 0x0048 /* Match Register 6 */
+#define LPC17_PWM_PCR_OFFSET 0x004c /* PWM Control Register */
+#define LPC17_PWM_LER_OFFSET 0x0050 /* Load Enable Register */
+#define LPC17_PWM_CTCR_OFFSET 0x0070 /* Counter/Timer Control Register */
+
+/* Register addresses ***************************************************************/
+
+#define LPC17_PWM1_IR (LPC17_PWM1_BASE+LPC17_PWM_IR_OFFSET)
+#define LPC17_PWM1_TCR (LPC17_PWM1_BASE+LPC17_PWM_TCR_OFFSET)
+#define LPC17_PWM1_TC (LPC17_PWM1_BASE+LPC17_PWM_TC_OFFSET)
+#define LPC17_PWM1_PR (LPC17_PWM1_BASE+LPC17_PWM_PR_OFFSET)
+#define LPC17_PWM1_PC (LPC17_PWM1_BASE+LPC17_PWM_PC_OFFSET)
+#define LPC17_PWM1_MCR (LPC17_PWM1_BASE+LPC17_PWM_MCR_OFFSET)
+#define LPC17_PWM1_MR0 (LPC17_PWM1_BASE+LPC17_PWM_MR0_OFFSET)
+#define LPC17_PWM1_MR1 (LPC17_PWM1_BASE+LPC17_PWM_MR1_OFFSET)
+#define LPC17_PWM1_MR2 (LPC17_PWM1_BASE+LPC17_PWM_MR2_OFFSET)
+#define LPC17_PWM1_MR3 (LPC17_PWM1_BASE+LPC17_PWM_MR3_OFFSET)
+#define LPC17_PWM1_MR4 (LPC17_PWM1_BASE+LPC17_PWM_MR4_OFFSET)
+#define LPC17_PWM1_MR5 (LPC17_PWM1_BASE+LPC17_PWM_MR5_OFFSET)
+#define LPC17_PWM1_MR6 (LPC17_PWM1_BASE+LPC17_PWM_MR6_OFFSET)
+#define LPC17_PWM1_CCR (LPC17_PWM1_BASE+LPC17_PWM_CCR_OFFSET)
+#define LPC17_PWM1_CR0 (LPC17_PWM1_BASE+LPC17_PWM_CR0_OFFSET)
+#define LPC17_PWM1_CR1 (LPC17_PWM1_BASE+LPC17_PWM_CR1_OFFSET)
+#define LPC17_PWM1_CR2 (LPC17_PWM1_BASE+LPC17_PWM_CR2_OFFSET)
+#define LPC17_PWM1_CR3 (LPC17_PWM1_BASE+LPC17_PWM_CR3_OFFSET)
+#define LPC17_PWM1_PCR (LPC17_PWM1_BASE+LPC17_PWM_PCR_OFFSET)
+#define LPC17_PWM1_LER (LPC17_PWM1_BASE+LPC17_PWM_LER_OFFSET)
+#define LPC17_PWM1_CTCR (LPC17_PWM1_BASE+LPC17_PWM_CTCR_OFFSET)
+
+/* Register bit definitions *********************************************************/
+/* Registers holding 32-bit numeric values (no bit field definitions):
+ *
+ * Timer Counter (TC)
+ * Prescale Register (PR)
+ * Prescale Counter (PC)
+ * Match Register 0 (MR0)
+ * Match Register 1 (MR1)
+ * Match Register 2 (MR2)
+ * Match Register 3 (MR3)
+ * Match Register 4 (MR3)
+ * Match Register 5 (MR3)
+ * Match Register 6 (MR3)
+ * Capture Register 0 (CR0)
+ * Capture Register 1 (CR1)
+ * Capture Register 1 (CR2)
+ * Capture Register 1 (CR3)
+ */
+
+/* Interrupt Register */
+
+#define PWM_IR_MR0 (1 << 0) /* Bit 0: PWM match channel 0 interrrupt */
+#define PWM_IR_MR1 (1 << 1) /* Bit 1: PWM match channel 1 interrrupt */
+#define PWM_IR_MR2 (1 << 2) /* Bit 2: PWM match channel 2 interrrupt */
+#define PWM_IR_MR3 (1 << 3) /* Bit 3: PWM match channel 3 interrrupt */
+#define PWM_IR_CAP0 (1 << 4) /* Bit 4: Capture input 0 interrrupt */
+#define PWM_IR_CAP1 (1 << 5) /* Bit 5: Capture input 1 interrrupt */
+ /* Bits 6-7: Reserved */
+#define PWM_IR_MR4 (1 << 8) /* Bit 8: PWM match channel 4 interrrupt */
+#define PWM_IR_MR5 (1 << 9) /* Bit 9: PWM match channel 5 interrrupt */
+#define PWM_IR_MR6 (1 << 10) /* Bit 10: PWM match channel 6 interrrupt */
+ /* Bits 11-31: Reserved */
+/* Timer Control Register */
+
+#define PWM_TCR_CNTREN (1 << 0) /* Bit 0: Counter Enable */
+#define PWM_TCR_CNTRRST (1 << 1) /* Bit 1: Counter Reset */
+ /* Bit 2: Reserved */
+#define PWM_TCR_PWMEN (1 << 3) /* Bit 3: PWM Enable */
+ /* Bits 4-31: Reserved */
+/* Match Control Register */
+
+#define PWM_MCR_MR0I (1 << 0) /* Bit 0: Interrupt on MR0 */
+#define PWM_MCR_MR0R (1 << 1) /* Bit 1: Reset on MR0 */
+#define PWM_MCR_MR0S (1 << 2) /* Bit 2: Stop on MR0 */
+#define PWM_MCR_MR1I (1 << 3) /* Bit 3: Interrupt on MR1 */
+#define PWM_MCR_MR1R (1 << 4) /* Bit 4: Reset on MR1 */
+#define PWM_MCR_MR1S (1 << 5) /* Bit 5: Stop on MR1 */
+#define PWM_MCR_MR2I (1 << 6) /* Bit 6: Interrupt on MR2 */
+#define PWM_MCR_MR2R (1 << 7) /* Bit 7: Reset on MR2 */
+#define PWM_MCR_MR2S (1 << 8) /* Bit 8: Stop on MR2 */
+#define PWM_MCR_MR3I (1 << 9) /* Bit 9: Interrupt on MR3 */
+#define PWM_MCR_MR3R (1 << 10) /* Bit 10: Reset on MR3 */
+#define PWM_MCR_MR3S (1 << 11) /* Bit 11: Stop on MR3 */
+#define PWM_MCR_MR4I (1 << 12) /* Bit 12: Interrupt on MR4 */
+#define PWM_MCR_MR4R (1 << 13) /* Bit 13: Reset on MR4 */
+#define PWM_MCR_MR4S (1 << 14) /* Bit 14: Stop on MR4 */
+#define PWM_MCR_MR5I (1 << 15) /* Bit 15: Interrupt on MR5 */
+#define PWM_MCR_MR5R (1 << 16) /* Bit 16: Reset on MR5*/
+#define PWM_MCR_MR5S (1 << 17) /* Bit 17: Stop on MR5 */
+#define PWM_MCR_MR6I (1 << 18) /* Bit 18: Interrupt on MR6 */
+#define PWM_MCR_MR6R (1 << 19) /* Bit 19: Reset on MR6 */
+#define PWM_MCR_MR6S (1 << 20) /* Bit 20: Stop on MR6 */
+ /* Bits 21-31: Reserved */
+/* Capture Control Register (Where are CAP2 and 3?) */
+
+#define PWM_CCR_CAP0RE (1 << 0) /* Bit 0: Capture on CAPn.0 rising edge */
+#define PWM_CCR_CAP0FE (1 << 1) /* Bit 1: Capture on CAPn.0 falling edg */
+#define PWM_CCR_CAP0I (1 << 2) /* Bit 2: Interrupt on CAPn.0 */
+#define PWM_CCR_CAP1RE (1 << 3) /* Bit 3: Capture on CAPn.1 rising edge */
+#define PWM_CCR_CAP1FE (1 << 4) /* Bit 4: Capture on CAPn.1 falling edg */
+#define PWM_CCR_CAP1I (1 << 5) /* Bit 5: Interrupt on CAPn.1 */
+ /* Bits 6-31: Reserved */
+/* PWM Control Register */
+ /* Bits 0-1: Reserved */
+#define PWM_PCR_SEL2 (1 << 2) /* Bit 2: PWM2 single edge controlled mode */
+#define PWM_PCR_SEL3 (1 << 3) /* Bit 3: PWM3 single edge controlled mode */
+#define PWM_PCR_SEL4 (1 << 4) /* Bit 4: PWM4 single edge controlled mode */
+#define PWM_PCR_SEL5 (1 << 5) /* Bit 5: PWM5 single edge controlled mode */
+#define PWM_PCR_SEL6 (1 << 6) /* Bit 6: PWM6 single edge controlled mode */
+ /* Bits 7-8: Reserved */
+#define PWM_PCR_ENA1 (1 << 9) /* Bit 9: Enable PWM1 output */
+#define PWM_PCR_ENA2 (1 << 10) /* Bit 10: Enable PWM2 output */
+#define PWM_PCR_ENA3 (1 << 11) /* Bit 11: Enable PWM3 output */
+#define PWM_PCR_ENA4 (1 << 12) /* Bit 12: Enable PWM4 output */
+#define PWM_PCR_ENA5 (1 << 13) /* Bit 13: Enable PWM5 output */
+#define PWM_PCR_ENA6 (1 << 14) /* Bit 14: Enable PWM6 output */
+ /* Bits 15-31: Reserved */
+/* Load Enable Register */
+
+#define PWM_LER_M0EN (1 << 0) /* Bit 0: Enable PWM Match 0 Latch */
+#define PWM_LER_M1EN (1 << 1) /* Bit 1: Enable PWM Match 1 Latch */
+#define PWM_LER_M2EN (1 << 2) /* Bit 2: Enable PWM Match 2 Latch */
+#define PWM_LER_M3EN (1 << 3) /* Bit 3: Enable PWM Match 3 Latch */
+#define PWM_LER_M4EN (1 << 4) /* Bit 4: Enable PWM Match 4 Latch */
+#define PWM_LER_M5EN (1 << 5) /* Bit 5: Enable PWM Match 5 Latch */
+#define PWM_LER_M6EN (1 << 6) /* Bit 6: Enable PWM Match 6 Latch */
+ /* Bits 7-31: Reserved */
+/* Counter/Timer Control Register */
+
+#define PWM_CTCR_MODE_SHIFT (0) /* Bits 0-1: Counter/Timer Mode */
+#define PWM_CTCR_MODE_MASK (3 << PWM_CTCR_MODE_SHIFT)
+# define PWM_CTCR_MODE_TIMER (0 << PWM_CTCR_MODE_SHIFT) /* Timer Mode, prescal match */
+# define PWM_CTCR_MODE_CNTRRE (1 << PWM_CTCR_MODE_SHIFT) /* Counter Mode, CAP rising edge */
+# define PWM_CTCR_MODE_CNTRFE (2 << PWM_CTCR_MODE_SHIFT) /* Counter Mode, CAP falling edge */
+# define PWM_CTCR_MODE_CNTRBE (3 << PWM_CTCR_MODE_SHIFT) /* Counter Mode, CAP both edges */
+#define PWM_CTCR_INPSEL_SHIFT (2) /* Bits 2-3: Count Input Select */
+#define PWM_CTCR_INPSEL_MASK (3 << PWM_CTCR_INPSEL_SHIFT)
+# define PWM_CTCR_INPSEL_CAPNp0 (0 << PWM_CTCR_INPSEL_SHIFT) /* CAPn.0 for TIMERn */
+# define PWM_CTCR_INPSEL_CAPNp1 (1 << PWM_CTCR_INPSEL_SHIFT) /* CAPn.0 for TIMERn */
+ /* Bits 4-31: Reserved */
+
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_pwm.h b/nuttx/arch/arm/src/lpc17xx/lpc17_pwm.h
index d16c61210..f0f26cea0 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_pwm.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_pwm.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/lpc17xx/lpc17_pwm.h
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -41,173 +41,13 @@
************************************************************************************/
#include <nuttx/config.h>
-
-#include "chip.h"
-#include "chip/lpc17_memorymap.h"
+#include "chip/lpc17_pwm.h"
+#include "chip/lpc17_mcpwm.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
-/* Register offsets *****************************************************************/
-
-#define LPC17_PWM_IR_OFFSET 0x0000 /* Interrupt Register */
-#define LPC17_PWM_TCR_OFFSET 0x0004 /* Timer Control Register */
-#define LPC17_PWM_TC_OFFSET 0x0008 /* Timer Counter */
-#define LPC17_PWM_PR_OFFSET 0x000c /* Prescale Register */
-#define LPC17_PWM_PC_OFFSET 0x0010 /* Prescale Counter */
-#define LPC17_PWM_MCR_OFFSET 0x0014 /* Match Control Register */
-#define LPC17_PWM_MR0_OFFSET 0x0018 /* Match Register 0 */
-#define LPC17_PWM_MR1_OFFSET 0x001c /* Match Register 1 */
-#define LPC17_PWM_MR2_OFFSET 0x0020 /* Match Register 2 */
-#define LPC17_PWM_MR3_OFFSET 0x0024 /* Match Register 3 */
-#define LPC17_PWM_CCR_OFFSET 0x0028 /* Capture Control Register */
-#define LPC17_PWM_CR0_OFFSET 0x002c /* Capture Register 0 */
-#define LPC17_PWM_CR1_OFFSET 0x0030 /* Capture Register 1 */
-#define LPC17_PWM_CR2_OFFSET 0x0034 /* Capture Register 2 */
-#define LPC17_PWM_CR3_OFFSET 0x0038 /* Capture Register 3 */
-#define LPC17_PWM_MR4_OFFSET 0x0040 /* Match Register 4 */
-#define LPC17_PWM_MR5_OFFSET 0x0044 /* Match Register 5 */
-#define LPC17_PWM_MR6_OFFSET 0x0048 /* Match Register 6 */
-#define LPC17_PWM_PCR_OFFSET 0x004c /* PWM Control Register */
-#define LPC17_PWM_LER_OFFSET 0x0050 /* Load Enable Register */
-#define LPC17_PWM_CTCR_OFFSET 0x0070 /* Counter/Timer Control Register */
-
-/* Register addresses ***************************************************************/
-
-#define LPC17_PWM1_IR (LPC17_PWM1_BASE+LPC17_PWM_IR_OFFSET)
-#define LPC17_PWM1_TCR (LPC17_PWM1_BASE+LPC17_PWM_TCR_OFFSET)
-#define LPC17_PWM1_TC (LPC17_PWM1_BASE+LPC17_PWM_TC_OFFSET)
-#define LPC17_PWM1_PR (LPC17_PWM1_BASE+LPC17_PWM_PR_OFFSET)
-#define LPC17_PWM1_PC (LPC17_PWM1_BASE+LPC17_PWM_PC_OFFSET)
-#define LPC17_PWM1_MCR (LPC17_PWM1_BASE+LPC17_PWM_MCR_OFFSET)
-#define LPC17_PWM1_MR0 (LPC17_PWM1_BASE+LPC17_PWM_MR0_OFFSET)
-#define LPC17_PWM1_MR1 (LPC17_PWM1_BASE+LPC17_PWM_MR1_OFFSET)
-#define LPC17_PWM1_MR2 (LPC17_PWM1_BASE+LPC17_PWM_MR2_OFFSET)
-#define LPC17_PWM1_MR3 (LPC17_PWM1_BASE+LPC17_PWM_MR3_OFFSET)
-#define LPC17_PWM1_MR4 (LPC17_PWM1_BASE+LPC17_PWM_MR4_OFFSET)
-#define LPC17_PWM1_MR5 (LPC17_PWM1_BASE+LPC17_PWM_MR5_OFFSET)
-#define LPC17_PWM1_MR6 (LPC17_PWM1_BASE+LPC17_PWM_MR6_OFFSET)
-#define LPC17_PWM1_CCR (LPC17_PWM1_BASE+LPC17_PWM_CCR_OFFSET)
-#define LPC17_PWM1_CR0 (LPC17_PWM1_BASE+LPC17_PWM_CR0_OFFSET)
-#define LPC17_PWM1_CR1 (LPC17_PWM1_BASE+LPC17_PWM_CR1_OFFSET)
-#define LPC17_PWM1_CR2 (LPC17_PWM1_BASE+LPC17_PWM_CR2_OFFSET)
-#define LPC17_PWM1_CR3 (LPC17_PWM1_BASE+LPC17_PWM_CR3_OFFSET)
-#define LPC17_PWM1_PCR (LPC17_PWM1_BASE+LPC17_PWM_PCR_OFFSET)
-#define LPC17_PWM1_LER (LPC17_PWM1_BASE+LPC17_PWM_LER_OFFSET)
-#define LPC17_PWM1_CTCR (LPC17_PWM1_BASE+LPC17_PWM_CTCR_OFFSET)
-
-/* Register bit definitions *********************************************************/
-/* Registers holding 32-bit numeric values (no bit field definitions):
- *
- * Timer Counter (TC)
- * Prescale Register (PR)
- * Prescale Counter (PC)
- * Match Register 0 (MR0)
- * Match Register 1 (MR1)
- * Match Register 2 (MR2)
- * Match Register 3 (MR3)
- * Match Register 4 (MR3)
- * Match Register 5 (MR3)
- * Match Register 6 (MR3)
- * Capture Register 0 (CR0)
- * Capture Register 1 (CR1)
- * Capture Register 1 (CR2)
- * Capture Register 1 (CR3)
- */
-
-/* Interrupt Register */
-
-#define PWM_IR_MR0 (1 << 0) /* Bit 0: PWM match channel 0 interrrupt */
-#define PWM_IR_MR1 (1 << 1) /* Bit 1: PWM match channel 1 interrrupt */
-#define PWM_IR_MR2 (1 << 2) /* Bit 2: PWM match channel 2 interrrupt */
-#define PWM_IR_MR3 (1 << 3) /* Bit 3: PWM match channel 3 interrrupt */
-#define PWM_IR_CAP0 (1 << 4) /* Bit 4: Capture input 0 interrrupt */
-#define PWM_IR_CAP1 (1 << 5) /* Bit 5: Capture input 1 interrrupt */
- /* Bits 6-7: Reserved */
-#define PWM_IR_MR4 (1 << 8) /* Bit 8: PWM match channel 4 interrrupt */
-#define PWM_IR_MR5 (1 << 9) /* Bit 9: PWM match channel 5 interrrupt */
-#define PWM_IR_MR6 (1 << 10) /* Bit 10: PWM match channel 6 interrrupt */
- /* Bits 11-31: Reserved */
-/* Timer Control Register */
-
-#define PWM_TCR_CNTREN (1 << 0) /* Bit 0: Counter Enable */
-#define PWM_TCR_CNTRRST (1 << 1) /* Bit 1: Counter Reset */
- /* Bit 2: Reserved */
-#define PWM_TCR_PWMEN (1 << 3) /* Bit 3: PWM Enable */
- /* Bits 4-31: Reserved */
-/* Match Control Register */
-
-#define PWM_MCR_MR0I (1 << 0) /* Bit 0: Interrupt on MR0 */
-#define PWM_MCR_MR0R (1 << 1) /* Bit 1: Reset on MR0 */
-#define PWM_MCR_MR0S (1 << 2) /* Bit 2: Stop on MR0 */
-#define PWM_MCR_MR1I (1 << 3) /* Bit 3: Interrupt on MR1 */
-#define PWM_MCR_MR1R (1 << 4) /* Bit 4: Reset on MR1 */
-#define PWM_MCR_MR1S (1 << 5) /* Bit 5: Stop on MR1 */
-#define PWM_MCR_MR2I (1 << 6) /* Bit 6: Interrupt on MR2 */
-#define PWM_MCR_MR2R (1 << 7) /* Bit 7: Reset on MR2 */
-#define PWM_MCR_MR2S (1 << 8) /* Bit 8: Stop on MR2 */
-#define PWM_MCR_MR3I (1 << 9) /* Bit 9: Interrupt on MR3 */
-#define PWM_MCR_MR3R (1 << 10) /* Bit 10: Reset on MR3 */
-#define PWM_MCR_MR3S (1 << 11) /* Bit 11: Stop on MR3 */
-#define PWM_MCR_MR4I (1 << 12) /* Bit 12: Interrupt on MR4 */
-#define PWM_MCR_MR4R (1 << 13) /* Bit 13: Reset on MR4 */
-#define PWM_MCR_MR4S (1 << 14) /* Bit 14: Stop on MR4 */
-#define PWM_MCR_MR5I (1 << 15) /* Bit 15: Interrupt on MR5 */
-#define PWM_MCR_MR5R (1 << 16) /* Bit 16: Reset on MR5*/
-#define PWM_MCR_MR5S (1 << 17) /* Bit 17: Stop on MR5 */
-#define PWM_MCR_MR6I (1 << 18) /* Bit 18: Interrupt on MR6 */
-#define PWM_MCR_MR6R (1 << 19) /* Bit 19: Reset on MR6 */
-#define PWM_MCR_MR6S (1 << 20) /* Bit 20: Stop on MR6 */
- /* Bits 21-31: Reserved */
-/* Capture Control Register (Where are CAP2 and 3?) */
-
-#define PWM_CCR_CAP0RE (1 << 0) /* Bit 0: Capture on CAPn.0 rising edge */
-#define PWM_CCR_CAP0FE (1 << 1) /* Bit 1: Capture on CAPn.0 falling edg */
-#define PWM_CCR_CAP0I (1 << 2) /* Bit 2: Interrupt on CAPn.0 */
-#define PWM_CCR_CAP1RE (1 << 3) /* Bit 3: Capture on CAPn.1 rising edge */
-#define PWM_CCR_CAP1FE (1 << 4) /* Bit 4: Capture on CAPn.1 falling edg */
-#define PWM_CCR_CAP1I (1 << 5) /* Bit 5: Interrupt on CAPn.1 */
- /* Bits 6-31: Reserved */
-/* PWM Control Register */
- /* Bits 0-1: Reserved */
-#define PWM_PCR_SEL2 (1 << 2) /* Bit 2: PWM2 single edge controlled mode */
-#define PWM_PCR_SEL3 (1 << 3) /* Bit 3: PWM3 single edge controlled mode */
-#define PWM_PCR_SEL4 (1 << 4) /* Bit 4: PWM4 single edge controlled mode */
-#define PWM_PCR_SEL5 (1 << 5) /* Bit 5: PWM5 single edge controlled mode */
-#define PWM_PCR_SEL6 (1 << 6) /* Bit 6: PWM6 single edge controlled mode */
- /* Bits 7-8: Reserved */
-#define PWM_PCR_ENA1 (1 << 9) /* Bit 9: Enable PWM1 output */
-#define PWM_PCR_ENA2 (1 << 10) /* Bit 10: Enable PWM2 output */
-#define PWM_PCR_ENA3 (1 << 11) /* Bit 11: Enable PWM3 output */
-#define PWM_PCR_ENA4 (1 << 12) /* Bit 12: Enable PWM4 output */
-#define PWM_PCR_ENA5 (1 << 13) /* Bit 13: Enable PWM5 output */
-#define PWM_PCR_ENA6 (1 << 14) /* Bit 14: Enable PWM6 output */
- /* Bits 15-31: Reserved */
-/* Load Enable Register */
-
-#define PWM_LER_M0EN (1 << 0) /* Bit 0: Enable PWM Match 0 Latch */
-#define PWM_LER_M1EN (1 << 1) /* Bit 1: Enable PWM Match 1 Latch */
-#define PWM_LER_M2EN (1 << 2) /* Bit 2: Enable PWM Match 2 Latch */
-#define PWM_LER_M3EN (1 << 3) /* Bit 3: Enable PWM Match 3 Latch */
-#define PWM_LER_M4EN (1 << 4) /* Bit 4: Enable PWM Match 4 Latch */
-#define PWM_LER_M5EN (1 << 5) /* Bit 5: Enable PWM Match 5 Latch */
-#define PWM_LER_M6EN (1 << 6) /* Bit 6: Enable PWM Match 6 Latch */
- /* Bits 7-31: Reserved */
-/* Counter/Timer Control Register */
-
-#define PWM_CTCR_MODE_SHIFT (0) /* Bits 0-1: Counter/Timer Mode */
-#define PWM_CTCR_MODE_MASK (3 << PWM_CTCR_MODE_SHIFT)
-# define PWM_CTCR_MODE_TIMER (0 << PWM_CTCR_MODE_SHIFT) /* Timer Mode, prescal match */
-# define PWM_CTCR_MODE_CNTRRE (1 << PWM_CTCR_MODE_SHIFT) /* Counter Mode, CAP rising edge */
-# define PWM_CTCR_MODE_CNTRFE (2 << PWM_CTCR_MODE_SHIFT) /* Counter Mode, CAP falling edge */
-# define PWM_CTCR_MODE_CNTRBE (3 << PWM_CTCR_MODE_SHIFT) /* Counter Mode, CAP both edges */
-#define PWM_CTCR_INPSEL_SHIFT (2) /* Bits 2-3: Count Input Select */
-#define PWM_CTCR_INPSEL_MASK (3 << PWM_CTCR_INPSEL_SHIFT)
-# define PWM_CTCR_INPSEL_CAPNp0 (0 << PWM_CTCR_INPSEL_SHIFT) /* CAPn.0 for TIMERn */
-# define PWM_CTCR_INPSEL_CAPNp1 (1 << PWM_CTCR_INPSEL_SHIFT) /* CAPn.0 for TIMERn */
- /* Bits 4-31: Reserved */
-
/************************************************************************************
* Public Types
************************************************************************************/