Add hooks for SD media change callbacks

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4267 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2012-01-06 01:58:03 +00:00
parent 7de5004f47
commit ad270ba835
4 changed files with 397 additions and 205 deletions

View File

@ -655,6 +655,7 @@ EXTERN void ssp_flush(FAR struct spi_dev_s *dev);
* *
****************************************************************************/ ****************************************************************************/
#ifdef CONFIG_SPI_CALLBACK
#ifdef CONFIG_LPC17_SPI #ifdef CONFIG_LPC17_SPI
EXTERN int lpc17_spiregister(FAR struct spi_dev_s *dev, EXTERN int lpc17_spiregister(FAR struct spi_dev_s *dev,
spi_mediachange_t callback, void *arg); spi_mediachange_t callback, void *arg);
@ -669,6 +670,7 @@ EXTERN int lpc17_ssp0register(FAR struct spi_dev_s *dev,
EXTERN int lpc17_ssp1register(FAR struct spi_dev_s *dev, EXTERN int lpc17_ssp1register(FAR struct spi_dev_s *dev,
spi_mediachange_t callback, void *arg); spi_mediachange_t callback, void *arg);
#endif #endif
#endif
/**************************************************************************** /****************************************************************************
* Name: lpc17_dmainitialize * Name: lpc17_dmainitialize

View File

@ -1,7 +1,7 @@
/**************************************************************************** /****************************************************************************
* arch/arm/src/lpc17xx/lpc17_spi.c * arch/arm/src/lpc17xx/lpc17_spi.c
* *
* Copyright (C) 2010 Gregory Nutt. All rights reserved. * Copyright (C) 2010, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr> * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
@ -104,6 +104,8 @@
* Private Types * Private Types
****************************************************************************/ ****************************************************************************/
/* This structure descibes the state of the SSP driver */
struct lpc17_spidev_s struct lpc17_spidev_s
{ {
struct spi_dev_s spidev; /* Externally visible part of the SPI interface */ struct spi_dev_s spidev; /* Externally visible part of the SPI interface */
@ -153,7 +155,11 @@ static const struct spi_ops_s g_spiops =
.send = spi_send, .send = spi_send,
.sndblock = spi_sndblock, .sndblock = spi_sndblock,
.recvblock = spi_recvblock, .recvblock = spi_recvblock,
#ifdef CONFIG_SPI_CALLBACK
.registercallback = lpc17_spiregister, /* Provided externally */
#else
.registercallback = 0, /* Not implemented */ .registercallback = 0, /* Not implemented */
#endif
}; };
static struct lpc17_spidev_s g_spidev = static struct lpc17_spidev_s g_spidev =
@ -597,5 +603,6 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
#endif #endif
return &priv->spidev; return &priv->spidev;
} }
#endif /* CONFIG_LPC17_SPI */ #endif /* CONFIG_LPC17_SPI */

View File

@ -1,7 +1,7 @@
/**************************************************************************** /****************************************************************************
* arch/arm/src/lpc17xx/lpc17_ssp.c * arch/arm/src/lpc17xx/lpc17_ssp.c
* *
* Copyright (C) 2010-2011 Gregory Nutt. All rights reserved. * Copyright (C) 2010-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org> * Author: Gregory Nutt <gnutt@nuttx.org>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
@ -108,6 +108,8 @@
* Private Types * Private Types
****************************************************************************/ ****************************************************************************/
/* This structure descibes the state of the SSP driver */
struct lpc17_sspdev_s struct lpc17_sspdev_s
{ {
struct spi_dev_s spidev; /* Externally visible part of the SPI interface */ struct spi_dev_s spidev; /* Externally visible part of the SPI interface */
@ -235,7 +237,7 @@ static struct lpc17_sspdev_s g_ssp1dev =
* Private Functions * Private Functions
****************************************************************************/ ****************************************************************************/
/************************************************************************************ /****************************************************************************
* Name: ssp_getreg * Name: ssp_getreg
* *
* Description: * Description:
@ -248,14 +250,14 @@ static struct lpc17_sspdev_s g_ssp1dev =
* Returned Value: * Returned Value:
* The contents of the 32-bit register * The contents of the 32-bit register
* *
************************************************************************************/ ****************************************************************************/
static inline uint32_t ssp_getreg(FAR struct lpc17_sspdev_s *priv, uint8_t offset) static inline uint32_t ssp_getreg(FAR struct lpc17_sspdev_s *priv, uint8_t offset)
{ {
return getreg32(priv->sspbase + (uint32_t)offset); return getreg32(priv->sspbase + (uint32_t)offset);
} }
/************************************************************************************ /****************************************************************************
* Name: ssp_putreg * Name: ssp_putreg
* *
* Description: * Description:
@ -269,7 +271,7 @@ static inline uint32_t ssp_getreg(FAR struct lpc17_sspdev_s *priv, uint8_t offse
* Returned Value: * Returned Value:
* None * None
* *
************************************************************************************/ ***************************************************************************/
static inline void ssp_putreg(FAR struct lpc17_sspdev_s *priv, uint8_t offset, uint32_t value) static inline void ssp_putreg(FAR struct lpc17_sspdev_s *priv, uint8_t offset, uint32_t value)
{ {

View File

@ -1,199 +1,380 @@
/************************************************************************************ /************************************************************************************
* configs/olimex-lpc1766stk/src/up_ssp.c * configs/olimex-lpc1766stk/src/up_ssp.c
* arch/arm/src/board/up_ssp.c * arch/arm/src/board/up_ssp.c
* *
* Copyright (C) 2010 Gregory Nutt. All rights reserved. * Copyright (C) 2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr> * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
* are met: * are met:
* *
* 1. Redistributions of source code must retain the above copyright * 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer. * notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright * 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in * notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the * the documentation and/or other materials provided with the
* distribution. * distribution.
* 3. Neither the name NuttX nor the names of its contributors may be * 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software * used to endorse or promote products derived from this software
* without specific prior written permission. * without specific prior written permission.
* *
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE. * POSSIBILITY OF SUCH DAMAGE.
* *
************************************************************************************/ ************************************************************************************/
/************************************************************************************ /************************************************************************************
* Included Files * Included Files
************************************************************************************/ ************************************************************************************/
#include <nuttx/config.h> #include <nuttx/config.h>
#include <stdint.h> #include <stdint.h>
#include <stdbool.h> #include <stdbool.h>
#include <debug.h> #include <debug.h>
#include <nuttx/spi.h> #include <nuttx/spi.h>
#include <arch/board/board.h> #ifdef CONFIG_SPI_CALLBACK
#include <nuttx/irq.h>
#include "up_arch.h" #endif
#include "chip.h"
#include "lpc17_internal.h" #include <arch/board/board.h>
#include "lpc1766stk_internal.h"
#include "up_arch.h"
#if defined(CONFIG_LPC17_SSP0) || defined(CONFIG_LPC17_SSP1) #include "chip.h"
#include "lpc17_internal.h"
/************************************************************************************ #include "lpc1766stk_internal.h"
* Definitions
************************************************************************************/ #if defined(CONFIG_LPC17_SSP0) || defined(CONFIG_LPC17_SSP1)
/* The following enable debug output from this file (needs CONFIG_DEBUG too). /************************************************************************************
* * Definitions
* CONFIG_SSP_DEBUG - Define to enable basic SSP debug ************************************************************************************/
* CONFIG_SSP_VERBOSE - Define to enable verbose SSP debug /* Configuration ************************************************************/
*/
#ifdef CONFIG_SPI_CALLBACK
#ifdef CONFIG_SSP_DEBUG # ifndef CONFIG_GPIO_IRQ
# define sspdbg lldbg # warning "CONFIG_GPIO_IRQ is required to support CONFIG_SPI_CALLBACK"
# ifdef CONFIG_SSP_VERBOSE # endif
# define sspvdbg lldbg #endif
# else
# define sspvdbg(x...) /* Debug ********************************************************************/
# endif /* The following enable debug output from this file (needs CONFIG_DEBUG too).
#else *
# undef CONFIG_SSP_VERBOSE * CONFIG_SSP_DEBUG - Define to enable basic SSP debug
# define sspdbg(x...) * CONFIG_SSP_VERBOSE - Define to enable verbose SSP debug
# define sspvdbg(x...) */
#endif
#ifdef CONFIG_SSP_DEBUG
/* Dump GPIO registers */ # define sspdbg lldbg
# ifdef CONFIG_SSP_VERBOSE
#ifdef CONFIG_SSP_VERBOSE # define sspvdbg lldbg
# define ssp_dumpssp0gpio(m) lpc17_dumpgpio(LPC1766STK_LCD_CS, m) # else
# define ssp_dumpssp1gpio(m) lpc17_dumpgpio(LPC1766STK_MMC_CS, m) # define sspvdbg(x...)
#else # endif
# define ssp_dumpssp0gpio(m) #else
# define ssp_dumpssp1gpio(m) # undef CONFIG_SSP_VERBOSE
#endif # define sspdbg(x...)
# define sspvdbg(x...)
/************************************************************************************ #endif
* Private Functions
************************************************************************************/ /* Dump GPIO registers */
/************************************************************************************ #ifdef CONFIG_SSP_VERBOSE
* Public Functions # define ssp_dumpssp0gpio(m) lpc17_dumpgpio(LPC1766STK_LCD_CS, m)
************************************************************************************/ # define ssp_dumpssp1gpio(m) lpc17_dumpgpio(LPC1766STK_MMC_CS, m)
#else
/************************************************************************************ # define ssp_dumpssp0gpio(m)
* Name: lpc17_sspinitialize # define ssp_dumpssp1gpio(m)
* #endif
* Description:
* Called to configure SPI chip select GPIO pins for the LPC1766-STK. /************************************************************************************
* * Private Types
************************************************************************************/ ************************************************************************************/
void weak_function lpc17_sspinitialize(void) /* This structure describes on media change callback */
{
/* Configure the SSP0 chip select GPIOs. Only the Nokia LCD is connected to SSP0 */ #ifdef CONFIG_SPI_CALLBACK
struct lpc17_mediachange_s
#ifdef CONFIG_LPC17_SSP0 {
ssp_dumpssp0gpio("BEFORE SSP0 Initialization"); spi_mediachange_t callback; /* The media change callback */
lpc17_configgpio(LPC1766STK_LCD_CS); FAR void *arg; /* Callback argument */
ssp_dumpssp0gpio("AFTER SSP0 Initialization"); };
#endif #endif
/* Configure SSP1 chip select GPIOs. Only the SD/MMC card slot is connected to SSP1 */ /************************************************************************************
* Private Data
#ifdef CONFIG_LPC17_SSP1 ************************************************************************************/
ssp_dumpssp0gpio("BEFORE SSP1 Initialization");
lpc17_configgpio(LPC1766STK_MMC_CS); /* Registered media change callback */
/* Also configure the SD/MMC power GPIO (but leave power off). This really has #ifdef CONFIG_SPI_CALLBACK
* nothing to do with SSP, but does belong with other SD/MMC GPIO configuration #ifdef CONFIG_LPC17_SSP0
* settings. static struct lpc17_mediachange_s g_ssp0callback;
*/ #endif
#ifdef CONFIG_LPC17_SSP1
lpc17_configgpio(LPC1766STK_MMC_PWR); static struct lpc17_mediachange_s g_ssp1callback;
ssp_dumpssp0gpio("AFTER SSP1 Initialization"); #endif
#endif #endif
}
/************************************************************************************
/************************************************************************************ * Private Functions
* Name: lpc17_ssp0/ssp1select and lpc17_ssp0/ssp1status ************************************************************************************/
*
* Description: /************************************************************************************
* The external functions, lpc17_ssp0/ssp1select and lpc17_ssp0/ssp1status * Name: ssp_cdirqsetup
* 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 * Description:
* include/nuttx/spi.h). All other methods (including up_spiinitialize()) * Setup to receive a card detection interrupt
* are provided by common LPC17xx logic. To use this common SPI logic on your *
* board: ************************************************************************************/
*
* 1. Provide logic in lpc17_boardinitialize() to configure SPI/SSP chip select #ifdef CONFIG_SPI_CALLBACK
* pins. static void ssp_cdirqsetup(int irq, xcpt_t irqhandler)
* 2. Provide lpc17_ssp0/ssp1select() and lpc17_ssp0/ssp1status() functions {
* in your board-specific logic. These functions will perform chip selection irqstate_t flags;
* and status operations using GPIOs in the way your board is configured.
* 3. Add a calls to up_spiinitialize() in your low level application /* Disable interrupts until we are done */
* initialization logic
* 4. The handle returned by up_spiinitialize() may then be used to bind the flags = irqsave();
* SPI driver to higher level logic (e.g., calling
* mmcsd_spislotinitialize(), for example, will bind the SPI driver to /* Configure the interrupt. Either attach and enable the new
* the SPI MMC/SD driver). * interrupt or disable and detach the old interrupt handler.
* */
************************************************************************************/
if (irqhandler)
#ifdef CONFIG_LPC17_SSP0 {
void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) /* Attach then enable the new interrupt handler */
{
sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); (void)irq_attach(irq, irqhandler);
if (devid == SPIDEV_DISPLAY) up_enable_irq(irq);
{ }
/* Assert/de-assert the CS pin to the card */ else
{
ssp_dumpssp0gpio("lpc17_ssp0select() Entry"); /* Disable then then detach the the old interrupt handler */
lpc17_gpiowrite(LPC1766STK_LCD_CS, !selected);
ssp_dumpssp0gpio("lpc17_ssp0select() Exit"); up_disable_irq(irq);
} (void)irq_detach(irq);
} }
}
uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) #endif
{
sspdbg("Returning nothing\n"); /************************************************************************************
return 0; * Name: ssp0/1_cdinterrupt
} *
#endif * Description:
* Handle card detection interrupt
#ifdef CONFIG_LPC17_SSP1 *
void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) ************************************************************************************/
{
sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #ifdef CONFIG_SPI_CALLBACK
if (devid == SPIDEV_MMCSD) #ifdef CONFIG_LPC17_SSP0
{ static int ssp0_cdinterrupt(int irq, FAR void *context)
/* Assert/de-assert the CS pin to the card */ {
/* Invoke the media change callback */
ssp_dumpssp1gpio("lpc17_ssp1select() Entry");
lpc17_gpiowrite(LPC1766STK_MMC_CS, !selected); if (g_ssp0callback.callback)
ssp_dumpssp1gpio("lpc17_ssp1select() Exit"); {
} g_ssp0callback.callback(g_ssp0callback.arg);
} }
return OK;
uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) }
{ #endif
sspdbg("Returning SPI_STATUS_PRESENT\n");
return SPI_STATUS_PRESENT; #ifdef CONFIG_LPC17_SSP1
} static int ssp1_cdinterrupt(int irq, FAR void *context)
#endif {
/* Invoke the media change callback */
#endif /* CONFIG_LPC17_SSP0 || CONFIG_LPC17_SSP1 */
if (g_ssp1callback.callback)
{
g_ssp1callback.callback(g_ssp1callback.arg);
}
return OK;
}
#endif
#endif
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: lpc17_sspinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the LPC1766-STK.
*
************************************************************************************/
void weak_function lpc17_sspinitialize(void)
{
/* Configure the SSP0 chip select GPIOs. Only the Nokia LCD is connected to SSP0 */
#ifdef CONFIG_LPC17_SSP0
ssp_dumpssp0gpio("BEFORE SSP0 Initialization");
lpc17_configgpio(LPC1766STK_LCD_CS);
ssp_dumpssp0gpio("AFTER SSP0 Initialization");
#endif
/* Configure SSP1 chip select GPIOs. Only the SD/MMC card slot is connected to SSP1 */
#ifdef CONFIG_LPC17_SSP1
ssp_dumpssp0gpio("BEFORE SSP1 Initialization");
lpc17_configgpio(LPC1766STK_MMC_CS);
/* Also configure the SD/MMC power GPIO (but leave power off). This really has
* nothing to do with SSP, but does belong with other SD/MMC GPIO configuration
* settings.
*/
lpc17_configgpio(LPC1766STK_MMC_PWR);
ssp_dumpssp0gpio("AFTER SSP1 Initialization");
#endif
#ifdef CONFIG_SPI_CALLBACK
/* If there were any CD detect pins for the LPC1766-STK, this is where
* they would be configured.
*/
#endif
}
/************************************************************************************
* Name: lpc17_ssp0/ssp1select and lpc17_ssp0/ssp1status
*
* Description:
* The external functions, lpc17_ssp0/ssp1select and lpc17_ssp0/ssp1status
* 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 LPC17xx logic. To use this common SPI logic on your
* board:
*
* 1. Provide logic in lpc17_boardinitialize() to configure SPI/SSP chip select
* pins.
* 2. Provide lpc17_ssp0/ssp1select() and lpc17_ssp0/ssp1status() 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_LPC17_SSP0
void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
if (devid == SPIDEV_DISPLAY)
{
/* Assert/de-assert the CS pin to the card */
ssp_dumpssp0gpio("lpc17_ssp0select() Entry");
lpc17_gpiowrite(LPC1766STK_LCD_CS, !selected);
ssp_dumpssp0gpio("lpc17_ssp0select() Exit");
}
}
uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
sspdbg("Returning nothing\n");
return 0;
}
#endif
#ifdef CONFIG_LPC17_SSP1
void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
if (devid == SPIDEV_MMCSD)
{
/* Assert/de-assert the CS pin to the card */
ssp_dumpssp1gpio("lpc17_ssp1select() Entry");
lpc17_gpiowrite(LPC1766STK_MMC_CS, !selected);
ssp_dumpssp1gpio("lpc17_ssp1select() Exit");
}
}
uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
sspdbg("Returning SPI_STATUS_PRESENT\n");
return SPI_STATUS_PRESENT;
}
#endif
/************************************************************************************
* Name: lpc17_ssp0/1register
*
* Description:
* If the board supports a card detect callback to inform the SPI-based
* MMC/SD drvier when an SD card is inserted or removed, then
* CONFIG_SPI_CALLBACK should be defined and the following function(s) must
* must be implemented. These functiosn implements the registercallback
* method of the SPI interface (see include/nuttx/spi.h for details)
*
* Input Parameters:
* dev - Device-specific state data
* callback - The funtion to call on the media change
* arg - A caller provided value to return with the callback
*
* Returned Value:
* 0 on success; negated errno on failure.
*
************************************************************************************/
#ifdef CONFIG_SPI_CALLBACK
#ifdef CONFIG_LPC17_SSP0
/* If there were any CD detect pins on the LPC1766-STK, this is how the
* would be configured.
*/
int lpc17_ssp0register(FAR struct spi_dev_s *dev, spi_mediachange_t callback, void *arg)
{
/* Save the callback information */
#if 0
g_ssp0callback.callback = callback;
g_ssp0callback.arg = arg;
/* Setup the interrupt */
spi_cdirqsetup(LPC1766STK_SPICD_IRQ, ssp0_cdinterrupt);
#endif
return OK;
}
#endif
#ifdef CONFIG_LPC17_SSP1
int lpc17_ssp1register(FAR struct spi_dev_s *dev, spi_mediachange_t callback, void *arg)
{
/* Save the callback information */
#if 0
g_ssp1callback.callback = callback;
g_ssp1callback.arg = arg;
/* Setup the interrupt */
spi_cdirqsetup(LPC1766STK_SPICD_IRQ, ssp1_cdinterrupt);
#endif
return OK;
}
#endif
#endif
#endif /* CONFIG_LPC17_SSP0 || CONFIG_LPC17_SSP1 */