summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-02 00:59:28 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-02 00:59:28 +0000
commit5fb6f65ca74421edf5569ce13ee9f9c364b87d02 (patch)
treed88d85fa390a78eb0815aea74f39bbb5a2b651e1
parent3c17616fb76eca92cc0daaa56b8769e381c69330 (diff)
downloadpx4-nuttx-5fb6f65ca74421edf5569ce13ee9f9c364b87d02.tar.gz
px4-nuttx-5fb6f65ca74421edf5569ce13ee9f9c364b87d02.tar.bz2
px4-nuttx-5fb6f65ca74421edf5569ce13ee9f9c364b87d02.zip
LPC1788 updates from Rommel Marcelo
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5696 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc178x_memorymap.h10
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h18
-rw-r--r--nuttx/arch/arm/src/lpc17xx/chip/lpc178x_syscon.h20
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.c15
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c23
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h16
-rw-r--r--nuttx/configs/open1788/include/board.h16
-rwxr-xr-xnuttx/configs/open1788/ostest/setenv.sh2
-rwxr-xr-xnuttx/configs/open1788/scripts/ld.script22
9 files changed, 65 insertions, 77 deletions
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_memorymap.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_memorymap.h
index bc94d527b..35c518665 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_memorymap.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_memorymap.h
@@ -70,10 +70,10 @@
# define LPC17_EXTSRAM_CS2 0x98000000 /* Chip select 2 /up to 64MB/ */
# define LPC17_EXTSRAM_CS3 0x9c000000 /* Chip select 3 /up to 64MB/ */
-# define LPC17_EXTDRAM_CS0 0x9c000000 /* Chip select 0 /up to 256MB/ */
-# define LPC17_EXTDRAM_CS1 0x9c000000 /* Chip select 1 /up to 256MB/ */
-# define LPC17_EXTDRAM_CS2 0x9c000000 /* Chip select 2 /up to 256MB/ */
-# define LPC17_EXTDRAM_CS3 0x9c000000 /* Chip select 3 /up to 256MB/ */
+# define LPC17_EXTDRAM_CS0 0xa0000000 /* Chip select 0 /up to 256MB/ */
+# define LPC17_EXTDRAM_CS1 0xb0000000 /* Chip select 1 /up to 256MB/ */
+# define LPC17_EXTDRAM_CS2 0xc0000000 /* Chip select 2 /up to 256MB/ */
+# define LPC17_EXTDRAM_CS3 0xd0000000 /* Chip select 3 /up to 256MB/ */
#define LPC17_CORTEXM3_BASE 0xe0000000 /* -0xe00fffff: (see armv7-m/nvic.h) */
#define LPC17_SCS_BASE 0xe000e000
@@ -119,7 +119,7 @@
#define LPC17_UART2_BASE 0x40098000 /* -0x4009bfff: UART 2 */
#define LPC17_UART3_BASE 0x4009c000 /* -0x4009ffff: UART 3 */
#define LPC17_I2C2_BASE 0x400a0000 /* -0x400a3fff: I2C 2 */
- /* -0x400a7fff: Reserved */
+#define LPC17_UART4_BASE 0x400a4000 /* -0x400a7fff: UART4 */
#define LPC17_I2S_BASE 0x400a8000 /* -0x400abfff: I2S */
#define LPC17_SSP2_BASE 0x400ac000 /* -0x400affff: SSP2 */
/* -0x400b3fff: Reserved */
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h
index 8afb1eedc..7efa24ca9 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_pinconfig.h
@@ -76,7 +76,7 @@
#define GPIO_I2S_RXCLK_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN4)
#define GPIO_CAN2_RD_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN4)
#define GPIO_CAP2p0_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN4)
-#define GPIO_LCD_VD0_1 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN4)
+#define GPIO_LCD_VD0_1 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN4)
#define GPIO_I2S_RXWS_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
#define GPIO_CAN2_TD_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN5)
@@ -87,25 +87,25 @@
#define GPIO_SSP1_SSEL_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN6)
#define GPIO_MAT2p0_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN6)
#define GPIO_UART1_RTS_1 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN6)
-#define GPIO_LCD_VD8_1 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN6)
+#define GPIO_LCD_VD8_1 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN6)
#define GPIO_I2S_TXCLK_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN7)
#define GPIO_SSP1_SCK_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN7)
#define GPIO_MAT2p1_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN7)
#define GPIO_RTC_EV0_1 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN7)
-#define GPIO_LCD_VD9_1 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN7)
+#define GPIO_LCD_VD9_1 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN7)
#define GPIO_I2S_TXWS_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN8)
#define GPIO_SSP1_MISO_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN8)
#define GPIO_MAT2p2_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN8)
#define GPIO_RTC_EV1_1 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN8)
-#define GPIO_LCD_VD16 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN8)
+#define GPIO_LCD_VD16 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN8)
#define GPIO_I2S_TXSDA_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN9)
#define GPIO_SSP1_MOSI_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN9)
#define GPIO_MAT2p3_1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN9)
#define GPIO_RTC_EV2_1 (GPIO_ALT4 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN9)
-#define GPIO_LCD_VD17 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN9)
+#define GPIO_LCD_VD17 (GPIO_ALT7 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN9)
#define GPIO_UART2_TXD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN10)
#define GPIO_I2C2_SDA_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN10)
@@ -129,19 +129,19 @@
#define GPIO_UART1_TXD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN15)
#define GPIO_SSP0_SCK_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN15)
-#define GPIO_SPIFI_IO2 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN15)
+#define GPIO_SPIFI_IO2 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN15)
#define GPIO_UART1_RXD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN16)
#define GPIO_SSP0_SSEL_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN16)
-#define GPIO_SPIFI_IO3 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN16)
+#define GPIO_SPIFI_IO3 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN16)
#define GPIO_UART1_CTS_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN17)
#define GPIO_SSP0_MISO_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN17)
-#define GPIO_SPIFI_IO1 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN17)
+#define GPIO_SPIFI_IO1 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN17)
#define GPIO_UART1_DCD_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN18)
#define GPIO_SSP0_MOSI_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN18)
-#define GPIO_SPIFI_IO0 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN18)
+#define GPIO_SPIFI_IO0 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN18)
#define GPIO_UART1_DSR_1 (GPIO_ALT1 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN19)
#define GPIO_SD_CLK_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN19)
diff --git a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_syscon.h b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_syscon.h
index 54530bdfa..f52fca35c 100644
--- a/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_syscon.h
+++ b/nuttx/arch/arm/src/lpc17xx/chip/lpc178x_syscon.h
@@ -57,7 +57,7 @@
/* Memory Mapping Control register (MEMMAP - 0x400F C040) */
-#define LPC17_SYSCON_MEMMAP_OFFSET 0x0040 /* Memory Mapping Control register */
+#define LPC17_SYSCON_MEMMAP_OFFSET 0x0040 /* Memory Mapping Control Register */
/* Clocking and power control - Phase locked loops */
@@ -289,16 +289,16 @@
/* Bits 9-31: Reserved */
/* USB Clock Configuration register */
-#define SYSCON_USBCLKSEL_USBDIV_SHIFT (0) /* Bits 0-4: PLL0/1 divide value USB clock */
-#define SYSCON_USBCLKSEL_USBDIV_MASK (0x1f << SYSCON_USBCLKSEL_USBDIV_SHIFT)
-# define SYSCON_USBCLKSEL_USBDIV_DIV1 (1 << SYSCON_USBCLKSEL_USBDIV_SHIFT) /* PLL0/1 output must be 48MHz */
-# define SYSCON_USBCLKSEL_USBDIV_DIV2 (2 << SYSCON_USBCLKSEL_USBDIV_SHIFT) /* PLL0/1 output must be 96MHz */
-# define SYSCON_USBCLKSEL_USBDIV_DIV3 (3 << SYSCON_USBCLKSEL_USBDIV_SHIFT) /* PLL0/1 output must be 144MHz */
+#define SYSCON_USBCLKCFG_USBDIV_SHIFT (0) /* Bits 0-4: PLL0/1 divide value USB clock */
+#define SYSCON_USBCLKCFG_USBDIV_MASK (0x1f << SYSCON_USBCLKCFG_USBDIV_SHIFT)
+# define SYSCON_USBCLKCFG_USBDIV_DIV1 (1 << SYSCON_USBCLKCFG_USBDIV_SHIFT) /* PLL0/1 output must be 48MHz */
+# define SYSCON_USBCLKCFG_USBDIV_DIV2 (2 << SYSCON_USBCLKCFG_USBDIV_SHIFT) /* PLL0/1 output must be 96MHz */
+# define SYSCON_USBCLKCFG_USBDIV_DIV3 (3 << SYSCON_USBCLKCFG_USBDIV_SHIFT) /* PLL0/1 output must be 144MHz */
/* Bits 5-7: Reserved */
-#define SYSCON_USBCLKSEL_USBSEL_SHIFT (8) /* Bits 8-9: Input clock to USBDIV */
-#define SYSCON_USBCLKSEL_USBSEL_MASK (3 << SYSCON_USBCLKSEL_USBSEL_SHIFT)
-#define SYSCON_USBCLKSEL_USBSEL_PLL0 (1 << SYSCON_USBCLKSEL_USBSEL_SHIFT) /* 01: PLL0 is used as input clock to USBDIV */
-#define SYSCON_USBCLKSEL_USBSEL_PLL1 (2 << SYSCON_USBCLKSEL_USBSEL_SHIFT) /* 10: PLL1 is used as input clock to USBDIV */
+#define SYSCON_USBCLKCFG_USBSEL_SHIFT (8) /* Bits 8-9: Input clock to USBDIV */
+#define SYSCON_USBCLKCFG_USBSEL_MASK (3 << SYSCON_USBCLKCFG_USBSEL_SHIFT)
+#define SYSCON_USBCLKCFG_USBSEL_PLL0 (1 << SYSCON_USBCLKCFG_USBSEL_SHIFT) /* 01: PLL0 is used as input clock to USBDIV */
+#define SYSCON_USBCLKCFG_USBSEL_PLL1 (2 << SYSCON_USBCLKCFG_USBSEL_SHIFT) /* 10: PLL1 is used as input clock to USBDIV */
/* 11: unused */
/* Bits 10-31: Reserved */
/* CAN0/1 Sleep Clear Register */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.c b/nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.c
index 6e46d3241..2ea4126ad 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_clockconfig.c
@@ -134,9 +134,13 @@ void lpc17_clockconfig(void)
putreg32(0x55, LPC17_SYSCON_PLL0FEED);
/* Wait for PLL to report that it is connected and enabled */
-
+# if defined(LPC176x)
while ((getreg32(LPC17_SYSCON_PLL0STAT) & (SYSCON_PLL0STAT_PLLE|SYSCON_PLL0STAT_PLLC))
!= (SYSCON_PLL0STAT_PLLE|SYSCON_PLL0STAT_PLLC));
+# elif defined(LPC178x)
+ while ((getreg32(LPC17_SYSCON_PLL0STAT) & (SYSCON_PLL0STAT_PLLE))
+ != (SYSCON_PLL0STAT_PLLE));
+# endif
#endif
/* PLL1 receives its clock input from the main oscillator only and can be used to
@@ -173,14 +177,19 @@ void lpc17_clockconfig(void)
putreg32(0x55, LPC17_SYSCON_PLL1FEED);
/* Wait for PLL to report that it is connected and enabled */
-
+# if defined(LPC176x)
while ((getreg32(LPC17_SYSCON_PLL1STAT) & (SYSCON_PLL1STAT_PLLE|SYSCON_PLL1STAT_PLLC))
!= (SYSCON_PLL1STAT_PLLE|SYSCON_PLL1STAT_PLLC));
+# elif defined(LPC178x)
+ while ((getreg32(LPC17_SYSCON_PLL1STAT) & (SYSCON_PLL1STAT_PLLE))
+ != (SYSCON_PLL1STAT_PLLE));
+# endif
#else
/* Otherwise, setup up the USB clock divider to generate the USB clock from PLL0 */
-
+#ifdef LPC176x
putreg32(BOARD_USBCLKCFG_VALUE, LPC17_SYSCON_USBCLKCFG);
#endif
+#endif /* LPC176x */
/* Disable all peripheral clocks. They must be configured by each device driver
* when the device driver is initialized.
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c
index a94eaf999..387875120 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.c
@@ -273,8 +273,8 @@ static int lpc17_configiocon(unsigned int port, unsigned int pin,
regaddr = LPC17_IOCON_P(port, pin);
regval = getreg32(regaddr);
- regval &= value;
- regval &= ~typemask;
+ regval |= value;
+ regval &= typemask;
putreg32(regval, regaddr);
return OK;
@@ -702,6 +702,10 @@ static int lpc17_configalternate(lpc17_pinset_t cfgset, unsigned int port,
#elif defined(LPC178x)
uint32_t regval = 0;
+ /* Set the alternate pin */
+
+ regval |= (alt & IOCON_FUNC_MASK);
+
/* Select open drain output */
if ((cfgset & GPIO_OPEN_DRAIN) != 0)
@@ -709,21 +713,6 @@ static int lpc17_configalternate(lpc17_pinset_t cfgset, unsigned int port,
regval |= IOCON_OD_MASK;
}
- //~ /* Select slew output */
- //~
- //~ if ((cfgset & GPIO_SLEW) != 0)
- //~ {
- //~ regval |= IOCON_SLEW_MASK;
- //~ }
-
- /* Set pull-up mode */
-
- regval |= ((cfgset & GPIO_PUMODE_MASK) >> GPIO_PINMODE_SHIFT);
-
- /* Set the alternate pin */
-
- regval |= (alt & ~IOCON_FUNC_MASK);
-
/* Set IOCON register */
lpc17_configiocon(port, pin, regval);
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h
index 8853afe9e..8bdaf01ca 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_gpio.h
@@ -69,7 +69,7 @@
* Port number: PPP (0-4)
* Pin number: NNNNN (0-31)
*/
-
+
/* Pin Function bits: FFF
* Only meaningful when the GPIO function is GPIO_PIN
*/
@@ -173,7 +173,7 @@
#elif defined(LPC178x)
/* Encoding: TTTT TTTT FFFF MMOV PPPN NNNN
- *
+ *
* Special Pin Functions: TTTT TTTT
* Pin Function: FFFF
* Pin Mode bits: MM
@@ -182,7 +182,7 @@
* Port number: PPP (0-4)
* Pin number: NNNNN (0-31)
*/
-
+
/* Special Pin Functions
* For pins that has ADC/DAC, USB, I2C
*/
@@ -241,13 +241,13 @@
/* Pin Mode: MM */
-#define GPIO_PINMODE_SHIFT (7)
+#define GPIO_PINMODE_SHIFT (7)
#define GPIO_PUMODE_SHIFT (10) /* Bits 10-11: Pin pull-up mode */
#define GPIO_PUMODE_MASK (3 << GPIO_PUMODE_SHIFT)
-# define GPIO_FLOAT (0 << GPIO_PUMODE_SHIFT) /* Pull-up resistor enabled */
-# define GPIO_PULLDN (1 << GPIO_PUMODE_SHIFT) /* Repeater mode enabled */
-# define GPIO_PULLUP (2 << GPIO_PUMODE_SHIFT) /* Neither pull-up nor -down */
-# define GPIO_REPEATER (3 << GPIO_PUMODE_SHIFT) /* Pull-down resistor enabled */
+# define GPIO_FLOAT (0 << GPIO_PUMODE_SHIFT) /* Neither pull-up nor -down */
+# define GPIO_PULLDN (1 << GPIO_PUMODE_SHIFT) /* Pull-down resistor enabled */
+# define GPIO_PULLUP (2 << GPIO_PUMODE_SHIFT) /* Pull-up resistor enabled */
+# define GPIO_REPEATER (3 << GPIO_PUMODE_SHIFT) /* Repeater mode enabled */
/* Open drain: O */
diff --git a/nuttx/configs/open1788/include/board.h b/nuttx/configs/open1788/include/board.h
index 579fb004b..c09bdfc3d 100644
--- a/nuttx/configs/open1788/include/board.h
+++ b/nuttx/configs/open1788/include/board.h
@@ -85,8 +85,8 @@
* The input to the divider (PLLCLK) will be determined by the PLL output.
*/
-#define BOARD_CCLKCFG_DIVIDER 6
-#define BOARD_CCLKCFG_VALUE ((BOARD_CCLKCFG_DIVIDER-1) << SYSCON_CCLKCFG_CCLKDIV_SHIFT)
+#define BOARD_CCLKCFG_DIVIDER 1
+#define BOARD_CCLKCFG_VALUE (BOARD_CCLKCFG_DIVIDER | SYSCON_CCLKCFG_CCLKSEL)
/* PLL0. PLL0 is used to generate the CPU clock (PLLCLK).
*
@@ -109,11 +109,11 @@
/* PLL1 : PLL1 is used to generate clock for the USB */
- #undef CONFIG_LPC17_PLL1
- #define CONFIG_LPC17_PLL1 1
- #define BOARD_PLL1CFG_MSEL 4
- #define BOARD_PLL1CFG_PSEL 2
- #define BOARD_PLL1CFG_VALUE \
+#undef CONFIG_LPC17_PLL1
+//~ #define CONFIG_LPC17_PLL1 1
+#define BOARD_PLL1CFG_MSEL 4
+#define BOARD_PLL1CFG_PSEL 2
+#define BOARD_PLL1CFG_VALUE \
(((BOARD_PLL1CFG_MSEL-1) << SYSCON_PLLCFG_MSEL_SHIFT) | \
((BOARD_PLL1CFG_PSEL-1) << SYSCON_PLLCFG_PSEL_SHIFT))
@@ -135,7 +135,7 @@
/* Flash access use 6 CPU clocks - Safe for any allowed conditions */
-#define BOARD_FLASHCFG_VALUE SYSCON_FLASHCFG_TIM_5
+#define BOARD_FLASHCFG_VALUE (SYSCON_FLASHCFG_TIM_5 | 0x03a)
/* Ethernet configuration */
diff --git a/nuttx/configs/open1788/ostest/setenv.sh b/nuttx/configs/open1788/ostest/setenv.sh
index ecbc9ef1c..88714298e 100755
--- a/nuttx/configs/open1788/ostest/setenv.sh
+++ b/nuttx/configs/open1788/ostest/setenv.sh
@@ -65,7 +65,7 @@ fi
export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
# The Olimex-lpc1766stk/tools directory
-export LPCTOOL_DIR="${WD}/configs/olimex-lpc1766stk/tools"
+export LPCTOOL_DIR="${WD}/configs/open1788/tools"
# Add the path to the toolchain and tools directory to the PATH varialble
export PATH="${TOOLCHAIN_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
diff --git a/nuttx/configs/open1788/scripts/ld.script b/nuttx/configs/open1788/scripts/ld.script
index 8ed9c24c3..78a0e8911 100755
--- a/nuttx/configs/open1788/scripts/ld.script
+++ b/nuttx/configs/open1788/scripts/ld.script
@@ -37,8 +37,8 @@
/* The LPC1788 has 512Kb of FLASH beginning at address 0x0000:0000 and
* 96Kb of total SRAM: 64Kb of SRAM in the CPU block beginning at address
* 0x10000000 and 32Kb of Peripheral SRAM in two banks, 8Kb at addresses
- * 0x20000000 bank0 first and 8kb at 0x20020000 at bank0 second. And 16Kb
- * at 0x20040000 on bank1.
+ * 0x20000000 bank0 first and 8kb at 0x20002000 at bank0 second. And 16Kb
+ * at 0x20004000 on bank1.
*
* Here we assume that .data and .bss will all fit into the 64Kb CPU SRAM
* address range.
@@ -48,8 +48,9 @@ MEMORY
{
FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 512K
SRAM (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
- PSRAM0 (rwx) : ORIGIN = 0x20000000, LENGTH = 16K /* Peripheral SRAM Bank 0 */
- PSRAM1 (rwx) : ORIGIN = 0x20040000, LENGTH = 16K /* Peripheral SRAM Bank 1 */
+ AHBRAM8_B0A(rwx): ORIGIN = 0x20000000, LENGTH = 8K
+ AHBRAM8_B0B(rwx): ORIGIN = 0x20002000, LENGTH = 8K
+ AHBRAM16(rwx): ORIGIN = 0x20004000, LENGTH = 16K
}
OUTPUT_ARCH(arm)
@@ -86,6 +87,7 @@ SECTIONS
.ARM.exidx : {
*(.ARM.exidx*)
} > FLASH
+
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
@@ -105,20 +107,8 @@ SECTIONS
*(COMMON)
_ebss = ABSOLUTE(.);
} > SRAM
-/*
- .psram0 (NOLOAD) :
- {
- *(.psram0)
- . = ALIGN(4)
- } > PSRAM0
- .psram1 (NOLOAD) :
- {
- *(.psram1)
- . = ALIGN(4)
- } > PSRAM1
-*/
/* Stabs debugging sections */
.stab 0 : { *(.stab) }