Initial cut of a driver for the TI CC3000 network module with support on the Freescale KL25Z board from Alan Carvalho de Assis

This commit is contained in:
Gregory Nutt 2013-09-03 14:59:48 -06:00
parent 7c34498c01
commit 47462f8238
5 changed files with 336 additions and 38 deletions

View File

@ -182,9 +182,18 @@
* alternative.
*/
#define PIN_SPI0_SCK PIN_SPI0_SCK_2
#define PIN_SPI0_MISO PIN_SPI0_MISO_4
#define PIN_SPI0_MOSI PIN_SPI0_MOSI_3
#define PIN_SPI0_SCK (PIN_SPI0_SCK_2 | PIN_ALT2_PULLUP)
#define PIN_SPI0_MISO (PIN_SPI0_MISO_4 | PIN_ALT2_PULLUP)
#define PIN_SPI0_MOSI (PIN_SPI0_MOSI_3 | PIN_ALT2_PULLUP)
#define PIN_SPI1_SCK (PIN_SPI1_SCK_2 | PIN_ALT2_PULLUP)
#define PIN_SPI1_MISO (PIN_SPI1_MISO_3 | PIN_ALT2_PULLUP)
#define PIN_SPI1_MOSI (PIN_SPI0_MOSI_7 | PIN_ALT2_PULLUP)
/* These pins are used by CC3000 module */
#define GPIO_WIFI_EN (GPIO_OUTPUT | GPIO_OUTPUT_ZER0 | PIN_PORTC | PIN12)
#define GPIO_WIFI_IRQ (GPIO_INPUT | PIN_PORTA | PIN16)
#define GPIO_WIFI_CS (GPIO_OUTPUT | GPIO_OUTPUT_ONE | PIN_PORTE | PIN1)
/************************************************************************************
* Public Data

View File

@ -0,0 +1,80 @@
/****************************************************************************
* configs/freedom-kl25z/include/kl_wifi.h
*
* Copyright (C) 2013 Alan Carvalho de Assis
* Author: Alan Carvalho de Assis <acassis@gmail.com>
* with adaptions from Gregory Nutt <gnutt@nuttx.org>
*
* Reference: https://community.freescale.com/community/
* the-embedded-beat/blog/2012/10/15/
* using-the-touch-interface-on-the-freescale-freedom-development-platform
*
* 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 <stdio.h>
#include <stdint.h>
long ReadWlanInterruptPin(void);
/*
* Enable WiFi Interrupt
*/
void WlanInterruptEnable(void);
/*
* Disable WiFi Interrupt
*/
void WlanInterruptDisable(void);
/*
* Enable/Disable WiFi
*/
void WriteWlanEnablePin(uint8_t val);
/*
* Assert CC3000 CS
*/
void AssertWlanCS(void);
/*
* Deassert CC3000 CS
*/
void DeassertWlanCS(void);
/*
* Setup needed pins
*/
void Wlan_Setup(void);

View File

@ -16,14 +16,14 @@ CONFIG_HOST_LINUX=y
#
# Build Configuration
#
# CONFIG_APPS_DIR="../apps"
CONFIG_APPS_DIR="../apps"
# CONFIG_BUILD_2PASS is not set
#
# Binary Output Formats
#
# CONFIG_RRLOAD_BINARY is not set
# CONFIG_INTELHEX_BINARY=y
# CONFIG_INTELHEX_BINARY is not set
CONFIG_MOTOROLA_SREC=y
CONFIG_RAW_BINARY=y
@ -73,23 +73,31 @@ CONFIG_ARCH_CHIP_KL=y
# CONFIG_ARCH_CHIP_LPC31XX is not set
# CONFIG_ARCH_CHIP_LPC43XX is not set
# CONFIG_ARCH_CHIP_NUC1XX is not set
# CONFIG_ARCH_CHIP_SAM3U is not set
# CONFIG_ARCH_CHIP_SAMA5 is not set
# CONFIG_ARCH_CHIP_SAM34 is not set
# CONFIG_ARCH_CHIP_STM32 is not set
# CONFIG_ARCH_CHIP_STR71X is not set
# CONFIG_ARCH_ARM7TDMI is not set
# CONFIG_ARCH_ARM926EJS is not set
# CONFIG_ARCH_ARM920T is not set
CONFIG_ARCH_CORTEXM0=y
# CONFIG_ARCH_CORTEXM3 is not set
# CONFIG_ARCH_CORTEXM4 is not set
# CONFIG_ARCH_CORTEXA5 is not set
CONFIG_ARCH_FAMILY="armv6-m"
CONFIG_ARCH_CHIP="kl"
CONFIG_ARCH_HAVE_CMNVECTOR=y
# CONFIG_ARMV7M_CMNVECTOR is not set
# CONFIG_ARCH_HAVE_FPU is not set
# CONFIG_ARCH_HAVE_MPU is not set
#
# ARMV6M Configuration Options
#
CONFIG_ARMV6M_TOOLCHAIN_BUILDROOT=y
# CONFIG_ARMV6M_TOOLCHAIN_BUILDROOT is not set
# CONFIG_ARMV6M_TOOLCHAIN_CODEREDL is not set
# CONFIG_ARMV6M_TOOLCHAIN_CODESOURCERYL is not set
# CONFIG_ARMV6M_TOOLCHAIN_GNU_EABIL is not set
CONFIG_ARMV6M_TOOLCHAIN_GNU_EABIL=y
# CONFIG_GPIO_IRQ is not set
#
@ -106,13 +114,10 @@ CONFIG_ARCH_FAMILY_KL2X=y
CONFIG_KL_UART0=y
# CONFIG_KL_UART1 is not set
# CONFIG_KL_UART2 is not set
# CONFIG_KL_UART3 is not set
# CONFIG_KL_UART4 is not set
# CONFIG_KL_UART5 is not set
# CONFIG_KL_FLEXCAN0 is not set
# CONFIG_KL_FLEXCAN1 is not set
# CONFIG_KL_SPI0 is not set
# CONFIG_KL_SPI1 is not set
CONFIG_KL_SPI0=y
CONFIG_KL_SPI1=y
# CONFIG_KL_SPI2 is not set
# CONFIG_KL_I2C0 is not set
# CONFIG_KL_I2C1 is not set
@ -123,10 +128,9 @@ CONFIG_KL_UART0=y
# CONFIG_KL_ADC1 is not set
# CONFIG_KL_CMP is not set
# CONFIG_KL_VREF is not set
# CONFIG_KL_SDHC is not set
# CONFIG_KL_FTM0 is not set
# CONFIG_KL_FTM1 is not set
# CONFIG_KL_FTM2 is not set
# CONFIG_KL_TPM0 is not set
# CONFIG_KL_TPM1 is not set
# CONFIG_KL_TPM2 is not set
# CONFIG_KL_LPTIMER is not set
# CONFIG_KL_RTC is not set
# CONFIG_KL_EWM is not set
@ -141,20 +145,12 @@ CONFIG_KL_UART0=y
# CONFIG_KL_PDB is not set
# CONFIG_KL_PIT is not set
CONFIG_KL_SYSTICK_CORECLK=y
# CONFIG_KL_SYSTICK_CORECLK_DIV16 is not set
#
# Kinetis GPIO Interrupt Configuration
#
#
# Kinetis UART Configuration
#
# CONFIG_KL_UARTFIFOS is not set
#
# External Memory Configuration
#
#
# Architecture Options
#
@ -175,8 +171,6 @@ CONFIG_ARCH_STACKDUMP=y
#
CONFIG_BOARD_LOOPSPERMSEC=2988
# CONFIG_ARCH_CALIBRATION is not set
CONFIG_RAM_START=0x1FFFF000
CONFIG_RAM_SIZE=16384
CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
CONFIG_ARCH_INTERRUPTSTACK=0
@ -189,6 +183,12 @@ CONFIG_BOOT_RUNFROMFLASH=y
# CONFIG_BOOT_RUNFROMSDRAM is not set
# CONFIG_BOOT_COPYTORAM is not set
#
# Boot Memory Configuration
#
CONFIG_RAM_START=0x1FFFF000
CONFIG_RAM_SIZE=16384
#
# Board Selection
#
@ -281,10 +281,15 @@ CONFIG_DEV_NULL=y
# CONFIG_CAN is not set
# CONFIG_PWM is not set
# CONFIG_I2C is not set
# CONFIG_SPI is not set
CONFIG_SPI=y
# CONFIG_SPI_OWNBUS is not set
CONFIG_SPI_EXCHANGE=y
# CONFIG_SPI_CMDDATA is not set
# CONFIG_SPI_BITBANG is not set
# CONFIG_RTC is not set
# CONFIG_WATCHDOG is not set
# CONFIG_ANALOG is not set
# CONFIG_AUDIO_DEVICES is not set
# CONFIG_BCH is not set
# CONFIG_INPUT is not set
# CONFIG_LCD is not set
@ -294,11 +299,14 @@ CONFIG_DEV_NULL=y
# CONFIG_PM is not set
# CONFIG_POWER is not set
# CONFIG_SENSORS is not set
# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
# CONFIG_16550_UART is not set
CONFIG_ARCH_HAVE_UART0=y
#
# USART Configuration
#
CONFIG_MCU_SERIAL=y
CONFIG_STANDARD_SERIAL=y
CONFIG_UART0_SERIAL_CONSOLE=y
@ -313,9 +321,16 @@ CONFIG_UART0_BAUD=115200
CONFIG_UART0_BITS=8
CONFIG_UART0_PARITY=0
CONFIG_UART0_2STOP=0
# CONFIG_UART0_IFLOWCONTROL is not set
# CONFIG_UART0_OFLOWCONTROL is not set
# CONFIG_SERIAL_IFLOWCONTROL is not set
# CONFIG_SERIAL_OFLOWCONTROL is not set
# CONFIG_USBDEV is not set
# CONFIG_USBHOST is not set
# CONFIG_WIRELESS is not set
CONFIG_WIRELESS=y
# CONFIG_WL_CC1101 is not set
CONFIG_WL_CC3000=y
# CONFIG_WL_NRF24L01 is not set
#
# System Logging Device Options
@ -340,6 +355,7 @@ CONFIG_UART0_2STOP=0
#
CONFIG_DISABLE_MOUNTPOINT=y
# CONFIG_FS_RAMMAP is not set
# CONFIG_FS_BINFS is not set
#
# System Logging
@ -360,10 +376,18 @@ CONFIG_MM_SMALL=y
CONFIG_MM_REGIONS=1
# CONFIG_GRAN is not set
#
# Audio Support
#
# CONFIG_AUDIO is not set
#
# Binary Formats
#
CONFIG_BINFMT_DISABLE=y
# CONFIG_BINFMT_DISABLE is not set
# CONFIG_NXFLAT is not set
# CONFIG_ELF is not set
CONFIG_BUILTIN=y
# CONFIG_PIC is not set
# CONFIG_SYMTAB_ORDEREDBYNAME is not set
@ -380,10 +404,12 @@ CONFIG_NUNGET_CHARS=0
# CONFIG_LIBM is not set
# CONFIG_NOPRINTF_FIELDWIDTH is not set
# CONFIG_LIBC_FLOATINGPOINT is not set
CONFIG_LIB_RAND_ORDER=1
# CONFIG_EOL_IS_CR is not set
# CONFIG_EOL_IS_LF is not set
# CONFIG_EOL_IS_BOTH_CRLF is not set
CONFIG_EOL_IS_EITHER_CRLF=y
# CONFIG_LIBC_EXECFUNCS is not set
CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024
CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=1536
# CONFIG_LIBC_STRERROR is not set
@ -398,6 +424,7 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
#
# CONFIG_SCHED_WORKQUEUE is not set
# CONFIG_LIB_KBDCODEC is not set
# CONFIG_LIB_SLCDCODEC is not set
#
# Basic CXX Support
@ -412,12 +439,14 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
#
# Built-In Applications
#
CONFIG_BUILTIN_PROXY_STACKSIZE=1024
#
# Examples
#
# CONFIG_EXAMPLES_BUTTONS is not set
# CONFIG_EXAMPLES_CAN is not set
CONFIG_EXAMPLES_CC3000BASIC=y
# CONFIG_EXAMPLES_COMPOSITE is not set
# CONFIG_EXAMPLES_DHCPD is not set
# CONFIG_EXAMPLES_ELF is not set
@ -431,8 +460,9 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
# CONFIG_EXAMPLES_IGMP is not set
# CONFIG_EXAMPLES_LCDRW is not set
# CONFIG_EXAMPLES_MM is not set
# CONFIG_EXAMPLES_MOUNT is not set
# CONFIG_EXAMPLES_MODBUS is not set
# CONFIG_EXAMPLES_MOUNT is not set
# CONFIG_EXAMPLES_NRF24L01TERM is not set
CONFIG_EXAMPLES_NSH=y
# CONFIG_EXAMPLES_NULL is not set
# CONFIG_EXAMPLES_NX is not set
@ -446,13 +476,16 @@ CONFIG_EXAMPLES_NSH=y
# CONFIG_EXAMPLES_OSTEST is not set
# CONFIG_EXAMPLES_PASHELLO is not set
# CONFIG_EXAMPLES_PIPE is not set
# CONFIG_EXAMPLES_POLL is not set
# CONFIG_EXAMPLES_POSIXSPAWN is not set
# CONFIG_EXAMPLES_QENCODER is not set
# CONFIG_EXAMPLES_RGMP is not set
# CONFIG_EXAMPLES_ROMFS is not set
# CONFIG_EXAMPLES_SENDMAIL is not set
# CONFIG_EXAMPLES_SERLOOP is not set
# CONFIG_EXAMPLES_SLCD is not set
# CONFIG_EXAMPLES_SMART_TEST is not set
# CONFIG_EXAMPLES_SMART is not set
# CONFIG_EXAMPLES_TCPECHO is not set
# CONFIG_EXAMPLES_TELNETD is not set
# CONFIG_EXAMPLES_THTTPD is not set
# CONFIG_EXAMPLES_TIFF is not set
@ -505,6 +538,7 @@ CONFIG_EXAMPLES_NSH=y
# NSH Library
#
CONFIG_NSH_LIBRARY=y
CONFIG_NSH_BUILTIN_APPS=y
#
# Disable Individual commands
@ -512,6 +546,7 @@ CONFIG_NSH_LIBRARY=y
# CONFIG_NSH_DISABLE_CAT is not set
CONFIG_NSH_DISABLE_CD=y
CONFIG_NSH_DISABLE_CP=y
# CONFIG_NSH_DISABLE_CMP is not set
CONFIG_NSH_DISABLE_DD=y
# CONFIG_NSH_DISABLE_ECHO is not set
# CONFIG_NSH_DISABLE_EXEC is not set
@ -548,9 +583,15 @@ CONFIG_NSH_DISABLE_UMOUNT=y
# CONFIG_NSH_DISABLE_USLEEP is not set
CONFIG_NSH_DISABLE_WGET=y
# CONFIG_NSH_DISABLE_XD is not set
#
# Configure Command Options
#
# CONFIG_NSH_CMDOPT_DF_H is not set
CONFIG_NSH_CODECS_BUFSIZE=128
CONFIG_NSH_FILEIOSIZE=64
CONFIG_NSH_LINELEN=80
CONFIG_NSH_MAXARGUMENTS=6
CONFIG_NSH_NESTDEPTH=3
CONFIG_NSH_DISABLESCRIPT=y
# CONFIG_NSH_DISABLEBG is not set
@ -560,7 +601,7 @@ CONFIG_NSH_CONSOLE=y
# USB Trace Support
#
# CONFIG_NSH_CONDEV is not set
# CONFIG_NSH_ARCHINIT is not set
CONFIG_NSH_ARCHINIT=y
#
# NxWidgets/NxWM
@ -585,7 +626,11 @@ CONFIG_NSH_CONSOLE=y
# CONFIG_SYSTEM_INSTALL is not set
#
# RAM Test
# FLASH Erase-all Command
#
#
# RAM test
#
# CONFIG_SYSTEM_RAMTEST is not set
@ -618,3 +663,8 @@ CONFIG_READLINE_ECHO=y
#
# USB Monitor
#
#
# Zmodem Commands
#
# CONFIG_SYSTEM_ZMODEM is not set

View File

@ -40,13 +40,13 @@ CFLAGS += -I$(TOPDIR)/sched
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
CSRCS = kl_boardinitialize.c
CSRCS = kl_boardinitialize.c kl_wifi.c
ifeq ($(CONFIG_KL_TSI),y)
CSRCS += kl_tsi.c
endif
ifeq ($(CONFIG_KL_SPI0),y)
ifeq ($(CONFIG_KL_SPI),y)
CSRCS += kl_spi.c
endif

View File

@ -0,0 +1,159 @@
/****************************************************************************
* configs/freedom-kl25z/src/kl_tsi.c
*
* Copyright (C) 2013 Alan Carvalho de Assis
* Author: Alan Carvalho de Assis <acassis@gmail.com>
*
*
* 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 <arch/board/kl_wifi.h>
#include <stdio.h>
#include <stdint.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <nuttx/fs/fs.h>
#include <nuttx/cc3000/spi.h>
#include "up_arch.h"
#include "kl_gpio.h"
#include "chip/kl_pinmux.h"
#include "chip/kl_sim.h"
#include "freedom-kl25z.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/*
* Used by CC3000 driver to read status of WIFI_IRQ
*/
inline long ReadWlanInterruptPin(void)
{
// Return the status of WIFI_IRQ pin
return kl_gpioread(GPIO_WIFI_IRQ);
}
/*
* Enable/Disable WiFi
*/
void WriteWlanEnablePin(uint8_t val)
{
kl_gpiowrite(GPIO_WIFI_EN, val);
}
/*
* Assert CC3000 CS
*/
void AssertWlanCS(void)
{
kl_gpiowrite(GPIO_WIFI_CS, false);
}
/*
* Deassert CC3000 CS
*/
void DeassertWlanCS(void)
{
kl_gpiowrite(GPIO_WIFI_CS, true);
}
/****************************************************************************
* Name: Wlan_Setup
*
* Description:
* Initialize all pins needed to control CC3000 Module and attach to IRQ
*
****************************************************************************/
void Wlan_Setup(void)
{
int ret;
uint32_t regval;
printf("\nExecuting kl_irq_initialize!\n");
/* Configure the PIN used to enable the chip */
kl_configgpio(GPIO_WIFI_EN);
/* Configure PIN to detect interrupts */
kl_configgpio(GPIO_WIFI_IRQ);
/* Configure PIN used as SPI CS */
kl_configgpio(GPIO_WIFI_CS);
/* Make sure the chip is OFF before we start */
WriteWlanEnablePin(false);
/* Make sure the SPI CS pin is deasserted */
DeassertWlanCS();
/* Configure pin to detect interrupt on falling edge */
regval = getreg32(KL_PORTA_PCR16);
regval |= PORT_PCR_IRQC_FALLING;
putreg32(regval, KL_PORTA_PCR16);
ret = irq_attach(KL_IRQ_PORTA, CC3000InterruptHandler);
if (ret == OK)
{
up_enable_irq(KL_IRQ_PORTA);
}
}