summaryrefslogtreecommitdiff
path: root/nuttx/configs/nutiny-nuc120
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-18 20:24:20 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-18 20:24:20 +0000
commitd3aa6ce3315a4f75b5dabcc7358a34a1ce2e451b (patch)
tree59cf90aba2d010904d3d3a8045b9d81f6866dbe6 /nuttx/configs/nutiny-nuc120
parent31a5581021afca8240e6aa7eebed28ef7a55e561 (diff)
downloadpx4-nuttx-d3aa6ce3315a4f75b5dabcc7358a34a1ce2e451b.tar.gz
px4-nuttx-d3aa6ce3315a4f75b5dabcc7358a34a1ce2e451b.tar.bz2
px4-nuttx-d3aa6ce3315a4f75b5dabcc7358a34a1ce2e451b.zip
More files for the Cortex-M0/NUC120 port
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5659 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs/nutiny-nuc120')
-rw-r--r--nuttx/configs/nutiny-nuc120/include/board.h41
-rw-r--r--nuttx/configs/nutiny-nuc120/ostest/defconfig2
-rw-r--r--nuttx/configs/nutiny-nuc120/scripts/ld.script113
-rw-r--r--nuttx/configs/nutiny-nuc120/src/nuc_led.c8
-rw-r--r--nuttx/configs/nutiny-nuc120/src/nutiny-nuc120.h17
5 files changed, 177 insertions, 4 deletions
diff --git a/nuttx/configs/nutiny-nuc120/include/board.h b/nuttx/configs/nutiny-nuc120/include/board.h
index 276ce5d04..14842db86 100644
--- a/nuttx/configs/nutiny-nuc120/include/board.h
+++ b/nuttx/configs/nutiny-nuc120/include/board.h
@@ -51,6 +51,47 @@
* Definitions
************************************************************************************/
/* Clocking *************************************************************************/
+/* Crystal frequencies */
+
+#define BOARD_HIGHSPEED_XTAL_FREQUENCY 12000000
+#define BOARD_LOWSPEED_XTAL_FREQUENCY 32768
+
+/* PLL: The PLL must be 48MHz x N times when using USB
+ *
+ * FOUT = FIN x (NF/NR) x (1 / NO)
+ * FIN = Input reference clock frequency
+ * NF = Feedback divider
+ * = (FB_DV + 2)
+ * NR = Input divider
+ * = (IN_DV + 2)
+ * NO = 1 if OUT_DV == 0
+ * 2 if OUT_DV == 1 or 2
+ * 4 if OUT_DV == 3
+ *
+ * FOUT = 12000000 x 48 / 3 / 4
+ * = 48MHz
+ */
+
+#define BOARD_PLL_FIN BOARD_HIGHSPEED_XTAL_FREQUENCY
+#define BOARD_PLL_FB_DV 46
+#define BOARD_PLL_NF (BOARD_PLL_FB_DV+2)
+#define BOARD_PLL_IN_DV 1
+#define BOARD_PLL_NR (BOARD_PLL_IN_DV+2)
+#define BOARD_PLL_OUT_DV 3
+#define BOARD_PLL_NO 4
+
+#define BOARD_PLL_FOUT \
+ (BOARD_PLL_FIN * BOARD_PLL_NF / BOARD_PLL_NR / BOARD_PLL_NO)
+
+/* HCLK. FOUT is the HCLK source clock. */
+
+#define BOARD_HCLK_N 0
+#define BOARD_HCLK_FREQUENCY (BOARD_PLL_FOUT / (BOARD_HCLK_N + 1))
+
+/* USB. FOUT is the source. The USB CLK must be 48MHz */
+
+#define BOARD_USB_N 0
+#define BOARD_USB_FREQUENCY (BOARD_PLL_FOUT / (BOARD_USB_N + 1))
/* LED definitions ******************************************************************/
/* The NuTiny has a single green LED that can be controlled from sofware. This LED
diff --git a/nuttx/configs/nutiny-nuc120/ostest/defconfig b/nuttx/configs/nutiny-nuc120/ostest/defconfig
index e13b47105..9e37c286a 100644
--- a/nuttx/configs/nutiny-nuc120/ostest/defconfig
+++ b/nuttx/configs/nutiny-nuc120/ostest/defconfig
@@ -414,7 +414,7 @@ CONFIG_DISABLE_MOUNTPOINT=y
# Memory Management
#
# CONFIG_MM_SMALL is not set
-CONFIG_MM_REGIONS=2
+CONFIG_MM_REGIONS=1
# CONFIG_GRAN is not set
#
diff --git a/nuttx/configs/nutiny-nuc120/scripts/ld.script b/nuttx/configs/nutiny-nuc120/scripts/ld.script
new file mode 100644
index 000000000..aed7e1b68
--- /dev/null
+++ b/nuttx/configs/nutiny-nuc120/scripts/ld.script
@@ -0,0 +1,113 @@
+/****************************************************************************
+ * configs/nutiny-nuc120/scripts/ld.script
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/* The NUC120LE3AN has 128Kb of FLASH beginning at address 0x0000:0000 and
+ * 16Kb of SRAM at address 0x20000000.
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x00000000, LENGTH = 128K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 16K
+}
+
+OUTPUT_ARCH(arm)
+ENTRY(_stext)
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > flash
+
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ *(.init_array .init_array.*)
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/nuttx/configs/nutiny-nuc120/src/nuc_led.c b/nuttx/configs/nutiny-nuc120/src/nuc_led.c
index 873a116e3..2482e7da0 100644
--- a/nuttx/configs/nutiny-nuc120/src/nuc_led.c
+++ b/nuttx/configs/nutiny-nuc120/src/nuc_led.c
@@ -103,10 +103,14 @@
****************************************************************************/
/****************************************************************************
- * Name: up_ledinit
+ * Name: nuc_ledinit
+ *
+ * Description:
+ * Initialize the on-board LED
+ *
****************************************************************************/
-void up_ledinit(void)
+void nuc_ledinit(void)
{
nuc_configgpio(GPIO_LED);
}
diff --git a/nuttx/configs/nutiny-nuc120/src/nutiny-nuc120.h b/nuttx/configs/nutiny-nuc120/src/nutiny-nuc120.h
index f7f3184bc..55744fb61 100644
--- a/nuttx/configs/nutiny-nuc120/src/nutiny-nuc120.h
+++ b/nuttx/configs/nutiny-nuc120/src/nutiny-nuc120.h
@@ -52,7 +52,7 @@
/* NuTiny-EVB-120 GPIOs *****************************************************************************/
/* The NuTiny has a single green LED that can be controlled from sofware. This LED
- * is connected to PIN17. It is pulled high so a low value will illuminate the LED.
+ * is connected to PIN17 (PB.0). It is pulled high so a low value will illuminate the LED.
*
* If CONFIG_ARCH_LEDs is defined, then NuttX will control the LED on board the
* NuTiny. The following definitions describe how NuttX controls the LEDs:
@@ -71,6 +71,8 @@
* LED_IDLE NUC1XX is is sleep mode (Optional, not used)
*/
+#define GPIO_LED (GPIO_OUTPUT | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8)
+
/* Button definitions ***************************************************************/
/* The NuTiny has no buttons */
@@ -111,6 +113,19 @@ void weak_function nuc_spiinitialize(void);
void weak_function nuc_usbinitialize(void);
#endif
+/****************************************************************************************************
+ * Name: nuc_ledinit
+ *
+ * Description:
+ * Initialize the on-board LED
+ *
+ ****************************************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+void nuc_ledinit(void);
+#endif
+
+
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_NUTINY_NUC120_SRC_NUTINY_NUC120_H */