summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorJakob Odersky <jodersky@gmail.com>2015-01-13 18:24:50 +0100
committerJakob Odersky <jodersky@gmail.com>2015-01-13 18:24:50 +0100
commit98abac5fc449be03c165fe9945b186008fcc39bc (patch)
tree306ca742813e2968db2fe12944bcd2c641f78c93
parent6d81b46da2e9ac74c3a7e4abed78e159b336eb5b (diff)
downloadnuttx-98abac5fc449be03c165fe9945b186008fcc39bc.tar.gz
nuttx-98abac5fc449be03c165fe9945b186008fcc39bc.tar.bz2
nuttx-98abac5fc449be03c165fe9945b186008fcc39bc.zip
trim teensy31 config
-rwxr-xr-xnuttx/configs/teensy31/scripts/ld.script1
-rw-r--r--nuttx/configs/teensy31/src/Makefile2
-rw-r--r--nuttx/configs/teensy31/src/cfmconfig.c27
-rw-r--r--nuttx/configs/teensy31/src/kwikstik-internal.h195
-rw-r--r--nuttx/configs/teensy31/src/up_boot.c1
-rw-r--r--nuttx/configs/teensy31/src/up_buttons.c126
-rw-r--r--nuttx/configs/teensy31/src/up_lcd.c134
-rw-r--r--nuttx/configs/teensy31/src/up_leds.c3
-rw-r--r--nuttx/configs/teensy31/src/up_spi.c164
9 files changed, 32 insertions, 621 deletions
diff --git a/nuttx/configs/teensy31/scripts/ld.script b/nuttx/configs/teensy31/scripts/ld.script
index 338a028dd..f3864f5f5 100755
--- a/nuttx/configs/teensy31/scripts/ld.script
+++ b/nuttx/configs/teensy31/scripts/ld.script
@@ -70,6 +70,7 @@ SECTIONS
} > cfmprotect
.text : {
+ . = ALIGN(4);
_stext = ABSOLUTE(.);
*(.text .text.*)
*(.fixup)
diff --git a/nuttx/configs/teensy31/src/Makefile b/nuttx/configs/teensy31/src/Makefile
index e4edfb0c5..a3ce81ff6 100644
--- a/nuttx/configs/teensy31/src/Makefile
+++ b/nuttx/configs/teensy31/src/Makefile
@@ -40,7 +40,7 @@ CFLAGS += -I$(TOPDIR)/sched
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
-CSRCS = up_boot.c up_lcd.c up_spi.c
+CSRCS = up_boot.c cfmconfig.c
ifeq ($(CONFIG_ARCH_LEDS),y)
CSRCS += up_leds.c
diff --git a/nuttx/configs/teensy31/src/cfmconfig.c b/nuttx/configs/teensy31/src/cfmconfig.c
new file mode 100644
index 000000000..1cd54c5cc
--- /dev/null
+++ b/nuttx/configs/teensy31/src/cfmconfig.c
@@ -0,0 +1,27 @@
+/* Barely based on "bare metal" sample from Freedom board:
+Copyright (c) 2012-2013 Andrew Payne
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights to
+use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
+the Software, and to permit persons to whom the Software is furnished to do so,
+subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
+FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
+COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
+IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION
+WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. */
+
+#include <stdint.h>
+
+__attribute__ ((section(".cfmconfig")))
+const uint8_t __flashconfigbytes[16] = {
+ 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
+ 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF
+};
diff --git a/nuttx/configs/teensy31/src/kwikstik-internal.h b/nuttx/configs/teensy31/src/kwikstik-internal.h
deleted file mode 100644
index 0a97471af..000000000
--- a/nuttx/configs/teensy31/src/kwikstik-internal.h
+++ /dev/null
@@ -1,195 +0,0 @@
-/************************************************************************************
- * configs/kwikstik-k40/src/kwikstik-internal.h
- * arch/arm/src/board/kwikstik-internal.h
- *
- * Copyright (C) 2011 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.
- *
- ************************************************************************************/
-
-#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 ***************************************************************/
-/* On-Board Connections
- *
- * ------------------- -------------------------- -------- -------------------
- * FEATURE CONNECTION PORT/PIN PIN FUNCTION
- * ------------------- -------------------------- -------- -------------------
- * Audio Jack Output Audio Amp On PTE28 PTE28
- * Audio Output DAC1_OUT DAC1_OUT
- * Volume Up PTD10 PTD10
- * Volume Down PTD11 PTD11
- * Buzzer Audio Out PTA8 FTM1_CH0
- * Microphone Microphone input PTA7 ADC0_SE10
- * SD Card Slot SD Clock PTE2 SDHC0_DCLK
- * SD Command PTE3 SDHC0_CMD
- * SD Data0 PTD12 SDHC0_D4
- * SD Data1 PTD13 SDHC0_D5
- * SD Data2 PTD14 SDHC0_D6
- * SD Data3 PTD15 SDHC0_D7
- * SD Card Detect PTE27 PTE27
- * SD Card On PTE6 PTE6
- * Infrared Port IR Transmit PTE4 IR_TX
- * IR Receive PTA13 CMP2_IN0
- * Touch Pads E1 / Touch PTB0 TSI0_CH0
- * E2 / Touch PTA4 TSI0_CH5
- * E3 / Touch PTA24 PTA24
- * E4 / Touch PTA25 PTA25
- * E5 / Touch PTA26 PTA26
- * E6 / Touch PTA27 PTA27
- */
-
-#define GPIO_SD_CARDDETECT (GPIO_PULLUP | PIN_INT_BOTH | PIN_PORTE | PIN27)
-#define GPIO_SD_CARDON (GPIO_HIGHDRIVE | GPIO_OUTPUT_ZER0 | PIN_PORTE | PIN6)
-
-/* Connections via the General Purpose Tower Plug-in (TWRPI) Socket
- * ------------------- -------------------------- -------- -------------------
- * FEATURE CONNECTION PORT/PIN PIN FUNCTION
- * ------------------- -------------------------- -------- -------------------
- * General Purpose TWRPI AN0 (J8 Pin 8) ? ADC0_DP0/ADC1_DP3
- * TWRPI Socket TWRPI AN1 (J8 Pin 9) ? ADC0_DM0/ADC1_DM3
- * TWRPI AN2 (J8 Pin 12) ? ADC1_DP0/ADC0_DP3
- * TWRPI ID0 (J8 Pin 17) ? ADC0_DP1
- * TWRPI ID1 (J8 Pin 18) ? ADC0_DM1
- * TWRPI I2C SCL (J9 Pin 3) PTC10 I2C1_SCL
- * TWRPI I2C SDA (J9 Pin 4) PTC11 I2C1_SDA
- * TWRPI SPI MISO (J9 Pin 9) PTB23 SPI2_SIN
- * TWRPI SPI MOSI (J9 Pin 10) PTB22 SPI2_SOUT
- * TWRPI SPI SS (J9 Pin 11) PTB20 SPI2_PCS0
- * TWRPI SPI CLK (J9 Pin 12) PTB21 SPI2_SCK
- * TWRPI GPIO0 (J9 Pin 15) PTC12 PTC12
- * TWRPI GPIO1 (J9 Pin 16) PTB9 PTB9
- * TWRPI GPIO2 (J9 Pin 17) PTB10 PTB10
- * TWRPI GPIO3 (J9 Pin 18) PTC5 PTC5
- * TWRPI GPIO4 (J9 Pin 19) PTA5 PTA5
- */
-
-/* Connections via the Tower Primary Connector Side A
- * --- -------------------- --------------------------------
- * PIN NAME USAGE
- * --- -------------------- --------------------------------
- * A9 GPIO9 / CTS1 PTE10/UART_CTS
- * A43 RXD1 PTE9/UART_RX
- * A44 TXD1 PTE8/UART_TX
- * A63 RSTOUT_b PTA9/FTM1_CH1
- */
-
-/* Connections via the Tower Primary Connector Side B
- * --- -------------------- --------------------------------
- * PIN NAME USAGE
- * --- -------------------- --------------------------------
- * B21 GPIO1 / RTS1 PTE7/UART_RTS
- * B37 PWM7 PTA8/FTM1_CH0
- * B38 PWM6 PTA9/FTM1_CH1
- * B41 CANRX0 PTE25/CAN1_RX
- * B42 CANTX0 PTE24/CAN1_TX
- * B44 SPI0_MISO PTA17/SPI0_SIN
- * B45 SPI0_MOSI PTA16/SPI0_SOUT
- * B46 SPI0_CS0_b PTA14/SPI0_PCS0
- * B48 SPI0_CLK PTA15/SPI0_SCK
- * B50 SCL1 PTE1/I2C1_SCL
- * B51 SDA1 PTE0/I2C1_SDA
- * B52 GPIO5 / SD_CARD_DET PTA16
- */
-
-/************************************************************************************
- * Public Types
- ************************************************************************************/
-
-/************************************************************************************
- * Public data
- ************************************************************************************/
-
-#ifndef __ASSEMBLY__
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Name: board_led_initialize
- *
- * Description:
- * Initialize LED GPIOs so that LEDs can be controlled.
- *
- ************************************************************************************/
-
-#ifdef CONFIG_ARCH_LEDS
-extern void board_led_initialize(void);
-#endif
-
-/************************************************************************************
- * 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/teensy31/src/up_boot.c b/nuttx/configs/teensy31/src/up_boot.c
index e95045674..4b1c55537 100644
--- a/nuttx/configs/teensy31/src/up_boot.c
+++ b/nuttx/configs/teensy31/src/up_boot.c
@@ -45,7 +45,6 @@
#include <arch/board/board.h>
#include "up_arch.h"
-#include "kwikstik-internal.h"
/************************************************************************************
* Definitions
diff --git a/nuttx/configs/teensy31/src/up_buttons.c b/nuttx/configs/teensy31/src/up_buttons.c
deleted file mode 100644
index a82d55ca2..000000000
--- a/nuttx/configs/teensy31/src/up_buttons.c
+++ /dev/null
@@ -1,126 +0,0 @@
-/****************************************************************************
- * configs/kwikstik-k40/src/board_buttons.c
- *
- * Copyright (C) 2011, 2014 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <stdint.h>
-
-#include <nuttx/arch.h>
-#include <arch/board/board.h>
-
-#include "kwikstik-internal.h"
-
-#ifdef CONFIG_ARCH_BUTTONS
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: board_button_initialize
- *
- * Description:
- * board_button_initialize() must be called to initialize button resources.
- * After that, board_buttons() may be called to collect the current state of
- * all buttons or board_button_irq() may be called to register button interrupt
- * handlers.
- *
- ****************************************************************************/
-
-void board_button_initialize(void)
-{
- /* The KwikStik-K40 board has no standard GPIO contact buttons */
-}
-
-/****************************************************************************
- * Name: board_buttons
- ****************************************************************************/
-
-uint8_t board_buttons(void)
-{
- /* The KwikStik-K40 board has no standard GPIO contact buttons */
-
- return 0;
-}
-
-/****************************************************************************
- * Button support.
- *
- * Description:
- * board_button_initialize() must be called to initialize button resources.
- * After that, board_buttons() may be called to collect the current state of
- * all buttons or board_button_irq() may be called to register button interrupt
- * handlers.
- *
- * After board_button_initialize() has been called, board_buttons() may be
- * called to collect the state of all buttons. board_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.
- *
- * board_button_irq() 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 be restored, if so desired).
- *
- ****************************************************************************/
-
-#ifdef CONFIG_ARCH_IRQBUTTONS
-xcpt_t board_button_irq(int id, xcpt_t irqhandler)
-{
- /* The KwikStik-K40 board has no standard GPIO contact buttons */
-
- return NULL;
-}
-#endif
-#endif /* CONFIG_ARCH_BUTTONS */
diff --git a/nuttx/configs/teensy31/src/up_lcd.c b/nuttx/configs/teensy31/src/up_lcd.c
deleted file mode 100644
index 2e28701af..000000000
--- a/nuttx/configs/teensy31/src/up_lcd.c
+++ /dev/null
@@ -1,134 +0,0 @@
-/**************************************************************************************
- * 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 <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.
- *
- **************************************************************************************/
-
-/**************************************************************************************
- * Included Files
- **************************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <sys/types.h>
-#include <assert.h>
-#include <debug.h>
-
-#include <arch/board/board.h>
-
-#include "up_arch.h"
-#include "kwikstik-internal.h"
-
-
-/**************************************************************************************
- * Pre-processor Definitions
- **************************************************************************************/
-
-/* Configuration **********************************************************************/
-
-/* Display/Color Properties ***********************************************************/
-
-/* Debug ******************************************************************************/
-
-#ifdef CONFIG_DEBUG_LCD
-# define lcddbg(format, ...) vdbg(format, ##__VA_ARGS__)
-#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/teensy31/src/up_leds.c b/nuttx/configs/teensy31/src/up_leds.c
index 4b98a0cb4..80a5aac50 100644
--- a/nuttx/configs/teensy31/src/up_leds.c
+++ b/nuttx/configs/teensy31/src/up_leds.c
@@ -106,6 +106,9 @@ void board_led_initialize(void)
PORTC_PCR5 = PORT_PCR_SRE | PORT_PCR_DSE | PORT_PCR_MUX(1); // set to gpio
GPIOC_PDDR |= (1 << 5); // set to output
GPIOC_PSOR |= (1 << 5); // set high
+ while(1) {
+
+ }
}
/****************************************************************************
diff --git a/nuttx/configs/teensy31/src/up_spi.c b/nuttx/configs/teensy31/src/up_spi.c
deleted file mode 100644
index acb1ca1c9..000000000
--- a/nuttx/configs/teensy31/src/up_spi.c
+++ /dev/null
@@ -1,164 +0,0 @@
-/************************************************************************************
- * 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 <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.
- *
- ************************************************************************************/
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <debug.h>
-
-#include <nuttx/spi/spi.h>
-#include <arch/board/board.h>
-
-#include "up_arch.h"
-#include "chip.h"
-#include "kinetis_internal.h"
-#include "kwikstik-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/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 */