summaryrefslogtreecommitdiff
path: root/nuttx/configs/kwikstik-k40/src
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-08-05 19:33:13 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-08-05 19:33:13 +0000
commit8f0b435a518c39a6141bbf888aa4bcd879808d44 (patch)
treefbb26e9e98d595d4ecae4c372b920b29638b4fd6 /nuttx/configs/kwikstik-k40/src
parent995855bd907c315e68b5a7865a065c6afa6512b6 (diff)
downloadpx4-nuttx-8f0b435a518c39a6141bbf888aa4bcd879808d44.tar.gz
px4-nuttx-8f0b435a518c39a6141bbf888aa4bcd879808d44.tar.bz2
px4-nuttx-8f0b435a518c39a6141bbf888aa4bcd879808d44.zip
Add directory structure to support the port to the Kinesis KwikStik-K40
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3845 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs/kwikstik-k40/src')
-rwxr-xr-xnuttx/configs/kwikstik-k40/src/Makefile93
-rwxr-xr-xnuttx/configs/kwikstik-k40/src/kwistik-internal.h110
-rwxr-xr-xnuttx/configs/kwikstik-k40/src/up_boot.c102
-rw-r--r--nuttx/configs/kwikstik-k40/src/up_buttons.c172
-rwxr-xr-xnuttx/configs/kwikstik-k40/src/up_lcd.c125
-rwxr-xr-xnuttx/configs/kwikstik-k40/src/up_leds.c113
-rwxr-xr-xnuttx/configs/kwikstik-k40/src/up_nsh.c139
-rwxr-xr-xnuttx/configs/kwikstik-k40/src/up_spi.c164
-rw-r--r--nuttx/configs/kwikstik-k40/src/up_usbdev.c115
-rwxr-xr-xnuttx/configs/kwikstik-k40/src/up_usbstrg.c118
10 files changed, 1251 insertions, 0 deletions
diff --git a/nuttx/configs/kwikstik-k40/src/Makefile b/nuttx/configs/kwikstik-k40/src/Makefile
new file mode 100755
index 000000000..9378539d1
--- /dev/null
+++ b/nuttx/configs/kwikstik-k40/src/Makefile
@@ -0,0 +1,93 @@
+############################################################################
+# configs/kwikstik-k40/src/Makefile
+#
+# Copyright (C) 2011 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.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+CFLAGS += -I$(TOPDIR)/sched
+
+ASRCS =
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = up_boot.c up_lcd.c up_leds.c up_buttons.c up_spi.c up_usbdev.c
+
+ifeq ($(CONFIG_NSH_ARCHINIT),y)
+CSRCS += up_nsh.c
+endif
+
+ifeq ($(CONFIG_USBSTRG),y)
+CSRCS += up_usbstrg.c
+endif
+
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+ifeq ($(WINTOOL),y)
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/cortexm3}"
+else
+ CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/cortexm3
+endif
+
+all: libboard$(LIBEXT)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+libboard$(LIBEXT): $(OBJS)
+ @( for obj in $(OBJS) ; do \
+ $(call ARCHIVE, $@, $${obj}); \
+ done ; )
+
+.depend: Makefile $(SRCS)
+ @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @touch $@
+
+depend: .depend
+
+clean:
+ @rm -f libboard$(LIBEXT) *~ .*.swp
+ $(call CLEAN)
+
+distclean: clean
+ @rm -f Make.dep .depend
+
+-include Make.dep
diff --git a/nuttx/configs/kwikstik-k40/src/kwistik-internal.h b/nuttx/configs/kwikstik-k40/src/kwistik-internal.h
new file mode 100755
index 000000000..46b63b9d0
--- /dev/null
+++ b/nuttx/configs/kwikstik-k40/src/kwistik-internal.h
@@ -0,0 +1,110 @@
+/************************************************************************************
+ * configs/kwikstik-k40/src/kwikstik_internal.h
+ * arch/arm/src/board/kwikstik_internal.n
+ *
+ * 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 __CONFIGS_KWIKSTK_K40_SRC_KWIKSTIK_INTERNAL_H
+#define __CONFIGS_KWIKSTK_K40_SRC_KWIKSTIK_INTERNAL_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+#include <stdint.h>
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* How many SPI modules does this chip support? The LM3S6918 supports 2 SPI
+ * modules (others may support more -- in such case, the following must be
+ * expanded).
+ */
+
+#if KINETIS_NSPI < 1
+# undef CONFIG_KINETIS_SPI1
+# undef CONFIG_KINETIS_SPI2
+#elif KINETIS_NSPI < 2
+# undef CONFIG_KINETIS_SPI2
+#endif
+
+/* KwikStik-K40 GPIOs ***************************************************************/
+
+/* LEDs */
+
+/* BUTTONS -- NOTE that some have EXTI interrupts configured */
+
+/* SPI FLASH chip select */
+
+/* USB Soft Connect Pullup */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: kinetis_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the KwikStik-K40 board.
+ *
+ ************************************************************************************/
+
+extern void weak_function kinetis_spiinitialize(void);
+
+/************************************************************************************
+ * Name: kinetis_usbinitialize
+ *
+ * Description:
+ * Called to setup USB-related GPIO pins for the KwikStik-K40 board.
+ *
+ ************************************************************************************/
+
+extern void weak_function kinetis_usbinitialize(void);
+
+#endif /* __ASSEMBLY__ */
+#endif /* __CONFIGS_KWIKSTK_K40_SRC_KWIKSTIK_INTERNAL_H */
+
diff --git a/nuttx/configs/kwikstik-k40/src/up_boot.c b/nuttx/configs/kwikstik-k40/src/up_boot.c
new file mode 100755
index 000000000..350294d2c
--- /dev/null
+++ b/nuttx/configs/kwikstik-k40/src/up_boot.c
@@ -0,0 +1,102 @@
+/************************************************************************************
+ * configs/kwikstik-k40/src/up_boot.c
+ * arch/arm/src/board/up_boot.c
+ *
+ * Copyright (C) 2011 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 <debug.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "kwikstik-internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: kinetis_boardinitialize
+ *
+ * Description:
+ * All Kinetis architectures must provide the following entry point. This entry
+ * point is called early in the initialization -- after all memory has been
+ * configured and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+void kinetis_boardinitialize(void)
+{
+ /* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function
+ * kinetis_spiinitialize() has been brought into the link.
+ */
+
+#if defined(CONFIG_KINETIS_SPI1) || defined(CONFIG_KINETIS_SPI2)
+ if (kinetis_spiinitialize)
+ {
+ kinetis_spiinitialize();
+ }
+#endif
+
+ /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not
+ * disabled, and 3) the weak function kinetis_usbinitialize() has been brought
+ * into the build.
+ */
+
+#if defined(CONFIG_USBDEV) && defined(CONFIG_KINETIS_USB)
+ if (kinetis_usbinitialize)
+ {
+ kinetis_usbinitialize();
+ }
+#endif
+
+ /* Configure on-board LEDs if LED support has been selected. */
+
+#ifdef CONFIG_ARCH_LEDS
+ up_ledinit();
+#endif
+}
diff --git a/nuttx/configs/kwikstik-k40/src/up_buttons.c b/nuttx/configs/kwikstik-k40/src/up_buttons.c
new file mode 100644
index 000000000..8ba02f4a6
--- /dev/null
+++ b/nuttx/configs/kwikstik-k40/src/up_buttons.c
@@ -0,0 +1,172 @@
+/****************************************************************************
+ * configs/kwikstik-k40/src/up_buttons.c
+ *
+ * Copyright (C) 2011 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 <stdint.h>
+
+#include <arch/board/board.h>
+#include "kwikstik-internal.h"
+
+#ifdef CONFIG_ARCH_BUTTONS
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+/* Pin configuration for each KwikStik-K40 button. This array is indexed by
+ * the BUTTON_* definitions in board.h
+ */
+
+#if 0
+static const uint16_t g_buttons[NUM_BUTTONS] =
+{
+};
+#endif
+#warning "Missing logic"
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_buttoninit
+ *
+ * Description:
+ * up_buttoninit() must be called to initialize button resources. After
+ * that, up_buttons() may be called to collect the current state of all
+ * buttons or up_irqbutton() may be called to register button interrupt
+ * handlers.
+ *
+ ****************************************************************************/
+
+void up_buttoninit(void)
+{
+#if 0
+ int i;
+
+ /* Configure the GPIO pins as inputs. */
+
+ for (i = 0; i < NUM_BUTTONS; i++)
+ {
+ kinetis_configgpio(g_buttons[i]);
+ }
+#else
+#warning "Missing logic"
+#endif
+}
+
+/****************************************************************************
+ * Name: up_buttons
+ ****************************************************************************/
+
+uint8_t up_buttons(void)
+{
+#if 0
+ uint8_t ret = 0;
+ int i;
+
+ /* Check that state of each key */
+
+ for (i = 0; i < NUM_BUTTONS; i++)
+ {
+ /* A LOW value means that the key is pressed for most keys */
+
+ bool released = kinetis_gpioread(g_buttons[i]);
+
+ /* Accumulate the set of depressed (not released) keys */
+
+ if (!released)
+ {
+ ret |= (1 << i);
+ }
+ }
+
+ return ret;
+#else
+#warning "Missing logic"
+ return 0;
+#endif
+}
+
+/************************************************************************************
+ * Button support.
+ *
+ * Description:
+ * up_buttoninit() must be called to initialize button resources. After
+ * that, up_buttons() may be called to collect the current state of all
+ * buttons or up_irqbutton() may be called to register button interrupt
+ * handlers.
+ *
+ * After up_buttoninit() has been called, up_buttons() may be called to
+ * collect the state of all buttons. up_buttons() returns an 8-bit bit set
+ * with each bit associated with a button. See the BUTTON_*_BIT and JOYSTICK_*_BIT
+ * definitions in board.h for the meaning of each bit.
+ *
+ * up_irqbutton() may be called to register an interrupt handler that will
+ * be called when a button is depressed or released. The ID value is a
+ * button enumeration value that uniquely identifies a button resource. See the
+ * BUTTON_* and JOYSTICK_* definitions in board.h for the meaning of enumeration
+ * value. The previous interrupt handler address is returned (so that it may
+ * restored, if so desired).
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_ARCH_IRQBUTTONS
+xcpt_t up_irqbutton(int id, xcpt_t irqhandler)
+{
+ xcpt_t oldhandler = NULL;
+
+ /* The following should be atomic */
+
+ if (id >= MIN_IRQBUTTON && id <= MAX_IRQBUTTON)
+ {
+ oldhandler = kinetis_gpiosetevent(g_buttons[id], true, true, true, irqhandler);
+ }
+ return oldhandler;
+}
+#endif
+#endif /* CONFIG_ARCH_BUTTONS */
diff --git a/nuttx/configs/kwikstik-k40/src/up_lcd.c b/nuttx/configs/kwikstik-k40/src/up_lcd.c
new file mode 100755
index 000000000..c2f911fc1
--- /dev/null
+++ b/nuttx/configs/kwikstik-k40/src/up_lcd.c
@@ -0,0 +1,125 @@
+/**************************************************************************************
+ * configs/kwikstik-k40/src/up_lcd.c
+ * arch/arm/src/board/up_lcd.c
+ *
+ * Copyright (C) 2011 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 "kwikstik-internal.h"
+
+/**************************************************************************************
+ * Pre-processor Definitions
+ **************************************************************************************/
+
+/* Configuration **********************************************************************/
+
+/* Display/Color Properties ***********************************************************/
+
+/* Debug ******************************************************************************/
+
+#ifdef CONFIG_DEBUG_LCD
+# define lcddbg(format, arg...) vdbg(format, ##arg)
+#else
+# define lcddbg(x...)
+#endif
+
+/**************************************************************************************
+ * Private Type Definition
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Private Function Protototypes
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Private Data
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Private Functions
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Public Functions
+ **************************************************************************************/
+
+/**************************************************************************************
+ * Name: up_lcdinitialize
+ *
+ * Description:
+ * Initialize the LCD video hardware. The initial state of the LCD is fully
+ * initialized, display memory cleared, and the LCD ready to use, but with the power
+ * setting at 0 (full off).
+ *
+ **************************************************************************************/
+
+int up_lcdinitialize(void)
+{
+ gvdbg("Initializing\n");
+#warning "Missing logic"
+ return OK;
+}
+
+/**************************************************************************************
+ * Name: up_lcdgetdev
+ *
+ * Description:
+ * Return a a reference to the LCD object for the specified LCD. This allows support
+ * for multiple LCD devices.
+ *
+ **************************************************************************************/
+
+FAR struct lcd_dev_s *up_lcdgetdev(int lcddev)
+{
+ DEBUGASSERT(lcddev == 0);
+#warning "Missing logic"
+ return NULL;
+}
+
+/**************************************************************************************
+ * Name: up_lcduninitialize
+ *
+ * Description:
+ * Unitialize the LCD support
+ *
+ **************************************************************************************/
+
+void up_lcduninitialize(void)
+{
+#warning "Missing logic"
+}
+
diff --git a/nuttx/configs/kwikstik-k40/src/up_leds.c b/nuttx/configs/kwikstik-k40/src/up_leds.c
new file mode 100755
index 000000000..0ad485ec6
--- /dev/null
+++ b/nuttx/configs/kwikstik-k40/src/up_leds.c
@@ -0,0 +1,113 @@
+/****************************************************************************
+ * configs/kwikstik-k40/src/up_leds.c
+ * arch/arm/src/board/up_leds.c
+ *
+ * Copyright (C) 2011 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 <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "up_internal.h"
+#include "kinetis_internal.h"
+#include "kwistik-internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Enables debug output from this file (needs CONFIG_DEBUG with
+ * CONFIG_DEBUG_VERBOSE too)
+ */
+
+#undef LED_DEBUG /* Define to enable debug */
+
+#ifdef LED_DEBUG
+# define leddbg lldbg
+# define ledvdbg llvdbg
+#else
+# define leddbg(x...)
+# define ledvdbg(x...)
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_ledinit
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+void up_ledinit(void)
+{
+# warning "Missing logic"
+}
+
+/****************************************************************************
+ * Name: up_ledon
+ ****************************************************************************/
+
+void up_ledon(int led)
+{
+# warning "Missing logic"
+}
+
+/****************************************************************************
+ * Name: up_ledoff
+ ****************************************************************************/
+
+void up_ledoff(int led)
+{
+# warning "Missing logic"
+}
+
+#endif /* CONFIG_ARCH_LEDS */
diff --git a/nuttx/configs/kwikstik-k40/src/up_nsh.c b/nuttx/configs/kwikstik-k40/src/up_nsh.c
new file mode 100755
index 000000000..eb16f71bf
--- /dev/null
+++ b/nuttx/configs/kwikstik-k40/src/up_nsh.c
@@ -0,0 +1,139 @@
+/****************************************************************************
+ * config/kwikstik-k40/src/up_nsh.c
+ * arch/arm/src/board/up_nsh.c
+ *
+ * Copyright (C) 2011 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 <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#ifdef CONFIG_KINETIS_SPI1
+# include <nuttx/spi.h>
+# include <nuttx/mtd.h>
+#endif
+
+#ifdef CONFIG_KINETIS_SDIO
+# include <nuttx/sdio.h>
+# include <nuttx/mmcsd.h>
+#endif
+
+#include "kinetis_internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* For now, don't build in any SPI1 support -- NSH is not using it */
+
+#undef CONFIG_KINETIS_SPI1
+
+/* PORT and SLOT number probably depend on the board configuration */
+
+#ifdef CONFIG_ARCH_BOARD_KWIKSTIK_K40
+# define CONFIG_NSH_HAVEUSBDEV 1
+# define CONFIG_NSH_HAVEMMCSD 1
+# if defined(CONFIG_NSH_MMCSDSLOTNO) && CONFIG_NSH_MMCSDSLOTNO != 0
+# error "Only one MMC/SD slot"
+# undef CONFIG_NSH_MMCSDSLOTNO
+# endif
+# ifndef CONFIG_NSH_MMCSDSLOTNO
+# define CONFIG_NSH_MMCSDSLOTNO 0
+# endif
+#else
+ /* Add configuration for new Kinetis boards here */
+# error "Unrecognized Kinetis board"
+# undef CONFIG_NSH_HAVEUSBDEV
+# undef CONFIG_NSH_HAVEMMCSD
+#endif
+
+/* Can't support USB features if USB is not enabled */
+
+#ifndef CONFIG_USBDEV
+# undef CONFIG_NSH_HAVEUSBDEV
+#endif
+
+/* Can't support MMC/SD features if mountpoints are disabled or if SDIO support
+ * is not enabled.
+ */
+
+#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_KINETIS_SDIO)
+# undef CONFIG_NSH_HAVEMMCSD
+#endif
+
+#ifndef CONFIG_NSH_MMCSDMINOR
+# define CONFIG_NSH_MMCSDMINOR 0
+#endif
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lib_lowprintf(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lib_lowprintf
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+int nsh_archinitialize(void)
+{
+# warning "Missing logic"
+ return OK;
+}
diff --git a/nuttx/configs/kwikstik-k40/src/up_spi.c b/nuttx/configs/kwikstik-k40/src/up_spi.c
new file mode 100755
index 000000000..d5d8865ce
--- /dev/null
+++ b/nuttx/configs/kwikstik-k40/src/up_spi.c
@@ -0,0 +1,164 @@
+/************************************************************************************
+ * configs/kwikstik-k40/src/up_spi.c
+ * arch/arm/src/board/up_spi.c
+ *
+ * Copyright (C) 2011 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 <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "chip.h"
+#include "kinetis_internal.h"
+#include "kwikstick-internal.h"
+
+#if defined(CONFIG_KINETIS_SPI1) || defined(CONFIG_KINETIS_SPI2)
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Enables debug output from this file (needs CONFIG_DEBUG too) */
+
+#ifdef CONFIG_DEBUG_SPI
+# define spidbg lldbg
+# ifdef CONFIG_DEBUG_SPI_VERBOSE
+# define spivdbg lldbg
+# else
+# define spivdbg(x...)
+# endif
+#else
+# undef CONFIG_DEBUG_SPI_VERBOSE
+# define spidbg(x...)
+# define spivdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: kinetis_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the KwikStik-K40 board.
+ *
+ ************************************************************************************/
+
+void weak_function kinetis_spiinitialize(void)
+{
+# warning "Missing logic"
+}
+
+/****************************************************************************
+ * Name: kinetis_spi1/2/3select and kinetis_spi1/2/3status
+ *
+ * Description:
+ * The external functions, kinetis_spi1/2/3select and kinetis_spi1/2/3status must be
+ * provided by board-specific logic. They are implementations of the select
+ * and status methods of the SPI interface defined by struct spi_ops_s (see
+ * include/nuttx/spi.h). All other methods (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 chip select
+ * pins.
+ * 2. Provide kinetis_spi1/2/3select() and kinetis_spi1/2/3status() functions in your
+ * board-specific logic. These functions will perform chip selection and
+ * status operations using GPIOs in the way your board is configured.
+ * 3. Add a calls to up_spiinitialize() in your low level application
+ * initialization logic
+ * 4. The handle returned by up_spiinitialize() may then be used to bind the
+ * SPI driver to higher level logic (e.g., calling
+ * mmcsd_spislotinitialize(), for example, will bind the SPI driver to
+ * the SPI MMC/SD driver).
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_KINETIS_SPI1
+void kinetis_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+# warning "Missing logic"
+}
+
+uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+# warning "Missing logic"
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#ifdef CONFIG_KINETIS_SPI2
+void kinetis_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+# warning "Missing logic"
+}
+
+uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+# warning "Missing logic"
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#ifdef CONFIG_KINETIS_SPI3
+void kinetis_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+# warning "Missing logic"
+}
+
+uint8_t kinetis_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+# warning "Missing logic"
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#endif /* CONFIG_KINETIS_SPI1 || CONFIG_KINETIS_SPI2 */
diff --git a/nuttx/configs/kwikstik-k40/src/up_usbdev.c b/nuttx/configs/kwikstik-k40/src/up_usbdev.c
new file mode 100644
index 000000000..60e54af7c
--- /dev/null
+++ b/nuttx/configs/kwikstik-k40/src/up_usbdev.c
@@ -0,0 +1,115 @@
+/************************************************************************************
+ * configs/kwikstik-k40/src/up_usbdev.c
+ * arch/arm/src/board/up_boot.c
+ *
+ * Copyright (C) 2011 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 <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/usb/usbdev.h>
+#include <nuttx/usb/usbdev_trace.h>
+
+#include "up_arch.h"
+#include "kinetis_internal.h"
+#include "kwikstik-internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: kinetis_usbinitialize
+ *
+ * Description:
+ * Called to setup USB-related GPIO pins for the KwikStik-K40 board.
+ *
+ ************************************************************************************/
+
+void kinetis_usbinitialize(void)
+{
+# warning "Missing logic"
+}
+
+/************************************************************************************
+ * Name: kinetis_usbpullup
+ *
+ * Description:
+ * If USB is supported and the board supports a pullup via GPIO (for USB software
+ * connect and disconnect), then the board software must provide kinetis_pullup.
+ * See include/nuttx/usb/usbdev.h for additional description of this method.
+ * Alternatively, if no pull-up GPIO the following EXTERN can be redefined to be
+ * NULL.
+ *
+ ************************************************************************************/
+
+int kinetis_usbpullup(FAR struct usbdev_s *dev, bool enable)
+{
+ usbtrace(TRACE_DEVPULLUP, (uint16_t)enable);
+# warning "Missing logic"
+ return OK;
+}
+
+/************************************************************************************
+ * Name: kinetis_usbsuspend
+ *
+ * Description:
+ * Board logic must provide the kinetis_usbsuspend logic if the USBDEV driver is
+ * used. This function is called whenever the USB enters or leaves suspend mode.
+ * This is an opportunity for the board logic to shutdown clocks, power, etc.
+ * while the USB is suspended.
+ *
+ ************************************************************************************/
+
+void kinetis_usbsuspend(FAR struct usbdev_s *dev, bool resume)
+{
+ ulldbg("resume: %d\n", resume);
+#warning "Missing logic"
+}
+
diff --git a/nuttx/configs/kwikstik-k40/src/up_usbstrg.c b/nuttx/configs/kwikstik-k40/src/up_usbstrg.c
new file mode 100755
index 000000000..d5dcebf7a
--- /dev/null
+++ b/nuttx/configs/kwikstik-k40/src/up_usbstrg.c
@@ -0,0 +1,118 @@
+/****************************************************************************
+ * configs/kwikstik-k40/src/up_usbstrg.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Configure and register the Kinetis MMC/SD block driver.
+ *
+ * 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 <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/sdio.h>
+#include <nuttx/mmcsd.h>
+
+#include "kinetis_internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_EXAMPLES_USBSTRG_DEVMINOR1
+# define CONFIG_EXAMPLES_USBSTRG_DEVMINOR1 0
+#endif
+
+/* SLOT number(s) could depend on the board configuration */
+
+#ifdef CONFIG_ARCH_BOARD_KWIKSTIK_K40
+# undef KINETIS_MMCSDSLOTNO
+# define KINETIS_MMCSDSLOTNO 0
+#else
+ /* Add configuration for new Kinetis boards here */
+# error "Unrecognized Kinetis board"
+#endif
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lib_lowprintf(__VA_ARGS__)
+# define msgflush()
+# else
+# define message(...) printf(__VA_ARGS__)
+# define msgflush() fflush(stdout)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lib_lowprintf
+# define msgflush()
+# else
+# define message printf
+# define msgflush() fflush(stdout)
+# endif
+#endif
+
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: usbstrg_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+int usbstrg_archinitialize(void)
+{
+ /* If examples/usbstrg is built as an NSH command, then SD slot should
+ * already have been initized in nsh_archinitialize() (see up_nsh.c). In
+ * this case, there is nothing further to be done here.
+ */
+
+#ifndef CONFIG_EXAMPLES_USBSTRG_BUILTIN
+# warning "Missing logic"
+#endif /* CONFIG_EXAMPLES_USBSTRG_BUILTIN */
+
+ return OK;
+}