summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-04-12 18:03:56 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-04-12 18:03:56 +0000
commit303ccdfdf00ec6d9bdc7b369b5e8338e4a9742bf (patch)
treee7a3a394109ab84701581cc257419ae344b2d866 /nuttx
parent0162245b27eb72c2973c587e5ea59317b43b88bd (diff)
downloadpx4-nuttx-303ccdfdf00ec6d9bdc7b369b5e8338e4a9742bf.tar.gz
px4-nuttx-303ccdfdf00ec6d9bdc7b369b5e8338e4a9742bf.tar.bz2
px4-nuttx-303ccdfdf00ec6d9bdc7b369b5e8338e4a9742bf.zip
Clean up clocking
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1698 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/include/imx/irq.h50
-rw-r--r--nuttx/arch/arm/src/imx/chip.h1
-rw-r--r--nuttx/arch/arm/src/imx/imx_boot.c29
-rwxr-xr-xnuttx/arch/arm/src/imx/imx_eim.h85
-rw-r--r--nuttx/arch/arm/src/imx/imx_memorymap.h27
-rw-r--r--nuttx/arch/arm/src/imx/imx_serial.c15
-rwxr-xr-xnuttx/arch/arm/src/imx/imx_system.h58
-rw-r--r--nuttx/configs/mx1ads/include/board.h97
-rw-r--r--nuttx/configs/mx1ads/src/Makefile2
-rwxr-xr-xnuttx/configs/mx1ads/src/up_boot.c105
10 files changed, 427 insertions, 42 deletions
diff --git a/nuttx/arch/arm/include/imx/irq.h b/nuttx/arch/arm/include/imx/irq.h
index 3559a8f05..c2fd93d89 100644
--- a/nuttx/arch/arm/include/imx/irq.h
+++ b/nuttx/arch/arm/include/imx/irq.h
@@ -50,23 +50,29 @@
/* i.MX1 Interrupts */
-#define IMX_IRQ_UART3PFERR ( 0)
-#define IMX_IRQ_UART3RTS ( 1)
-#define IMX_IRQ_UART3DTR ( 2)
-#define IMX_IRQ_UART3UARTC ( 3)
-#define IMX_IRQ_UART3TX ( 4)
-#define IMX_IRQ_PENUP ( 5)
+#ifndef CONFIG_ARCH_CHIP_IMXL
+# define IMX_IRQ_UART3PFERR ( 0)
+# define IMX_IRQ_UART3RTS ( 1)
+# define IMX_IRQ_UART3DTR ( 2)
+# define IMX_IRQ_UART3UARTC ( 3)
+# define IMX_IRQ_UART3TX ( 4)
+# define IMX_IRQ_PENUP ( 5)
+#endif
#define IMX_IRQ_CSI ( 6)
#define IMX_IRQ_MMAMAC ( 7)
#define IMX_IRQ_MMA ( 8)
-#define IMX_IRQ_COMP ( 9)
+#ifndef CONFIG_ARCH_CHIP_IMXL
+# define IMX_IRQ_COMP ( 9)
+#endif
#define IMX_IRQ_MSHCXINT (10)
#define IMX_IRQ_GPIOPORTA (11)
#define IMX_IRQ_GPIOPORTB (12)
#define IMX_IRQ_GPIOPORTC (13)
#define IMX_IRQ_LCDC (14)
-#define IMX_IRQ_SIM (15)
-#define IMX_IRQ_SIMDATA (16)
+#ifndef CONFIG_ARCH_CHIP_IMXL
+# define IMX_IRQ_SIM (15)
+# define IMX_IRQ_SIMDATA (16)
+#endif
#define IMX_IRQ_RTC (17)
#define IMX_IRQ_RTCSAMINT (18)
#define IMX_IRQ_UART2PFERR (19)
@@ -81,12 +87,16 @@
#define IMX_IRQ_UART1UARTC (28)
#define IMX_IRQ_UART1TX (29)
#define IMX_IRQ_UART1RX (30)
-#define IMX_IRQ_PENDATA (33)
+#ifndef CONFIG_ARCH_CHIP_IMXL
+# define IMX_IRQ_PENDATA (33)
+#endif
#define IMX_IRQ_PWM (34)
#define IMX_IRQ_MMCSD (35)
-#define IMX_IRQ_SSI2TX (36)
-#define IMX_IRQ_SSI2RX (37)
-#define IMX_IRQ_SSI2ERR (38)
+#ifndef CONFIG_ARCH_CHIP_IMXL
+# define IMX_IRQ_SSI2TX (36)
+# define IMX_IRQ_SSI2RX (37)
+# define IMX_IRQ_SSI2ERR (38)
+#endif
#define IMX_IRQ_I2C (39)
#define IMX_IRQ_CSPI2 (40)
#define IMX_IRQ_CSPI1 (41)
@@ -94,7 +104,9 @@
#define IMX_IRQ_SSITXERR (43)
#define IMX_IRQ_SSIRX (44)
#define IMX_IRQ_SSIRXERR (45)
-#define IMX_IRQ_TOUCH (46)
+#ifndef CONFIG_ARCH_CHIP_IMXL
+# define IMX_IRQ_TOUCH (46)
+#endif
#define IMX_IRQ_USBD0 (47)
#define IMX_IRQ_USBD1 (48)
#define IMX_IRQ_USBD2 (49)
@@ -102,10 +114,12 @@
#define IMX_IRQ_USBD4 (51)
#define IMX_IRQ_USBD5 (52)
#define IMX_IRQ_USBD6 (53)
-#define IMX_IRQ_UART3RX (54)
-#define IMX_IRQ_BTSYS (55)
-#define IMX_IRQ_BTTIM (56)
-#define IMX_IRQ_BTWUI (57)
+#ifndef CONFIG_ARCH_CHIP_IMXL
+# define IMX_IRQ_UART3RX (54)
+# define IMX_IRQ_BTSYS (55)
+# define IMX_IRQ_BTTIM (56)
+# define IMX_IRQ_BTWUI (57)
+#endif
#define IMX_IRQ_TIMER2 (58)
#define IMX_IRQ_TIMER1 (59)
#define IMX_IRQ_DMAERR (60)
diff --git a/nuttx/arch/arm/src/imx/chip.h b/nuttx/arch/arm/src/imx/chip.h
index e9d17d246..00272ccdb 100644
--- a/nuttx/arch/arm/src/imx/chip.h
+++ b/nuttx/arch/arm/src/imx/chip.h
@@ -51,6 +51,7 @@
#include "imx_i2c.h"
#include "imx_cspi.h"
#include "imx_gpio.h"
+#include "imx_eim.h"
#include "imx_aitc.h"
/************************************************************************************
diff --git a/nuttx/arch/arm/src/imx/imx_boot.c b/nuttx/arch/arm/src/imx/imx_boot.c
index 88eb341ef..a463dcf34 100644
--- a/nuttx/arch/arm/src/imx/imx_boot.c
+++ b/nuttx/arch/arm/src/imx/imx_boot.c
@@ -71,17 +71,42 @@ extern uint32 _vector_end; /* End+1 of vector block */
* Private Variables
************************************************************************************/
+/* Mapping of the external memory regions will probably have to be made board
+ * specific.
+ */
+
static const struct section_mapping_s section_mapping[] =
{
{ IMX_PERIPHERALS_PSECTION, IMX_PERIPHERALS_VSECTION,
IMX_PERIPHERALS_MMUFLAGS, IMX_PERIPHERALS_NSECTIONS},
{ IMX_FLASH_PSECTION, IMX_FLASH_VSECTION,
IMX_FLASH_MMUFLAGS, IMX_FLASH_NSECTIONS},
+ { IMX_CS1_PSECTION, IMX_CS1_VSECTION,
+ IMX_PERIPHERALS_MMUFLAGS, IMX_CS1_NSECTIONS},
+ { IMX_CS2_PSECTION, IMX_CS2_VSECTION,
+ IMX_PERIPHERALS_MMUFLAGS, IMX_CS2_NSECTIONS},
+ { IMX_CS3_PSECTION, IMX_CS3_VSECTION,
+ IMX_PERIPHERALS_MMUFLAGS, IMX_CS3_NSECTIONS},
+ { IMX_CS4_PSECTION, IMX_CS4_VSECTION,
+ IMX_PERIPHERALS_MMUFLAGS, IMX_CS4_NSECTIONS},
+ { IMX_CS5_PSECTION, IMX_CS5_VSECTION,
+ IMX_PERIPHERALS_MMUFLAGS, IMX_CS5_NSECTIONS},
};
#define NMAPPINGS (sizeof(section_mapping) / sizeof(struct section_mapping_s))
/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+/* All i.MX architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ */
+
+extern void imx_boardinitialize(void);
+
+/************************************************************************************
* Private Functions
************************************************************************************/
@@ -181,4 +206,8 @@ void up_boot(void)
*/
up_copyvectorblock();
+
+ /* Perform board-specific initialiation */
+
+ imx_boardinitialize();
}
diff --git a/nuttx/arch/arm/src/imx/imx_eim.h b/nuttx/arch/arm/src/imx/imx_eim.h
new file mode 100755
index 000000000..50849794a
--- /dev/null
+++ b/nuttx/arch/arm/src/imx/imx_eim.h
@@ -0,0 +1,85 @@
+/************************************************************************************
+ * arch/arm/src/imx/imx_eim.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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_IMX_WIEM_H
+#define __ARCH_ARM_IMX_WIEM_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* EIM Register Offsets ************************************************************/
+
+#define EIM_CS0H_OFFSET 0x00
+#define EIM_CS0L_OFFSET 0x04
+#define EIM_CS1H_OFFSET 0x08
+#define EIM_CS1L_OFFSET 0x0c
+#define EIM_CS2H_OFFSET 0x10
+#define EIM_CS2L_OFFSET 0x14
+#define EIM_CS3H_OFFSET 0x18
+#define EIM_CS3L_OFFSET 0x1c
+#define EIM_CS4H_OFFSET 0x20
+#define EIM_CS4L_OFFSET 0x24
+#define EIM_CS5H_OFFSET 0x28
+#define EIM_CS5L_OFFSET 0x2c
+#define EIM_WEIM_OFFSET 0x30
+
+/* EIM Register Addresses ***********************************************************/
+
+#define IMX_EIM_CS0H (EIM_BASE_ADDR + EIM_CS0H_OFFSET)
+#define IMX_EIM_CS0L (EIM_BASE_ADDR + EIM_CS0L_OFFSET)
+#define IMX_EIM_CS1H (EIM_BASE_ADDR + EIM_CS1H_OFFSET)
+#define IMX_EIM_CS1L (EIM_BASE_ADDR + EIM_CS1L_OFFSET)
+#define IMX_EIM_CS2H (EIM_BASE_ADDR + EIM_CS2H_OFFSET)
+#define IMX_EIM_CS2L (EIM_BASE_ADDR + EIM_CS2L_OFFSET)
+#define IMX_EIM_CS3H (EIM_BASE_ADDR + EIM_CS3H_OFFSET)
+#define IMX_EIM_CS3L (EIM_BASE_ADDR + EIM_CS3L_OFFSET)
+#define IMX_EIM_CS4H (EIM_BASE_ADDR + EIM_CS4H_OFFSET)
+#define IMX_EIM_CS4L (EIM_BASE_ADDR + EIM_CS4L_OFFSET)
+#define IMX_EIM_CS5H (EIM_BASE_ADDR + EIM_CS5H_OFFSET)
+#define IMX_EIM_CS5L (EIM_BASE_ADDR + EIM_CS5L_OFFSET)
+#define IMX_EIM_WEIM (EIM_BASE_ADDR + EIM_WEIM_OFFSET)
+
+/* EIM Register Bit Definitions *****************************************************/
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_IMX_EIM_H */
diff --git a/nuttx/arch/arm/src/imx/imx_memorymap.h b/nuttx/arch/arm/src/imx/imx_memorymap.h
index 587744ef4..c25b44b9b 100644
--- a/nuttx/arch/arm/src/imx/imx_memorymap.h
+++ b/nuttx/arch/arm/src/imx/imx_memorymap.h
@@ -53,11 +53,11 @@
#define IMX_SDRAM0_PSECTION 0x08000000 /* -0x0bffffff SDRAM0 (CSD0) 64Mb */
#define IMX_SDRAM1_PSECTION 0x0c000000 /* -0x0fffffff SDRAM1 (CSD1) 64Mb */
#define IMX_FLASH_PSECTION 0x10000000 /* -0x11ffffff FLASH (CS0) 32Mb */
-#define IMX_CS1_PSECTION 0x12000000 /* -0x12ffffff CS1 32Mb */
-#define IMX_CS2_PSECTION 0x13000000 /* -0x13ffffff CS2 32Mb */
-#define IMX_CS3_PSECTION 0x14000000 /* -0x14ffffff CS3 32Mb */
-#define IMX_CS4_PSECTION 0x15000000 /* -0x15ffffff CS4 32Mb */
-#define IMX_CS5_PSECTION 0x16000000 /* -0x16ffffff CS5 32Mb */
+#define IMX_CS1_PSECTION 0x12000000 /* -0x12ffffff CS1 16Mb */
+#define IMX_CS2_PSECTION 0x13000000 /* -0x13ffffff CS2 16Mb */
+#define IMX_CS3_PSECTION 0x14000000 /* -0x14ffffff CS3 16Mb */
+#define IMX_CS4_PSECTION 0x15000000 /* -0x15ffffff CS4 16Mb */
+#define IMX_CS5_PSECTION 0x16000000 /* -0x16ffffff CS5 16Mb */
/* Sizes of Address Sections ********************************************************/
@@ -66,11 +66,11 @@
#define IMX_SDRAM0_NSECTIONS 16 /* 16Mb Based on CONFIG_DRAM_SIZE */
#define IMX_SDRAM1_NSECTIONS 0 /* 64Mb (Not mapped) */
#define IMX_FLASH_NSECTIONS 32 /* 64Mb Based on CONFIG_FLASH_SIZE */
-#define IMX_CS1_NSECTIONS 0 /* 32Mb (Not mapped) */
-#define IMX_CS2_NSECTIONS 0 /* 32Mb (Not mapped) */
-#define IMX_CS3_NSECTIONS 0 /* 32Mb (Not mapped) */
-#define IMX_CS4_NSECTIONS 0 /* 32Mb (Not mapped) */
-#define IMX_CS5_NSECTIONS 0 /* 32Mb (Not mapped) */
+#define IMX_CS1_NSECTIONS 16 /* 16Mb */
+#define IMX_CS2_NSECTIONS 16 /* 16Mb */
+#define IMX_CS3_NSECTIONS 16 /* 16Mb */
+#define IMX_CS4_NSECTIONS 16 /* 16Mb */
+#define IMX_CS5_NSECTIONS 16 /* 16Mb */
/* Virtual Memory Map ***************************************************************/
@@ -125,6 +125,11 @@
#define IMX_PERIPHERALS_VSECTION 0x00200000 /* -0x002fffff 1Mb */
#define IMX_FLASH_VSECTION 0x10000000 /* -(+CONFIG_FLASH_SIZE) */
+#define IMX_CS1_VSECTION 0x12000000 /* -0x12ffffff CS1 32Mb */
+#define IMX_CS2_VSECTION 0x13000000 /* -0x13ffffff CS2 32Mb */
+#define IMX_CS3_VSECTION 0x14000000 /* -0x14ffffff CS3 32Mb */
+#define IMX_CS4_VSECTION 0x15000000 /* -0x15ffffff CS4 32Mb */
+#define IMX_CS5_VSECTION 0x16000000 /* -0x16ffffff CS5 32Mb */
/* In any event, the vector base address is 0x0000:0000 */
@@ -161,7 +166,7 @@
#define IMX_SC_OFFSET 0x0001b800
#define IMX_GPIO_OFFSET 0x0001c000 /* -0x0001cfff GPIO 4Kb */
/* -0x0001ffff Reserved 12Kb */
-#define IMX_EIM_OFFSET 0x00020000 /* -0x00020fff WEIM 4Kb */
+#define IMX_EIM_OFFSET 0x00020000 /* -0x00020fff EIM 4Kb */
#define IMX_SDRAMC_OFFSET 0x00021000 /* -0x00021fff SDRAMC 4Kb */
#define IMX_DSPA_OFFSET 0x00022000 /* -0x00022fff DSPA 4Kb */
#define IMX_AITC_OFFSET 0x00023000 /* -0x00023fff AITC 4Kb */
diff --git a/nuttx/arch/arm/src/imx/imx_serial.c b/nuttx/arch/arm/src/imx/imx_serial.c
index cd18dc50e..aa5140c51 100644
--- a/nuttx/arch/arm/src/imx/imx_serial.c
+++ b/nuttx/arch/arm/src/imx/imx_serial.c
@@ -63,6 +63,14 @@
* Definitions
****************************************************************************/
+/* Configuration ************************************************************/
+
+/* The i.MXL chip has only two UARTs */
+
+#if defined(CONFIG_ARCH_CHIP_IMXL) && !defined(CONFIG_UART3_DISABLE)
+# define CONFIG_UART3_DISABLE 1
+#endif
+
/****************************************************************************
* Private Types
****************************************************************************/
@@ -497,6 +505,7 @@ static int up_setup(struct uart_dev_s *dev)
/* Setup hardware flow control */
+ regval = 0;
#if 0
if (priv->hwfc)
{
@@ -508,10 +517,14 @@ static int up_setup(struct uart_dev_s *dev)
/* Set CTS trigger level */
- up_serilout(priv, UART_UCR4, 30 << UART_UCR4_CTSTL_SHIFT);
+ regval |= 30 << UART_UCR4_CTSTL_SHIFT;
}
#endif
+ /* i.MX reference clock (PERCLK1) is configured for 16MHz */
+
+ up_serialout(priv, UART_UCR4, regval | UART_UCR4_REF16);
+
/* Setup the new UART configuration */
up_serialout(priv, UART_UCR2, ucr2);
diff --git a/nuttx/arch/arm/src/imx/imx_system.h b/nuttx/arch/arm/src/imx/imx_system.h
index ed3b4faa8..f5af05cd0 100755
--- a/nuttx/arch/arm/src/imx/imx_system.h
+++ b/nuttx/arch/arm/src/imx/imx_system.h
@@ -82,6 +82,64 @@
/* PLL Register Bit Definitions *****************************************************/
+#define PLL_CSCR_MPEN (1 << 0) /* Bit 0: 1 = MCU PLL enabled */
+#define PLL_CSCR_SPEN (1 << 1) /* Bit 1: System PLL Enable */
+#define PLL_CSCR_BCLKDIV_SHIFT 10 /* Bits 13–10: BClock Divider */
+#define PLL_CSCR_BCLKDIV_MASK (15 << PLL_CSCR_BCLK_DIV_SHIFT)
+#define PLL_CSCR_PRESC (1 << 15) /* Bit 15: MPU PLL clock prescaler */
+#define PLL_CSCR_SYSTEM_SEL (1 << 16) /* Bit 16: System clock source select */
+#define PLL_CSCR_OSCEN (1 << 17) /* Bit 17: Ext. 16MHz oscillator enable */
+#define PLL_CSCR_CLK16_SEL (1 << 18) /* Bit 18: Select BT ref RFBTCLK16 */
+#define PLL_CSCR_MPLLRESTART (1 << 21) /* Bit 21: MPLL Restart */
+#define PLL_CSCR_SPLLRESTART (1 << 22) /* Bit 22: SPLL Restart */
+#define PLL_CSCR_SDCNT_SHIFT 24 /* Bits 25–24: Shut-Down Control */
+#define PLL_CSCR_SDCNT_MASK (3 << PLL_CSCR_SDCNT_SHIFT)
+#define CSCR_SDCNT_2ndEDGE (1 << PLL_CSCR_SDCNT_SHIFT)
+#define CSCR_SDCNT_3rdEDGE (2 << PLL_CSCR_SDCNT_SHIFT)
+#define CSCR_SDCNT_4thEDGE (3 << PLL_CSCR_SDCNT_SHIFT)
+#define PLL_CSCR_USBDIV_SHIFT 28 /* Bits 28–26: USB Divider */
+#define PLL_CSCR_USBDIV_MASK (7 << PLL_CSCR_USB_DIV_SHIFT)
+#define PLL_CSCR_CLKOSEL_SHIFT 29 /* Bits 31–29: CLKO Select */
+#define PLL_CSCR_CLKOSEL_MASK (7 << PLL_CSCR_CLKOSEL_SHIFT)
+#define CSCR_CLKOSEL_PERCLK1 (0 << PLL_CSCR_CLKOSEL_SHIFT)
+#define CSCR_CLKOSEL_HCLK (1 << PLL_CSCR_CLKOSEL_SHIFT)
+#define CSCR_CLKOSEL_CLK48M (2 << PLL_CSCR_CLKOSEL_SHIFT)
+#define CSCR_CLKOSEL_CLK16M (3 << PLL_CSCR_CLKOSEL_SHIFT)
+#define CSCR_CLKOSEL_PREMCLK (4 << PLL_CSCR_CLKOSEL_SHIFT)
+#define CSCR_CLKOSEL_FCLK (5 << PLL_CSCR_CLKOSEL_SHIFT)
+
+#define PLL_MPCTL0_MFN_SHIFT 0 /* Bits 9–0: Multiplication Factor (Numerator) */
+#define PLL_MPCTL0_MFN_MASK (0x03ff << PLL_MPCTL0_MFN_SHIFT)
+#define PLL_MPCTL0_MFI_SHIFT 10 /* Bits 13–10: Multiplication Factor (Integer) */
+#define PLL_MPCTL0_MFI_MASK (0x0f << PLL_MPCTL0_MFI_SHIFT)
+#define PLL_MPCTL0_MFD_SHIFT 16 /* Bits 25–16: Multiplication Factor (Denominator) */
+#define PLL_MPCTL0_MFD_MASK (0x03ff << PLL_MPCTL0_MFD_SHIFT)
+#define PLL_MPCTL0_PD_SHIFT 26 /* Bits 29–26: Predivider Factor */
+#define PLL_MPCTL0_PD_MASK (0x0f << PLL_MPCTL0_PD_SHIFT
+
+#define PLL_MPCTL1_BRMO (1 << 6) /* Bit 6: Controls the BRM order */
+
+#define PLL_SPCTL0_MFN_SHIFT 0 /* Bits 9–0: Multiplication Factor (Numerator) */
+#define PLL_SPCTL0_MFN_MASK (0x03ff << PLL_SPCTL0_MFN_SHIFT)
+#define PLL_SPCTL0_MFI_SHIFT 10 /* Bits 13–10: Multiplication Factor (Integer) */
+#define PLL_SPCTL0_MFI_MASK (0x0f << PLL_SPCTL0_MFI_SHIFT)
+#define PLL_SPCTL0_MFD_SHIFT 16 /* Bits 25–16: Multiplication Factor (Denominator) */
+#define PLL_SPCTL0_MFD_MASK (0x03ff << PLL_SPCTL0_MFD_SHIFT)
+#define PLL_SPCTL0_PD_SHIFT 26 /* Bits 29–26: Predivider Factor */
+#define PLL_SPCTL0_PD_MASK (0x0f << PLL_SPCTL0_PD_SHIFT)
+
+#define PLL_SPCTL1_BRMO (1 << 6) /* Bit 6: Controls the BRM order */
+#define PLL_SPCTL1_LF (1 << 15) /* Bit 15: Indicates if System PLL is locked */
+
+#define PLL_PCDR_PCLKDIV1_SHIFT 0 /* Bits 3–0: Peripheral Clock Divider 1 */
+#define PLL_PCDR_PCLKDIV1_MASK (0x0f << PLL_PCDR_PCLKDIV1_SHIFT)
+#define PLL_PCDR_PCLKDIV2_SHIFT 4 /* Bits 7–4: Peripheral Clock Divider 2 */
+#define PLL_PCDR_PCLKDIV2_MASK (0x0f << PLL_PCDR_PCLKDIV2_SHIFT)
+#define PLL_PCDR_PCLKDIV3_SHIFT 16 /* Bits 22–16: Peripheral Clock Divider 3 */
+#define PLL_PCDR_PCLKDIV3_MASK (0x7f << PLL_PCDR_PCLKDIV3_SHIFT)
+
+/* PLL Helper Macros ****************************************************************/
+
/* SC Register Offsets **************************************************************/
#define SC_RSR_OFFSET 0x0000 /* Reset Source Register */
diff --git a/nuttx/configs/mx1ads/include/board.h b/nuttx/configs/mx1ads/include/board.h
index 4379121d7..978017b15 100644
--- a/nuttx/configs/mx1ads/include/board.h
+++ b/nuttx/configs/mx1ads/include/board.h
@@ -49,24 +49,92 @@
* Definitions
************************************************************************************/
-/* Clock settings */
+/* Clock settings -- All clock values are precalculated */
-#define IMX_SYS_CLK_FREQ 16780000
-#define IMX_SYSPLL_CLK_FREQ 16000000
-#define IMX_PERCLK1_FREQ 96000000
+#define IMX_SYS_CLK_FREQ 16780000 /* Crystal frequency */
-/* MPCTL */
+/* MPCTL0 -- Controls the MCU clock:
+ *
+ * MFI + MFN / (MFD+1)
+ * IMX_MCUPLL_CLK_FREQ = 2 * IMX_SYS_CLK_FREQ * --------------------
+ * PD + 1
+ */
+
+#if 0 /* 150 MHz */
+# define IMX_MPCTL0_MFN 16
+# define IMX_MPCTL0_MFI 9
+# define IMX_MPCTL0_MFD 99
+# define IMX_MPCTL0_PD 1
+#else /* 180 MHz */
+# define IMX_MPCTL0_MFN 441
+# define IMX_MPCTL0_MFI 4
+# define IMX_MPCTL0_MFD 938
+# define IMX_MPCTL0_PD 0
+#endif
+
+#define IMX_MPCTL0_VALUE \
+ ((IMX_MPCTL0_MFN << PLL_MPCTL0_MFN_SHIFT) |\
+ (IMX_MPCTL0_MFI << PLL_MPCTL0_MFI_SHIFT) |\
+ (IMX_MPCTL0_MFD << PLL_MPCTL0_MFD_SHIFT) |\
+ (IMX_MPCTL0_PD << PLL_MPCTL0_PD_SHIFT))
+
+/* This yields: */
+
+#if 0 /* 150 MHz */
+# define IMX_MCUPLL_CLK_FREQ 153704800
+#else /* 180 MHz */
+# define IMX_MCUPLL_CLK_FREQ 183561405
+#endif
+
+/* SPCTL0 -- Controls the system PLL:
+ *
+ * MFI + MFN / (MFD+1)
+ * IMX_SYSPLL_CLK_FREQ = 2 * IMX_SYS_CLK_FREQ * --------------------
+ * PD + 1
+ */
+
+#define IMX_SPCTL0_MFN 678
+#define IMX_SPCTL0_MFI 5
+#define IMX_SPCTL0_MFD 938
+#define IMX_SPCTL0_PD 1
+
+#define IMX_SPCTL0_VALUE \
+ ((IMX_SPCTL0_MFN << PLL_SPCTL0_MFN_SHIFT) |\
+ (IMX_SPCTL0_MFI << PLL_SPCTL0_MFI_SHIFT) |\
+ (IMX_SPCTL0_MFD << PLL_SPCTL0_MFD_SHIFT) |\
+ (IMX_SPCTL0_PD << PLL_SPCTL0_PD_SHIFT))
-#define IMX_MPCTL0_VALUE 0x04632410 /* For 150MHz MCU PLL clock */
-#define IMX_MPCTL0_VALUE 0x03AA11B9 /* For 150 MHz ARM clock with 32.768 KHz crystal */
+/* This yields: */
-/* SPCTL */
+#define IMX_SYSPLL_CLK_FREQ 96015910
-#define IMX_SPCTL0_VALUE 0x07AA16A6; /* For 96MHz peripheral clock with 32.768 KHz crystal */
+/* PDCR -- Controls peripheral clocks */
-/* PDCR */
+#define IMX_PCLKDIV1 5
+#define IMX_PCLKDIV2 5
+#define IMX_PCLKDIV3 0
-#define IMX_PCDR_VALUE 0x00000055
+#define IMX_PCDR_VALUE \
+ ((IMX_PCLKDIV1 << PLL_PCDR_PCLKDIV1_SHIFT) |\
+ (IMX_PCLKDIV2 << PLL_PCDR_PCLKDIV2_SHIFT) |\
+ (IMX_PCLKDIV3 << PLL_PCDR_PCLKDIV3_SHIFT))
+
+/* IMX_PERCLK1_FREQ = IMX_SYSPLL_CLK_FREQ / IMX_PCLKDIV1 + 1 */
+
+#define IMX_PERCLK1_FREQ 16002651
+
+/* IMX_PERCLK2_FREQ = IMX_SYSPLL_CLK_FREQ / IMX_PCLKDIV2 + 1 */
+
+#define IMX_PERCLK2_FREQ 16002651
+
+/* IMX_PERCLK2_FREQ = IMX_SYSPLL_CLK_FREQ / IMX_PCLKDIV4 + 1 */
+
+#define IMX_PERCLK2_FREQ 96015910
+
+/* CSCR settings -- Controls HCLK and BCLK and USB clock */
+
+#define IMX_CSCR_BCLKDIV 1
+#define IMX_CSCR_USBDIV 6
/* LED definitions ******************************************************************/
@@ -88,6 +156,13 @@
#ifndef __ASSEMBLY__
+/* All i.MX architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ */
+
+extern void imx_boardinitialize(void);
+
#endif
#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/nuttx/configs/mx1ads/src/Makefile b/nuttx/configs/mx1ads/src/Makefile
index eba605d8c..9078d5832 100644
--- a/nuttx/configs/mx1ads/src/Makefile
+++ b/nuttx/configs/mx1ads/src/Makefile
@@ -39,7 +39,7 @@ CFLAGS += -I$(TOPDIR)/sched
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
-CSRCS = up_leds.c up_network.c
+CSRCS = up_boot.c up_leds.c up_network.c
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
diff --git a/nuttx/configs/mx1ads/src/up_boot.c b/nuttx/configs/mx1ads/src/up_boot.c
new file mode 100755
index 000000000..237f6aa9b
--- /dev/null
+++ b/nuttx/configs/mx1ads/src/up_boot.c
@@ -0,0 +1,105 @@
+/************************************************************************************
+ * configs/mx1ads/src/up_boot.c
+ * arch/arm/src/board/up_boot.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <sys/types.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "imx_gpio.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: imx_boardinitialize
+ *
+ * Description:
+ * All i.MX architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ ************************************************************************************/
+
+void imx_boardinitialize(void)
+{
+ uint32 regval;
+
+ putreg32(0x000003ab, IMX_SC_GPCR); /* I/O pad driving strength */
+ putreg32(IMX_MPCTL0_VALUE, IMX_PLL_MPCTL0);
+ putreg32(IMX_SPCTL0_VALUE, IMX_PLL_SPCTL0);
+
+ regval = (CSCR_CLKOSEL_FCLK | /* Output FCLK on CLK0 */
+ (IMX_CSCR_USBDIV << PLL_CSCR_USBDIV_SHIFT) | /* USB divider */
+ CSCR_SDCNT_4thEDGE | /* Shutdown on 4th edge */
+ (IMX_CSCR_BCLKDIV << PLL_CSCR_BCLKDIV_SHIFT) | /* Bclock divider */
+ PLL_CSCR_SPEN | PLL_CSCR_MPEN); /* Enable MUC and System PLL */
+ putreg32(regval, IMX_PLL_CSCR);
+
+ /* Use these new frequencies now */
+
+ putreg32(IMX_PLL_CSCR, regval | (PLL_CSCR_MPLLRESTART|PLL_CSCR_SPLLRESTART));
+
+ /* Setup peripheral clocking */
+
+ putreg32(IMX_PCDR_VALUE, IMX_PLL_PCDR);
+
+ /* Configure CS4 for cs8900 Ethernet */
+
+#ifdef CONFIG_NET
+ putreg32(0x00000f00, IMX_EIM_CS4H);
+ putreg32(0x00001501, IMX_EIM_CS4L);
+
+ imxgpio_configprimary(GPIOA, 21);
+ imxgpio_configprimary(GPIOA, 22);
+
+ regval = getreg32(IMX_CS4_VSECTION + 0x0c);
+ regval = getreg32(IMX_CS4_VSECTION + 0x0c);
+#endif
+}