From fa05c01cab6acc95f759f2432d43e5ac9ea7d29d Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 11 Nov 2009 00:13:42 +0000 Subject: Rename mmcsd.c to mmcsd_sdio.c git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2242 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/stm32/stm32_sdio.h | 17 ++ nuttx/drivers/mmcsd/Make.defs | 2 +- nuttx/drivers/mmcsd/mmcsd.c | 468 ---------------------------------- nuttx/drivers/mmcsd/mmcsd_sdio.c | 468 ++++++++++++++++++++++++++++++++++ nuttx/include/nuttx/sdio.h | 10 +- 5 files changed, 492 insertions(+), 473 deletions(-) delete mode 100644 nuttx/drivers/mmcsd/mmcsd.c create mode 100644 nuttx/drivers/mmcsd/mmcsd_sdio.c diff --git a/nuttx/arch/arm/src/stm32/stm32_sdio.h b/nuttx/arch/arm/src/stm32/stm32_sdio.h index e2b8e31cc..73a29d8cf 100755 --- a/nuttx/arch/arm/src/stm32/stm32_sdio.h +++ b/nuttx/arch/arm/src/stm32/stm32_sdio.h @@ -101,6 +101,8 @@ # define SDIO_POWER_PWRCTRL_RSVDPWRUP (2 << POWER_PWRCTRL_SHIFT) /* 10: Reserved power-up */ # define SDIO_POWER_PWRCTRL_ON (3 << POWER_PWRCTRL_SHIFT) /* 11: Power-on: card is clocked */ +#define SDIO_POWER_RESET (0) /* Reset value */ + #define SDIO_CLKCR_CLKDIV_SHIFT (0) /* Bits 7-0: Clock divide factor */ #define SDIO_CLKCR_CLKDIV_MASK (0xff << SDIO_CLKCR_CLKDIV_SHIFT) #define SDIO_CLKCR_CLKEN (1 << 8) /* Bit 8: Clock enable bit */ @@ -114,6 +116,9 @@ #define SDIO_CLKCR_NEGEDGE (1 << 13) /* Bit 13: SDIO_CK dephasing selection bit */ #define SDIO_CLKCR_HWFC_EN (1 << 14) /* Bit 14: HW Flow Control enable */ +#define SDIO_CLKCR_RESET (0) /* Reset value */ +#define SDIO_ARG_RESET (0) /* Reset value */ + #define SDIO_CMD_CMDINDEX_SHIFT (0) #define SDIO_CMD_CMDINDEX_MASK (0x3f << SDIO_CMD_CMDINDEX_SHIFT) #define SDIO_CMD_WAITRESP_SHIFT (6) /* Bits 7-6: Wait for response bits */ @@ -129,12 +134,18 @@ #define SDIO_CMD_NIEN (1 << 13) /* Bit 13: not Interrupt Enable */ #define SDIO_CMD_ATACMD (1 << 14) /* Bit 14: CE-ATA command */ +#define SDIO_CMD_RESET (0) /* Reset value */ + #define SDIO_RESPCMD_SHIFT (0) #define SDIO_RESPCMD_MASK (0x3f << SDIO_RESPCMD_SHIFT) +#define SDIO_DTIMER_RESET (0) /* Reset value */ + #define SDIO_DLEN_SHIFT (0) #define SDIO_DLEN_MASK (0x01ffffff << SDIO_DLEN_SHIFT) +#define SDIO_DLEN_RESET (0) /* Reset value */ + #define SDIO_DCTRL_DTEN (1 << 0) /* Bit 0: Data transfer enabled bit */ #define SDIO_DCTRL_DTDIR (1 << 1) /* Bit 1: Data transfer direction */ #define SDIO_DCTRL_DTMODE (1 << 2) /* Bit 2: Data transfer mode */ @@ -161,6 +172,8 @@ #define SDIO_DCTRL_RWMOD (1 << 10) /* Bit 10: Read wait mode */ #define SDIO_DCTRL_SDIOEN (1 << 11) /* Bit 11: SD I/O enable functions */ +#define SDIO_DCTRL_RESET (0) /* Reset value */ + #define SDIO_DATACOUNT_SHIFT (0) #define SDIO_DATACOUNT_MASK (0x01ffffff << SDIO_DATACOUNT_SHIFT) @@ -203,6 +216,8 @@ #define SDIO_ICR_SDIOITC (1 << 22) /* Bit 22: SDIOIT flag clear bit */ #define SDIO_ICR_CEATAENDC (1 << 23) /* Bit 23: CEATAEND flag clear bit */ +#define SDIO_ICR_RESET 0x00c007ff + #define SDIO_MASK_CCRCFAILIE (1 << 0) /* Bit 0: Command CRC fail interrupt enable */ #define SDIO_MASK_DCRCFAILIE (1 << 1) /* Bit 1: Data CRC fail interrupt enable */ #define SDIO_MASK_CTIMEOUTIE (1 << 2) /* Bit 2: Command timeout interrupt enable */ @@ -228,6 +243,8 @@ #define SDIO_MASK_SDIOITIE (1 << 22) /* Bit 22: SDIO mode interrupt received interrupt enable */ #define SDIO_MASK_CEATAENDIE (1 << 23) /* Bit 23: CE-ATA command completion interrupt enable */ +#define SDIO_MASK_RESET (0) + #define SDIO_FIFOCNT_SHIFT (0) #define SDIO_FIFOCNT_MASK (0x01ffffff << SDIO_FIFOCNT_SHIFT) diff --git a/nuttx/drivers/mmcsd/Make.defs b/nuttx/drivers/mmcsd/Make.defs index 37c82903f..6e7bf8080 100644 --- a/nuttx/drivers/mmcsd/Make.defs +++ b/nuttx/drivers/mmcsd/Make.defs @@ -34,5 +34,5 @@ ############################################################################ MMCSD_ASRCS = -MMCSD_CSRCS = mmcsd.c mmcsd_spi.c mmcsd_debug.c +MMCSD_CSRCS = mmcsd_sdio.c mmcsd_spi.c mmcsd_debug.c diff --git a/nuttx/drivers/mmcsd/mmcsd.c b/nuttx/drivers/mmcsd/mmcsd.c deleted file mode 100644 index 348c46321..000000000 --- a/nuttx/drivers/mmcsd/mmcsd.c +++ /dev/null @@ -1,468 +0,0 @@ -/**************************************************************************** - * drivers/mmcsd/mmcsd.c - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#define MAX_CREFS 0xff /* Because a ubyte is used. Use a larger - * type if necessary */ - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/* This structure is contains the unique state of the MMC/SD block driver */ - -struct mmcsd_state_s -{ - struct sdio_dev_s *dev; /* The MMCSD device bound to this instance */ - ubyte crefs; /* Open references on the driver */ - - /* Status flags */ - - ubyte widebus:1; /* TRUE: Wide 4-bit bus selected */ - ubyte mediachange:1; /* TRUE: Media changed since last check */ -#ifdef CONFIG_SDIO_DMA - ubyte dma:1; /* TRUE: hardware supports DMA */ -#endif - - /* Read-ahead and write buffering support */ - -#if defined(CONFIG_FS_WRITEBUFFER) || defined(CONFIG_FS_READAHEAD) - struct rwbuffer_s rwbuffer; -#endif -}; - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/* Transfer helpers *********************************************************/ - -static ssize_t mmcsd_doread(FAR void *dev, FAR ubyte *buffer, - off_t startblock, size_t nblocks); -static ssize_t mmcsd_dowrite(FAR void *dev, FAR const ubyte *buffer, - off_t startblock, size_t nblocks); - -/* Block driver methods *****************************************************/ - -static int mmcsd_open(FAR struct inode *inode); -static int mmcsd_close(FAR struct inode *inode); -static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer, - size_t start_sector, unsigned int nsectors); -#ifdef CONFIG_FS_WRITABLE -static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer, - size_t start_sector, unsigned int nsectors); -#endif -static int mmcsd_geometry(FAR struct inode *inode, - struct geometry *geometry); -static int mmcsd_ioctl(FAR struct inode *inode, int cmd, - unsigned long arg); - -/* Initialization/uninitialization/reset ************************************/ - -static int mmcsd_hwinitialize(struct mmcsd_state_s *priv); -static inline void - mmcsd_hwuninitialize(struct mmcsd_state_s *priv); - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -static const struct block_operations g_bops = -{ - mmcsd_open, /* open */ - mmcsd_close, /* close */ - mmcsd_read, /* read */ -#ifdef CONFIG_FS_WRITABLE - mmcsd_write, /* write */ -#else - NULL, /* write */ -#endif - mmcsd_geometry, /* geometry */ - mmcsd_ioctl /* ioctl */ -}; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Transfer Helpers - ****************************************************************************/ -/**************************************************************************** - * Name: mmcsd_doread - * - * Description: - * Read the specified numer of sectors from the physical device. - * - ****************************************************************************/ - -static ssize_t mmcsd_doread(FAR void *dev, FAR ubyte *buffer, - off_t startblock, size_t nblocks) -{ - struct mmcsd_state_s *priv = (struct mmcsd_state_s *)dev; -#ifdef CONFIG_CPP_HAVE_WARNING -# warning "Not implemented" -#endif - return -ENOSYS; -} - -/**************************************************************************** - * Name: mmcsd_dowrite - * - * Description: Write the specified number of sectors - * - ****************************************************************************/ - -#ifdef CONFIG_FS_WRITABLE -static ssize_t mmcsd_dowrite(FAR void *dev, FAR const ubyte *buffer, - off_t startblock, size_t nblocks) -{ - struct mmcsd_state_s *priv = (struct mmcsd_state_s *)dev; -#ifdef CONFIG_CPP_HAVE_WARNING -# warning "Not implemented" -#endif - return -ENOSYS; -} -#endif - -/**************************************************************************** - * Block Driver Methods - ****************************************************************************/ -/**************************************************************************** - * Name: mmcsd_open - * - * Description: Open the block device - * - ****************************************************************************/ - -static int mmcsd_open(FAR struct inode *inode) -{ - struct mmcsd_state_s *priv; - - fvdbg("Entry\n"); - DEBUGASSERT(inode && inode->i_private); - priv = (struct mmcsd_state_s *)inode->i_private; - - /* Just increment the reference count on the driver */ - - DEBUGASSERT(priv->crefs < MAX_CREFS); - priv->crefs++; - return OK; -} - -/**************************************************************************** - * Name: mmcsd_close - * - * Description: close the block device - * - ****************************************************************************/ - -static int mmcsd_close(FAR struct inode *inode) -{ - struct mmcsd_state_s *priv; - - fvdbg("Entry\n"); - DEBUGASSERT(inode && inode->i_private); - priv = (struct mmcsd_state_s *)inode->i_private; - - /* Decrement the reference count on the block driver */ - - DEBUGASSERT(priv->crefs > 0); - priv->crefs--; - return OK; -} - -/**************************************************************************** - * Name: mmcsd_read - * - * Description: - * Read the specified numer of sectors from the read-ahead buffer or from - * the physical device. - * - ****************************************************************************/ - -static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer, - size_t start_sector, unsigned int nsectors) -{ - struct mmcsd_state_s *priv; - - fvdbg("sector: %d nsectors: %d sectorsize: %d\n"); - DEBUGASSERT(inode && inode->i_private); - priv = (struct mmcsd_state_s *)inode->i_private; - -#ifdef CONFIG_FS_READAHEAD - return rwb_read(&priv->rwbuffer, start_sector, nsectors, buffer); -#else - return mmcsd_doread(priv, buffer, start_sector, nsectors); -#endif -} - -/**************************************************************************** - * Name: mmcsd_write - * - * Description: - * Write the specified number of sectors to the write buffer or to the - * physical device. - * - ****************************************************************************/ - -#ifdef CONFIG_FS_WRITABLE -static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer, - size_t start_sector, unsigned int nsectors) -{ - struct mmcsd_state_s *priv; - - fvdbg("sector: %d nsectors: %d sectorsize: %d\n"); - DEBUGASSERT(inode && inode->i_private); - priv = (struct mmcsd_state_s *)inode->i_private; - -#ifdef CONFIG_FS_WRITEBUFFER - return rwb_write(&priv->rwbuffer, start_sector, nsectors, buffer); -#else - return mmcsd_dowrite(priv, buffer, start_sector, nsectors); -#endif -} -#endif - -/**************************************************************************** - * Name: mmcsd_geometry - * - * Description: Return device geometry - * - ****************************************************************************/ - -static int mmcsd_geometry(FAR struct inode *inode, struct geometry *geometry) -{ - struct mmcsd_state_s *priv; - - fvdbg("Entry\n"); - DEBUGASSERT(inode && inode->i_private); - if (geometry) - { - priv = (struct mmcsd_state_s *)inode->i_private; -#ifdef CONFIG_CPP_HAVE_WARNING -# warning "Not implemented" -#endif - return -ENOSYS; - } - return -EINVAL; -} - -/**************************************************************************** - * Name: mmcsd_ioctl - * - * Description: Return device geometry - * - ****************************************************************************/ - -static int mmcsd_ioctl(FAR struct inode *inode, int cmd, unsigned long arg) -{ - struct mmcsd_state_s *priv ; - - fvdbg("Entry\n"); - DEBUGASSERT(inode && inode->i_private); - priv = (struct mmcsd_state_s *)inode->i_private; - -#ifdef CONFIG_CPP_HAVE_WARNING -# warning "Not implemented" -#endif - return -ENOTTY; -} - -/**************************************************************************** - * Initialization/uninitialization/reset - ****************************************************************************/ -/**************************************************************************** - * Name: mmcsd_hwinitialize - * - * Description: One-time hardware initialization - * - ****************************************************************************/ - -static int mmcsd_hwinitialize(struct mmcsd_state_s *priv) -{ -#ifdef CONFIG_CPP_HAVE_WARNING -# warning "Not implemented" -#endif - return -ENODEV; -} - -/**************************************************************************** - * Name: mmcsd_hwinitialize - * - * Description: Restore the MMC/SD slot to the uninitialized state - * - ****************************************************************************/ - -static inline void mmcsd_hwuninitialize(struct mmcsd_state_s *priv) -{ - SDIO_RESET(priv->dev); -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: mmcsd_slotinitialize - * - * Description: - * Initialize one slot for operation using the MMC/SD interface - * - * Input Parameters: - * minor - The MMC/SD minor device number. The MMC/SD device will be - * registered as /dev/mmcsdN where N is the minor number - * slotno - The slot number to use. This is only meaningful for architectures - * that support multiple MMC/SD slots. This value must be in the range - * {0, ..., CONFIG_MMCSD_NSLOTS}. - * dev - And instance of an MMC/SD interface. The MMC/SD hardware should - * be initialized and ready to use. - * - ****************************************************************************/ - -int mmcsd_slotinitialize(int minor, int slotno, FAR struct sdio_dev_s *dev) -{ - struct mmcsd_state_s *priv; - char devname[16]; - int ret = -ENOMEM; - - fvdbg("minor: %d slotno: %d\n", minor, slotno); - - /* Sanity check */ - -#ifdef CONFIG_DEBUG - if (minor < 0 || minor > 255 || !dev) - { - return -EINVAL; - } -#endif - - /* Allocate a MMC/SD state structure */ - - priv = (struct mmcsd_state_s *)malloc(sizeof(struct mmcsd_state_s)); - if (priv) - { - /* Initialize the MMC/SD state structure */ - - memset(priv, 0, sizeof(struct mmcsd_state_s)); - - /* Bind the MMCSD driver to the MMCSD state structure */ - - priv->dev = dev; - - /* Initialize the hardware associated with the slot */ - - ret = mmcsd_hwinitialize(priv); - - /* Was the slot initialized successfully? */ - - if (ret != 0) - { - /* No... But the error ENODEV is returned if hardware initialization - * succeeded but no card is inserted in the slot. In this case, the - * no error occurred, but the driver is still not ready. - */ - - if (ret == -ENODEV) - { - fdbg("MMC/SD slot %d is empty\n", slotno); - } - else - { - fdbg("ERROR: Failed to initialize MMC/SD slot %d: %d\n", - slotno, -ret); - goto errout_with_alloc; - } - } - - /* Initialize buffering */ - -#if defined(CONFIG_FS_WRITEBUFFER) || defined(CONFIG_FS_READAHEAD) - - ret = rwb_initialize(&priv->rwbuffer); - if (ret < 0) - { - fdbg("ERROR: Buffer setup failed: %d\n", -ret); - goto errout_with_hwinit; - } -#endif - - /* Create a MMCSD device name */ - - snprintf(devname, 16, "/dev/mmcsd%d", minor); - - /* Inode private data is a reference to the MMCSD state structure */ - - ret = register_blockdriver(devname, &g_bops, 0, priv); - if (ret < 0) - { - fdbg("ERROR: register_blockdriver failed: %d\n", -ret); - goto errout_with_buffers; - } - } - return OK; - -errout_with_buffers: -#if defined(CONFIG_FS_WRITEBUFFER) || defined(CONFIG_FS_READAHEAD) - rwb_uninitialize(&priv->rwbuffer); -#endif -errout_with_hwinit: - mmcsd_hwuninitialize(priv); -errout_with_alloc: - free(priv); - return ret; -} diff --git a/nuttx/drivers/mmcsd/mmcsd_sdio.c b/nuttx/drivers/mmcsd/mmcsd_sdio.c new file mode 100644 index 000000000..8a0b6dea3 --- /dev/null +++ b/nuttx/drivers/mmcsd/mmcsd_sdio.c @@ -0,0 +1,468 @@ +/**************************************************************************** + * drivers/mmcsd/mmcsd_sdio.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define MAX_CREFS 0xff /* Because a ubyte is used. Use a larger + * type if necessary */ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* This structure is contains the unique state of the MMC/SD block driver */ + +struct mmcsd_state_s +{ + struct sdio_dev_s *dev; /* The MMCSD device bound to this instance */ + ubyte crefs; /* Open references on the driver */ + + /* Status flags */ + + ubyte widebus:1; /* TRUE: Wide 4-bit bus selected */ + ubyte mediachange:1; /* TRUE: Media changed since last check */ +#ifdef CONFIG_SDIO_DMA + ubyte dma:1; /* TRUE: hardware supports DMA */ +#endif + + /* Read-ahead and write buffering support */ + +#if defined(CONFIG_FS_WRITEBUFFER) || defined(CONFIG_FS_READAHEAD) + struct rwbuffer_s rwbuffer; +#endif +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Transfer helpers *********************************************************/ + +static ssize_t mmcsd_doread(FAR void *dev, FAR ubyte *buffer, + off_t startblock, size_t nblocks); +static ssize_t mmcsd_dowrite(FAR void *dev, FAR const ubyte *buffer, + off_t startblock, size_t nblocks); + +/* Block driver methods *****************************************************/ + +static int mmcsd_open(FAR struct inode *inode); +static int mmcsd_close(FAR struct inode *inode); +static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer, + size_t start_sector, unsigned int nsectors); +#ifdef CONFIG_FS_WRITABLE +static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer, + size_t start_sector, unsigned int nsectors); +#endif +static int mmcsd_geometry(FAR struct inode *inode, + struct geometry *geometry); +static int mmcsd_ioctl(FAR struct inode *inode, int cmd, + unsigned long arg); + +/* Initialization/uninitialization/reset ************************************/ + +static int mmcsd_hwinitialize(struct mmcsd_state_s *priv); +static inline void + mmcsd_hwuninitialize(struct mmcsd_state_s *priv); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct block_operations g_bops = +{ + mmcsd_open, /* open */ + mmcsd_close, /* close */ + mmcsd_read, /* read */ +#ifdef CONFIG_FS_WRITABLE + mmcsd_write, /* write */ +#else + NULL, /* write */ +#endif + mmcsd_geometry, /* geometry */ + mmcsd_ioctl /* ioctl */ +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Transfer Helpers + ****************************************************************************/ +/**************************************************************************** + * Name: mmcsd_doread + * + * Description: + * Read the specified numer of sectors from the physical device. + * + ****************************************************************************/ + +static ssize_t mmcsd_doread(FAR void *dev, FAR ubyte *buffer, + off_t startblock, size_t nblocks) +{ + struct mmcsd_state_s *priv = (struct mmcsd_state_s *)dev; +#ifdef CONFIG_CPP_HAVE_WARNING +# warning "Not implemented" +#endif + return -ENOSYS; +} + +/**************************************************************************** + * Name: mmcsd_dowrite + * + * Description: Write the specified number of sectors + * + ****************************************************************************/ + +#ifdef CONFIG_FS_WRITABLE +static ssize_t mmcsd_dowrite(FAR void *dev, FAR const ubyte *buffer, + off_t startblock, size_t nblocks) +{ + struct mmcsd_state_s *priv = (struct mmcsd_state_s *)dev; +#ifdef CONFIG_CPP_HAVE_WARNING +# warning "Not implemented" +#endif + return -ENOSYS; +} +#endif + +/**************************************************************************** + * Block Driver Methods + ****************************************************************************/ +/**************************************************************************** + * Name: mmcsd_open + * + * Description: Open the block device + * + ****************************************************************************/ + +static int mmcsd_open(FAR struct inode *inode) +{ + struct mmcsd_state_s *priv; + + fvdbg("Entry\n"); + DEBUGASSERT(inode && inode->i_private); + priv = (struct mmcsd_state_s *)inode->i_private; + + /* Just increment the reference count on the driver */ + + DEBUGASSERT(priv->crefs < MAX_CREFS); + priv->crefs++; + return OK; +} + +/**************************************************************************** + * Name: mmcsd_close + * + * Description: close the block device + * + ****************************************************************************/ + +static int mmcsd_close(FAR struct inode *inode) +{ + struct mmcsd_state_s *priv; + + fvdbg("Entry\n"); + DEBUGASSERT(inode && inode->i_private); + priv = (struct mmcsd_state_s *)inode->i_private; + + /* Decrement the reference count on the block driver */ + + DEBUGASSERT(priv->crefs > 0); + priv->crefs--; + return OK; +} + +/**************************************************************************** + * Name: mmcsd_read + * + * Description: + * Read the specified numer of sectors from the read-ahead buffer or from + * the physical device. + * + ****************************************************************************/ + +static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer, + size_t start_sector, unsigned int nsectors) +{ + struct mmcsd_state_s *priv; + + fvdbg("sector: %d nsectors: %d sectorsize: %d\n"); + DEBUGASSERT(inode && inode->i_private); + priv = (struct mmcsd_state_s *)inode->i_private; + +#ifdef CONFIG_FS_READAHEAD + return rwb_read(&priv->rwbuffer, start_sector, nsectors, buffer); +#else + return mmcsd_doread(priv, buffer, start_sector, nsectors); +#endif +} + +/**************************************************************************** + * Name: mmcsd_write + * + * Description: + * Write the specified number of sectors to the write buffer or to the + * physical device. + * + ****************************************************************************/ + +#ifdef CONFIG_FS_WRITABLE +static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer, + size_t start_sector, unsigned int nsectors) +{ + struct mmcsd_state_s *priv; + + fvdbg("sector: %d nsectors: %d sectorsize: %d\n"); + DEBUGASSERT(inode && inode->i_private); + priv = (struct mmcsd_state_s *)inode->i_private; + +#ifdef CONFIG_FS_WRITEBUFFER + return rwb_write(&priv->rwbuffer, start_sector, nsectors, buffer); +#else + return mmcsd_dowrite(priv, buffer, start_sector, nsectors); +#endif +} +#endif + +/**************************************************************************** + * Name: mmcsd_geometry + * + * Description: Return device geometry + * + ****************************************************************************/ + +static int mmcsd_geometry(FAR struct inode *inode, struct geometry *geometry) +{ + struct mmcsd_state_s *priv; + + fvdbg("Entry\n"); + DEBUGASSERT(inode && inode->i_private); + if (geometry) + { + priv = (struct mmcsd_state_s *)inode->i_private; +#ifdef CONFIG_CPP_HAVE_WARNING +# warning "Not implemented" +#endif + return -ENOSYS; + } + return -EINVAL; +} + +/**************************************************************************** + * Name: mmcsd_ioctl + * + * Description: Return device geometry + * + ****************************************************************************/ + +static int mmcsd_ioctl(FAR struct inode *inode, int cmd, unsigned long arg) +{ + struct mmcsd_state_s *priv ; + + fvdbg("Entry\n"); + DEBUGASSERT(inode && inode->i_private); + priv = (struct mmcsd_state_s *)inode->i_private; + +#ifdef CONFIG_CPP_HAVE_WARNING +# warning "Not implemented" +#endif + return -ENOTTY; +} + +/**************************************************************************** + * Initialization/uninitialization/reset + ****************************************************************************/ +/**************************************************************************** + * Name: mmcsd_hwinitialize + * + * Description: One-time hardware initialization + * + ****************************************************************************/ + +static int mmcsd_hwinitialize(struct mmcsd_state_s *priv) +{ +#ifdef CONFIG_CPP_HAVE_WARNING +# warning "Not implemented" +#endif + return -ENODEV; +} + +/**************************************************************************** + * Name: mmcsd_hwinitialize + * + * Description: Restore the MMC/SD slot to the uninitialized state + * + ****************************************************************************/ + +static inline void mmcsd_hwuninitialize(struct mmcsd_state_s *priv) +{ + SDIO_RESET(priv->dev); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mmcsd_slotinitialize + * + * Description: + * Initialize one slot for operation using the MMC/SD interface + * + * Input Parameters: + * minor - The MMC/SD minor device number. The MMC/SD device will be + * registered as /dev/mmcsdN where N is the minor number + * slotno - The slot number to use. This is only meaningful for architectures + * that support multiple MMC/SD slots. This value must be in the range + * {0, ..., CONFIG_MMCSD_NSLOTS}. + * dev - And instance of an MMC/SD interface. The MMC/SD hardware should + * be initialized and ready to use. + * + ****************************************************************************/ + +int mmcsd_slotinitialize(int minor, int slotno, FAR struct sdio_dev_s *dev) +{ + struct mmcsd_state_s *priv; + char devname[16]; + int ret = -ENOMEM; + + fvdbg("minor: %d slotno: %d\n", minor, slotno); + + /* Sanity check */ + +#ifdef CONFIG_DEBUG + if (minor < 0 || minor > 255 || !dev) + { + return -EINVAL; + } +#endif + + /* Allocate a MMC/SD state structure */ + + priv = (struct mmcsd_state_s *)malloc(sizeof(struct mmcsd_state_s)); + if (priv) + { + /* Initialize the MMC/SD state structure */ + + memset(priv, 0, sizeof(struct mmcsd_state_s)); + + /* Bind the MMCSD driver to the MMCSD state structure */ + + priv->dev = dev; + + /* Initialize the hardware associated with the slot */ + + ret = mmcsd_hwinitialize(priv); + + /* Was the slot initialized successfully? */ + + if (ret != 0) + { + /* No... But the error ENODEV is returned if hardware initialization + * succeeded but no card is inserted in the slot. In this case, the + * no error occurred, but the driver is still not ready. + */ + + if (ret == -ENODEV) + { + fdbg("MMC/SD slot %d is empty\n", slotno); + } + else + { + fdbg("ERROR: Failed to initialize MMC/SD slot %d: %d\n", + slotno, -ret); + goto errout_with_alloc; + } + } + + /* Initialize buffering */ + +#if defined(CONFIG_FS_WRITEBUFFER) || defined(CONFIG_FS_READAHEAD) + + ret = rwb_initialize(&priv->rwbuffer); + if (ret < 0) + { + fdbg("ERROR: Buffer setup failed: %d\n", -ret); + goto errout_with_hwinit; + } +#endif + + /* Create a MMCSD device name */ + + snprintf(devname, 16, "/dev/mmcsd%d", minor); + + /* Inode private data is a reference to the MMCSD state structure */ + + ret = register_blockdriver(devname, &g_bops, 0, priv); + if (ret < 0) + { + fdbg("ERROR: register_blockdriver failed: %d\n", -ret); + goto errout_with_buffers; + } + } + return OK; + +errout_with_buffers: +#if defined(CONFIG_FS_WRITEBUFFER) || defined(CONFIG_FS_READAHEAD) + rwb_uninitialize(&priv->rwbuffer); +#endif +errout_with_hwinit: + mmcsd_hwuninitialize(priv); +errout_with_alloc: + free(priv); + return ret; +} diff --git a/nuttx/include/nuttx/sdio.h b/nuttx/include/nuttx/sdio.h index 8fe29c572..52205f79b 100755 --- a/nuttx/include/nuttx/sdio.h +++ b/nuttx/include/nuttx/sdio.h @@ -104,18 +104,20 @@ * Name: SDIO_WIDEBUS * * Description: - * Enable/disable wide (4-bit) data bus + * Called after change in Bus width has been selected (via ACMD6). Most + * controllers will need to perform some special operations to work + * correctly in the new bus mode. * * Input Parameters: - * dev - An instance of the MMC/SD device interface - * enable - TRUE: enable wide bus + * dev - An instance of the MMC/SD device interface + * wide - TRUE: wide bus (4-bit) bus mode enabled * * Returned Value: * None * ****************************************************************************/ -#define SDIO_WIDEBUS(dev,enable) ((dev)->widebus(dev,enable)) +#define SDIO_WIDEBUS(dev,wide) ((dev)->widebus(dev,wide)) /**************************************************************************** * Name: SDIO_CLOCK -- cgit v1.2.3