diff --git a/arch/arm/include/cxd56xx/usbdev.h b/arch/arm/include/cxd56xx/usbdev.h new file mode 100644 index 0000000000..f44e75487b --- /dev/null +++ b/arch/arm/include/cxd56xx/usbdev.h @@ -0,0 +1,65 @@ +/**************************************************************************** + * arch/arm/include/cxd56xx/usbdev.h + * + * Copyright 2018 Sony Semiconductor Solutions Corporation + * + * 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 of Sony Semiconductor Solutions Corporation 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 __ARCH_ARM_INCLUDE_CXD56XX_USBDEV_H +#define __ARCH_ARM_INCLUDE_CXD56XX_USBDEV_H + +/******************************************************************************************** + * Included Files + ********************************************************************************************/ + +/******************************************************************************************** + * Pre-processor Definitions + ********************************************************************************************/ + +/* BOARDIOC_USBDEV_SETNOTIFYSIG signal value ************************************************/ + +#define USBDEV_STATE_DETACH 0 +#define USBDEV_STATE_ATTACH 1 + +/* + * The BOARDIOC_USBDEV_SETNOTIFYSIG signal output the VBUS connection state + * and supply current value to the signal handler argument (sival_int). + * + * Please use the following macros. + * + * - USBDEV_CONNECTED : Get VBUS connection state. + * - USBDEV_POWER_CURRENT : Get VBUS supply current. + */ + +#define USBDEV_CONNECTED(x) (0xffff & ((x)>>16)) +#define USBDEV_POWER_CURRENT(x) (0xffff & (x)) + +#endif /* __ARCH_ARM_INCLUDE_CXD56XX_USBDEV_H */ diff --git a/arch/arm/src/cxd56xx/Kconfig b/arch/arm/src/cxd56xx/Kconfig index 8812a0808e..3074074273 100644 --- a/arch/arm/src/cxd56xx/Kconfig +++ b/arch/arm/src/cxd56xx/Kconfig @@ -68,4 +68,51 @@ config CXD56_UART2 ---help--- UART interface with hardware flow control in the application subsystem. +config CXD56_USBDEV + bool "USB" + default n + ---help--- + Enables USB + +menuconfig CXD56_SDIO + bool "SDIO SD Card" + default n + select ARCH_HAVE_SDIO + select SDIO_BLOCKSETUP + select SCHED_WORKQUEUE + select SCHED_HPWORK + +if CXD56_SDIO + +config CXD56_SDIO_DMA + bool "Support DMA data transfers" + default y + select SDIO_DMA + ---help--- + Support DMA data transfers. + Enable SD card DMA data transfers. This is marginally optional. + For most usages, SD accesses will cause data overruns if used without + DMA. + +config CXD56_SDIO_WIDTH_D1_ONLY + bool "Use D1 only" + default n + ---help--- + Select 1-bit transfer mode. Default: 4-bit transfer mode. + +config CXD56_SDIO_DISABLE_CD_WP + bool "Disable the CD and WP pin for SDIO" + default y + ---help--- + Disable the CD and WP pin for Embedded SDIO.If the CD pin is not disable, + the SDIO initialization will be failed. + +config CXD56_SDIO_ENABLE_MULTIFUNCTION + bool "Enable SDIO multi-function" + default n + ---help--- + Support multi-function with SDIO interfaced peripheral other than SD Card. + +endif # SDIO Configuration + endmenu diff --git a/arch/arm/src/cxd56xx/Make.defs b/arch/arm/src/cxd56xx/Make.defs index fe7cd8d8e1..cbc488ef2b 100644 --- a/arch/arm/src/cxd56xx/Make.defs +++ b/arch/arm/src/cxd56xx/Make.defs @@ -97,3 +97,7 @@ CHIP_CSRCS += cxd56_icc.c ifeq ($(CONFIG_CXD56_GPIO_IRQ),y) CHIP_CSRCS += cxd56_gpioint.c endif + +ifeq ($(CONFIG_USBDEV),y) +CHIP_CSRCS += cxd56_usbdev.c +endif diff --git a/arch/arm/src/cxd56xx/cxd56_sdhci.c b/arch/arm/src/cxd56xx/cxd56_sdhci.c new file mode 100644 index 0000000000..a8129144be --- /dev/null +++ b/arch/arm/src/cxd56xx/cxd56_sdhci.c @@ -0,0 +1,4583 @@ +/**************************************************************************** + * arch/arm/src/cxd56xx/cxd56_sdhci.c + * + * Copyright (C) 2008-2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Copyright 2018 Sony Semiconductor Solutions Corporation + * + * 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 +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "cxd56_sdhci.h" +#include "cxd56_clock.h" +#include "cxd56_pinconfig.h" + +#ifdef CONFIG_CXD56_SDIO + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +#ifndef CONFIG_CXD56_SDIO_DMA +# warning "Large Non-DMA transfer may result in RX overrun failures" +#endif + +#if !defined(CONFIG_SCHED_WORKQUEUE) || !defined(CONFIG_SCHED_HPWORK) +# error "Callback support requires CONFIG_SCHED_WORKQUEUE and CONFIG_SCHED_HPWORK" +#endif + +#if !defined(CONFIG_MMCSD_MULTIBLOCK_DISABLE) && !defined(CONFIG_SDIO_BLOCKSETUP) +# error "This driver requires CONFIG_SDIO_BLOCKSETUP" +#endif + +#ifndef CONFIG_CXD56_SDHCI_PRIO +# define CONFIG_CXD56_SDHCI_PRIO NVIC_SYSH_PRIORITY_DEFAULT +#endif + +#ifndef CONFIG_CXD56_SDHCI_DMAPRIO +# define CONFIG_CXD56_SDHCI_DMAPRIO DMA_CCR_PRIMED +#endif + +#if !defined(CONFIG_DEBUG_FS) || !defined(CONFIG_DEBUG_VERBOSE) +# undef CONFIG_SDIO_XFRDEBUG +#endif + +/* SDCLK frequencies corresponding to various modes of operation. These + * values may be provided in either the NuttX configuration file or in + * the board.h file + * + * NOTE: These settings are not currently used. Since there are only four + * frequencies, it makes more sense to just "can" the fixed frequency prescaler + * and divider values. + */ + +#ifndef CONFIG_CXD56_IDMODE_FREQ +# define CONFIG_CXD56_IDMODE_FREQ 400000 /* 400 KHz, ID mode */ +#endif +#ifndef CONFIG_CXD56_MMCXFR_FREQ +# define CONFIG_CXD56_MMCXFR_FREQ 20000000 /* 20MHz MMC, normal clocking */ +#endif +#ifndef CONFIG_CXD56_SD1BIT_FREQ +# define CONFIG_CXD56_SD1BIT_FREQ 20000000 /* 20MHz SD 1-bit, normal clocking */ +#endif +#ifndef CONFIG_CXD56_SD4BIT_FREQ +# define CONFIG_CXD56_SD4BIT_FREQ 25000000 /* 25MHz SD 4-bit, normal clocking */ +#endif +#ifndef CONFIG_CXD56_HSSD4BIT_FREQ +# define CONFIG_CXD56_HSSD4BIT_FREQ 50000000 /* 50MHz SD 4-bit, highspeed clocking */ +#endif + +#define CXD56_SDIO_BASECLK_FREQ (cxd56_get_sdio_baseclock()*2) + +/* Timing */ + +#define SDHCI_CARDSTATETIMEOUT (2000000) +#define SDHCI_CMDTIMEOUT (100000) +#define SDHCI_LONGTIMEOUT (1000000) + +#define SDHCI_WAIT_POWERON MSEC2TICK(252) +#define SDHCI_WAIT_POWEROFF MSEC2TICK(300) + +/* Big DVS setting. Range is 0=SDCLK*213 through 14=SDCLK*227 */ + +#define SDHCI_DTOCV_MAXTIMEOUT (0xF-0x1) +#define SDHCI_DTOCV_DATATIMEOUT (0XF-0x1) + +/* Data transfer / Event waiting interrupt mask bits */ + +#define SDHCI_RESPERR_INTS (SDHCI_INT_CCE|SDHCI_INT_CTOE|SDHCI_INT_CEBE|SDHCI_INT_CIE) +#define SDHCI_RESPDONE_INTS (SDHCI_RESPERR_INTS|SDHCI_INT_CC) + +#define SDHCI_XFRERR_INTS (SDHCI_INT_DCE|SDHCI_INT_DTOE|SDHCI_INT_DEBE) +#define SDHCI_RCVDONE_INTS (SDHCI_XFRERR_INTS|SDHCI_INT_BRR|SDHCI_INT_TC) +#define SDHCI_SNDDONE_INTS (SDHCI_XFRERR_INTS|SDHCI_INT_BWR|SDHCI_INT_TC) +#define SDHCI_XFRDONE_INTS (SDHCI_XFRERR_INTS|SDHCI_INT_BRR|SDHCI_INT_BWR|SDHCI_INT_TC) + +#define SDHCI_DMAERR_INTS (SDHCI_INT_DCE|SDHCI_INT_DTOE|SDHCI_INT_DEBE|SDHCI_INT_DMAE) +#define SDHCI_DMADONE_INTS (SDHCI_DMAERR_INTS|SDHCI_INT_DINT|SDHCI_INT_TC) + +#define SDHCI_WAITALL_INTS (SDHCI_RESPDONE_INTS|SDHCI_XFRDONE_INTS|SDHCI_DMADONE_INTS) + +/* Register logging support */ + +#ifdef CONFIG_SDIO_XFRDEBUG +# define SAMPLENDX_BEFORE_SETUP 0 +# define SAMPLENDX_AFTER_SETUP 1 +# define SAMPLENDX_END_TRANSFER 2 +# define DEBUG_NSAMPLES 3 +#endif + +/* DMA */ + +#define CXD56_SDHCI_BUF_SIZE (2048) +#define SDHCI_MAX_BLOCK_COUNT (0xffffffff) +#define SDHCI_MAX_ADMA_TRANS_SIZE (0xffff+1) +#ifndef CONFIG_CXD56_SDIO_MAX_LEN_ADMA_DSCR +# define CXD56_SDIO_MAX_LEN_ADMA_DSCR (16) +#else +# define CXD56_SDIO_MAX_LEN_ADMA_DSCR (CONFIG_CXD56_SDIO_MAX_LEN_ADMA_DSCR) +#endif + +#define SDHCI_ADMA_DSCR_L_LEN_MASK (0xffff0000) +#define SDHCI_ADMA_DSCR_L_LEN_SHIFT (16) +#define SDHCI_ADMA_DSCR_L_ACT_SHIFT (4) +#define SDHCI_ADMA_DSCR_L_ACT_NOP (0<<4) +#define SDHCI_ADMA_DSCR_L_ACT_RSV (1<<4) +#define SDHCI_ADMA_DSCR_L_ACT_TRAN (2<<4) +#define SDHCI_ADMA_DSCR_L_ACT_LNK (3<<4) +#define SDHCI_ADMA_DSCR_L_INT (0x00000004) +#define SDHCI_ADMA_DSCR_L_END (0x00000002) +#define SDHCI_ADMA_DSCR_L_VALID (0x00000001) +#define SDHCI_ADMA_DSCR_H_ADDR_MASK (0xffffffff) + +#define CXD56_SDHCI_ADSADDR_H (CXD56_SDHCI_ADSADDR+0x4) + +/* Card Common Control Registers (CCCR) */ + +#define SDIO_CCCR_SIZE 0x100 + +#define SDIO_CMD5253_READ (0<<31) +#define SDIO_CMD5253_WRITE (1<<31) +#define SDIO_CMD5253_FUNC_SHIFT (28) + +#define SDIO_CMD52_EXCHANGE (1<<27) +#define SDIO_CMD52_REG_SHIFT (9) +#define SDIO_CMD52_DATA_MASK 0xff + +#define CMD52_RESP_OK(resp) (0 == (resp&0xCB00)) + +/* For Function Basic Registers */ + +#define SDIO_FBR_START 0x100 + +/* Card Information Structure (CIS) */ + +#define SDIO_CIS_START 0x1000 +#define SDIO_CIS_END (SDIO_CIS_START+0x17000-0x10) + +/* CIS tuple codes (based on PC Card 16) */ + +#define SDIO_CISTPL_NULL 0x00 +#define SDIO_CISTPL_VERS_1 0x15 +#define SDIO_CISTPL_MANFID 0x20 +#define SDIO_CISTPL_FUNCID 0x21 +#define SDIO_CISTPL_FUNCE 0x22 +#define SDIO_CISTPL_END 0xff + +/* CISTPL_FUNCID codes */ + +#define TPLFID_FUNC_SDIO 0x0c + +#define SDIO_THREAD_DEFPRIO 50 +#define SDIO_THREAD_STACKSIZE 1024 + +#define SDIO_OCR_NUM_FUNCTIONS(ocr) (((ocr) >> 28) & 0x7) +#define SDIO_FUNC_NUM_MAX (7) + +#ifndef MIN +# define MIN(a, b) ((a) < (b) ? (a) : (b)) +#endif + +#define SDIO_BLOCK_TIMEOUT 200 +#define SDIO_BLOCK_SIZE 512 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +#ifdef CONFIG_CXD56_SDIO_ENABLE_MULTIFUNCTION +/* Structure describing a single SDIO card slot. */ + +struct sdio_softc_s +{ + int func_num; /* number of I/O functions (SDIO) */ + FAR struct sdio_function_s *fn[SDIO_FUNC_NUM_MAX + 1]; /* selected card */ + bool full_speed; /* high speed mode */ + uint8_t dma; /* true: hardware supports DMA */ + sem_t sem; /* Assures mutually exclusive access to the sdio */ +}; + +/* Structure describing either an SDIO device I/O function. */ + +struct sdio_function_s +{ + /* common members */ + FAR struct sdio_softc_s *sc; /* card slot softc */ + sdio_irqhandler_t *irq_callback; /* function callback */ + int number; /* I/O function number or -1, 0 for func0,1 for func1... */ + struct sdio_cis_s cis; /* decoded CIS */ +}; +#endif /* CONFIG_CXD56_SDIO_ENABLE_MULTIFUNCTION */ + +/* This structure defines the state of the CXD56xx SDIO interface */ + +struct cxd56_sdiodev_s +{ + struct sdio_dev_s dev; /* Standard, base SDIO interface */ + + /* CXD56xx-specific extensions */ + /* Event support */ + + sem_t waitsem; /* Implements event waiting */ + sdio_eventset_t waitevents; /* Set of events to be waited for */ + uint32_t waitints; /* Interrupt enables for event waiting */ + volatile sdio_eventset_t wkupevent; /* The event that caused the wakeup */ + WDOG_ID waitwdog; /* Watchdog that handles event timeouts */ + + /* Callback support */ + + sdio_statset_t cdstatus; /* Card status */ + sdio_eventset_t cbevents; /* Set of events to be cause callbacks */ + worker_t callback; /* Registered callback function */ + void *cbarg; /* Registered callback argument */ + struct work_s cbwork; /* Callback work queue structure */ + + /* Interrupt mode data transfer support */ + + uint32_t *buffer; /* Address of current R/W buffer */ + size_t remaining; /* Number of bytes remaining in the transfer */ + uint32_t xfrints; /* Interrupt enables for data transfer */ + + /* DMA data transfer support */ + +#ifdef CONFIG_SDIO_DMA + volatile uint8_t xfrflags; /* Used to synchronize SDIO and DMA completion events */ + bool usedma; + bool dmasend_prepare; + size_t receive_size; + uint8_t *aligned_buffer; /* Used to buffer alignment */ + uint8_t *receive_buffer; /* Used to keep receive buffer address */ + uint32_t dma_cmd; + uint32_t dmasend_cmd; + uint32_t dmasend_regcmd; +#endif + + /* Parameters */ + + uint16_t blocksize; +#ifdef CONFIG_CXD56_SDIO_ENABLE_MULTIFUNCTION + struct sdio_softc_s sc; /* Structure describing a single SDIO card slot. */ +#endif /* CONFIG_CXD56_SDIO_ENABLE_MULTIFUNCTION */ +}; + +/* Register logging support */ + +#ifdef CONFIG_SDIO_XFRDEBUG +struct cxd56_sdhcregs_s +{ + /* All read-able SDHC registers */ + + uint32_t dsaddr; /* DMA System Address Register */ + uint32_t blkattr; /* Block Attributes Register */ + uint32_t cmdarg; /* Command Argument Register */ + uint32_t xferty; /* Transfer Type Register */ + uint32_t cmdrsp0; /* Command Response 0 */ + uint32_t cmdrsp1; /* Command Response 1 */ + uint32_t cmdrsp2; /* Command Response 2 */ + uint32_t cmdrsp3; /* Command Response 3 */ + uint32_t prsstat; /* Present State Register */ + uint32_t proctl; /* Protocol Control Register */ + uint32_t sysctl; /* System Control Register */ + uint32_t irqstat; /* Interrupt Status Register */ + uint32_t irqstaten; /* Interrupt Status Enable Register */ + uint32_t irqsigen; /* Interrupt Signal Enable Register */ + uint32_t ac12err; /* Auto CMD12 Error Status Register */ + uint32_t htcapblt; /* Host Controller Capabilities */ + uint32_t admaes; /* ADMA Error Status Register */ + uint32_t adsaddr; /* ADMA System Address Register */ + uint32_t vendor; /* Vendor Specific Register */ + uint32_t hostver; /* Host Controller Version */ +}; +#endif + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Low-level helpers ********************************************************/ + +static void cxd56_takesem(struct cxd56_sdiodev_s *priv); +#define cxd56_givesem(priv) (sem_post(&(priv)->waitsem)) +static void cxd56_configwaitints(struct cxd56_sdiodev_s *priv, uint32_t waitints, + sdio_eventset_t waitevents, sdio_eventset_t wkupevents); +static void cxd56_configxfrints(struct cxd56_sdiodev_s *priv, uint32_t xfrints); + +/* DMA Helpers **************************************************************/ + +#ifdef CONFIG_SDIO_XFRDEBUG +static void cxd56_sampleinit(void); +static void cxd56_sdhcsample(struct cxd56_sdhcregs_s *regs); +static void cxd56_sample(struct cxd56_sdiodev_s *priv, int index); +static void cxd56_dumpsample(struct cxd56_sdiodev_s *priv, + struct cxd56_sdhcregs_s *regs, const char *msg); +static void cxd56_dumpsamples(struct cxd56_sdiodev_s *priv); +static void cxd56_showregs(struct cxd56_sdiodev_s *priv, const char *msg); +#else +# define cxd56_sampleinit() +# define cxd56_sample(priv,index) +# define cxd56_dumpsamples(priv) +# define cxd56_showregs(priv,msg) +#endif + +/* Data Transfer Helpers ****************************************************/ + +static void cxd56_dataconfig(struct cxd56_sdiodev_s *priv, bool bwrite, + unsigned int blocksize, unsigned int nblocks, + unsigned int timeout); +static void cxd56_datadisable(void); +static void cxd56_transmit(struct cxd56_sdiodev_s *priv); +static void cxd56_receive(struct cxd56_sdiodev_s *priv); +static void cxd56_eventtimeout(int argc, uint32_t arg); +static void cxd56_endwait(struct cxd56_sdiodev_s *priv, sdio_eventset_t wkupevent); +static void cxd56_endtransfer(struct cxd56_sdiodev_s *priv, sdio_eventset_t wkupevent); + +/* Interrupt Handling *******************************************************/ + +static int cxd56_interrupt(int irq, FAR void *context, FAR void *arg); + +/* SDIO interface methods ***************************************************/ + +/* Mutual exclusion */ + +#ifdef CONFIG_SDIO_MUXBUS +static int cxd56_sdio_lock(FAR struct sdio_dev_s *dev, bool lock); +#endif + +/* Initialization/setup */ + +static void cxd56_sdio_sdhci_reset(FAR struct sdio_dev_s *dev); +static sdio_capset_t cxd56_sdio_capabilities(FAR struct sdio_dev_s *dev); +static sdio_statset_t cxd56_sdio_status(FAR struct sdio_dev_s *dev); +static void cxd56_sdio_widebus(FAR struct sdio_dev_s *dev, bool enable); +static void cxd56_sdio_frequency(uint32_t frequency); +static void cxd56_sdio_clock(FAR struct sdio_dev_s *dev, + enum sdio_clock_e rate); +static int cxd56_sdio_attach(FAR struct sdio_dev_s *dev); + +/* Command/Status/Data Transfer */ + +static int cxd56_sdio_sendcmd(FAR struct sdio_dev_s *dev, uint32_t cmd, + uint32_t arg); +static void cxd56_blocksetup(FAR struct sdio_dev_s *dev, unsigned int blocklen, + unsigned int nblocks); +static int cxd56_sdio_recvsetup(FAR struct sdio_dev_s *dev, FAR uint8_t *buffer, + size_t nbytes); +static int cxd56_sdio_sendsetup(FAR struct sdio_dev_s *dev, + FAR const uint8_t *buffer, uint32_t nbytes); +static int cxd56_sdio_cancel(FAR struct sdio_dev_s *dev); + +static int cxd56_sdio_waitresponse(FAR struct sdio_dev_s *dev, uint32_t cmd); +static int cxd56_sdio_recvshortcrc(FAR struct sdio_dev_s *dev, uint32_t cmd, + uint32_t *rshort); +static int cxd56_sdio_recvlong(FAR struct sdio_dev_s *dev, uint32_t cmd, + uint32_t rlong[4]); +static int cxd56_sdio_recvshort(FAR struct sdio_dev_s *dev, uint32_t cmd, + uint32_t *rshort); + +/* EVENT handler */ + +static void cxd56_sdio_waitenable(FAR struct sdio_dev_s *dev, + sdio_eventset_t eventset); +static sdio_eventset_t + cxd56_sdio_eventwait(FAR struct sdio_dev_s *dev, uint32_t timeout); +static void cxd56_sdio_callbackenable(FAR struct sdio_dev_s *dev, + sdio_eventset_t eventset); +static int cxd56_sdio_registercallback(FAR struct sdio_dev_s *dev, + worker_t callback, void *arg); + +/* DMA */ + +#ifdef CONFIG_SDIO_DMA +static int cxd56_sdio_admasetup(FAR const uint8_t *buffer, size_t buflen); +static int cxd56_sdio_dmarecvsetup(FAR struct sdio_dev_s *dev, + FAR uint8_t *buffer, size_t buflen); +static int cxd56_sdio_dmasendsetup(FAR struct sdio_dev_s *dev, + FAR const uint8_t *buffer, size_t buflen); +#endif + +#ifdef CONFIG_CXD56_SDIO_ENABLE_MULTIFUNCTION +static int cxd56_sdio_enable_cardint(void); +static int cxd56_sdio_register_irq(FAR struct sdio_dev_s *dev, int func_num, + FAR sdio_irqhandler_t * handler); +static int cxd56_sdio_function_disable(FAR struct sdio_dev_s *dev, int func_num); +static int cxd56_sdio_function_enable(FAR struct sdio_dev_s *dev, int func_num); +static int cxd56_sdio_readb(FAR struct sdio_dev_s *dev, int func_num, + uint32_t addr, FAR uint8_t * rdata); +static int cxd56_sdio_writeb(FAR struct sdio_dev_s *dev, int func_num, + uint32_t addr, uint8_t data, FAR uint8_t * rdata); +static int cxd56_sdio_read(FAR struct sdio_dev_s *dev, int func_num, uint32_t addr, + FAR uint8_t * data, uint32_t size); +static int cxd56_sdio_write(FAR struct sdio_dev_s *dev, int func_num, uint32_t addr, + FAR uint8_t * data, uint32_t size); +static int cxd56_sdhci_irq_handler(FAR struct sdio_dev_s *dev); +static int cxd56_sdio_get_cis(FAR struct sdio_dev_s *dev, int func_num, + FAR struct sdio_cis_s * cis); +#endif /* CONFIG_CXD56_SDIO_ENABLE_MULTIFUNCTION */ + +/* Initialization/uninitialization/reset ************************************/ + +static void cxd56_sdio_callback(void *arg); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +struct cxd56_sdiodev_s g_sdhcdev = +{ + .dev = + { +#ifdef CONFIG_SDIO_MUXBUS + .lock = cxd56_sdio_lock, +#endif + .reset = cxd56_sdio_sdhci_reset, + .capabilities = cxd56_sdio_capabilities, + .status = cxd56_sdio_status, + .widebus = cxd56_sdio_widebus, + .clock = cxd56_sdio_clock, + .attach = cxd56_sdio_attach, + .sendcmd = cxd56_sdio_sendcmd, + .blocksetup = cxd56_blocksetup, + .recvsetup = cxd56_sdio_recvsetup, + .sendsetup = cxd56_sdio_sendsetup, + .cancel = cxd56_sdio_cancel, + .waitresponse = cxd56_sdio_waitresponse, + .recvR1 = cxd56_sdio_recvshortcrc, + .recvR2 = cxd56_sdio_recvlong, + .recvR3 = cxd56_sdio_recvshort, + .recvR4 = cxd56_sdio_recvshort, + .recvR5 = cxd56_sdio_recvshort, + .recvR6 = cxd56_sdio_recvshortcrc, + .recvR7 = cxd56_sdio_recvshort, + .waitenable = cxd56_sdio_waitenable, + .eventwait = cxd56_sdio_eventwait, + .callbackenable = cxd56_sdio_callbackenable, + .registercallback = cxd56_sdio_registercallback, +#ifdef CONFIG_SDIO_DMA + .dmarecvsetup = cxd56_sdio_dmarecvsetup, + .dmasendsetup = cxd56_sdio_dmasendsetup, +#endif +#ifdef CONFIG_CXD56_SDIO_ENABLE_MULTIFUNCTION + .register_irq = cxd56_sdio_register_irq, + .function_disable = cxd56_sdio_function_disable, + .function_enable = cxd56_sdio_function_enable, + .readb = cxd56_sdio_readb, + .writeb = cxd56_sdio_writeb, + .read = cxd56_sdio_read, + .write = cxd56_sdio_write, + .get_cis = cxd56_sdio_get_cis, +#endif /* CONFIG_CXD56_SDIO_ENABLE_MULTIFUNCTION */ + }, +}; + +/* Register logging support */ + +#ifdef CONFIG_SDIO_XFRDEBUG +static struct cxd56_sdhcregs_s g_sampleregs[DEBUG_NSAMPLES]; +#endif + +/* DMA */ + +#ifdef CONFIG_SDIO_DMA +static FAR uint32_t cxd56_sdhci_adma_dscr[CXD56_SDIO_MAX_LEN_ADMA_DSCR*2]; +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Low-level Helpers + ****************************************************************************/ +/**************************************************************************** + * Name: cxd56_takesem + * + * Description: + * Take the wait semaphore (handling false alarm wakeups due to the receipt + * of signals). + * + * Input Parameters: + * dev - Instance of the SDIO device driver state structure. + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void cxd56_takesem(struct cxd56_sdiodev_s *priv) +{ + /* Take the semaphore (perhaps waiting) */ + + while (sem_wait(&priv->waitsem) != 0) + { + /* The only case that an error should occr here is if the wait was + * awakened by a signal. + */ + + ASSERT(errno == EINTR); + } +} + +/**************************************************************************** + * Name: cxd56_configwaitints + * + * Description: + * Enable/disable SDIO interrupts needed to suport the wait function + * + * Input Parameters: + * priv - A reference to the SDIO device state structure + * waitints - The set of bits in the SDIO MASK register to set + * waitevents - Waited for events + * wkupevent - Wake-up events + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void cxd56_configwaitints(struct cxd56_sdiodev_s *priv, uint32_t waitints, + sdio_eventset_t waitevents, + sdio_eventset_t wkupevent) +{ + irqstate_t flags; + + /* Save all of the data and set the new interrupt mask in one, atomic + * operation. + */ + + flags = enter_critical_section(); + priv->waitevents = waitevents; + priv->wkupevent = wkupevent; + priv->waitints = waitints; +#ifdef CONFIG_SDIO_DMA + priv->xfrflags = 0; +#endif + putreg32(priv->xfrints | priv->waitints | SDHCI_INT_CINT, + CXD56_SDHCI_IRQSIGEN); + leave_critical_section(flags); +} + +/**************************************************************************** + * Name: cxd56_configxfrints + * + * Description: + * Enable SDIO interrupts needed to support the data transfer event + * + * Input Parameters: + * priv - A reference to the SDIO device state structure + * xfrints - The set of bits in the SDIO MASK register to set + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void cxd56_configxfrints(struct cxd56_sdiodev_s *priv, uint32_t xfrints) +{ + irqstate_t flags; + flags = enter_critical_section(); + priv->xfrints = xfrints; + putreg32(priv->xfrints | priv->waitints | SDHCI_INT_CINT,CXD56_SDHCI_IRQSIGEN); + leave_critical_section(flags); +} + +/**************************************************************************** + * DMA Helpers + ****************************************************************************/ + +/**************************************************************************** + * Name: cxd56_sampleinit + * + * Description: + * Setup prior to collecting DMA samples + * + ****************************************************************************/ + +#ifdef CONFIG_SDIO_XFRDEBUG +static void cxd56_sampleinit(void) +{ + memset(g_sampleregs, 0xff, DEBUG_NSAMPLES * sizeof(struct cxd56_sdhcregs_s)); +} +#endif + +/**************************************************************************** + * Name: cxd56_sdhcsample + * + * Description: + * Sample SDIO registers + * + ****************************************************************************/ + +#ifdef CONFIG_SDIO_XFRDEBUG +static void cxd56_sdhcsample(struct cxd56_sdhcregs_s *regs) +{ + regs->dsaddr = getreg32(CXD56_SDHCI_DSADDR); /* DMA System Address Register */ + regs->blkattr = getreg32(CXD56_SDHCI_BLKATTR); /* Block Attributes Register */ + regs->cmdarg = getreg32(CXD56_SDHCI_CMDARG); /* Command Argument Register */ + regs->xferty = getreg32(CXD56_SDHCI_XFERTYP); /* Transfer Type Register */ + regs->cmdrsp0 = getreg32(CXD56_SDHCI_CMDRSP0); /* Command Response 0 */ + regs->cmdrsp1 = getreg32(CXD56_SDHCI_CMDRSP1); /* Command Response 1 */ + regs->cmdrsp2 = getreg32(CXD56_SDHCI_CMDRSP2); /* Command Response 2 */ + regs->cmdrsp3 = getreg32(CXD56_SDHCI_CMDRSP3); /* Command Response 3 */ + regs->prsstat = getreg32(CXD56_SDHCI_PRSSTAT); /* Present State Register */ + regs->proctl = getreg32(CXD56_SDHCI_PROCTL); /* Protocol Control Register */ + regs->sysctl = getreg32(CXD56_SDHCI_SYSCTL); /* System Control Register */ + regs->irqstat = getreg32(CXD56_SDHCI_IRQSTAT); /* Interrupt Status Register */ + regs->irqstaten = getreg32(CXD56_SDHCI_IRQSTATEN); /* Interrupt Status Enable Register */ + regs->irqsigen = getreg32(CXD56_SDHCI_IRQSIGEN); /* Interrupt Signal Enable Register */ + regs->ac12err = getreg32(CXD56_SDHCI_AC12ERR); /* Auto CMD12 Error Status Register */ + regs->htcapblt = getreg32(CXD56_SDHCI_HTCAPBLT); /* Host Controller Capabilities */ + regs->admaes = getreg32(CXD56_SDHCI_ADMAES); /* ADMA Error Status Register */ + regs->adsaddr = getreg32(CXD56_SDHCI_ADSADDR); /* ADMA System Address Register */ + regs->vendor = getreg32(CXD56_SDHCI_VENDOR); /* Vendor Specific Register */ + regs->hostver = getreg32(CXD56_SDHCI_HOSTVER); /* Host Controller Version */ +} +#endif + +/**************************************************************************** + * Name: cxd56_sample + * + * Description: + * Sample SDIO/DMA registers + * + ****************************************************************************/ + +#ifdef CONFIG_SDIO_XFRDEBUG +static void cxd56_sample(struct cxd56_sdiodev_s *priv, int index) +{ + cxd56_sdhcsample(&g_sampleregs[index]); +} +#endif + +/**************************************************************************** + * Name: cxd56_dumpsample + * + * Description: + * Dump one register sample + * + ****************************************************************************/ + +#ifdef CONFIG_SDIO_XFRDEBUG +static void cxd56_dumpsample(struct cxd56_sdiodev_s *priv, + struct cxd56_sdhcregs_s *regs, const char *msg) +{ + mcinfo("SDHC Registers: %s\n", msg); + mcinfo(" DSADDR[%08x]: %08x\n", CXD56_SDHCI_DSADDR, regs->dsaddr); + mcinfo(" BLKATTR[%08x]: %08x\n", CXD56_SDHCI_BLKATTR, regs->blkattr); + mcinfo(" CMDARG[%08x]: %08x\n", CXD56_SDHCI_CMDARG, regs->cmdarg); + mcinfo(" COMMAND[%08x]: %08x\n", CXD56_SDHCI_XFERTYP, regs->xferty); + mcinfo(" CMDRSP0[%08x]: %08x\n", CXD56_SDHCI_CMDRSP0, regs->cmdrsp0); + mcinfo(" CMDRSP1[%08x]: %08x\n", CXD56_SDHCI_CMDRSP1, regs->cmdrsp1); + mcinfo(" CMDRSP2[%08x]: %08x\n", CXD56_SDHCI_CMDRSP2, regs->cmdrsp2); + mcinfo(" CMDRSP3[%08x]: %08x\n", CXD56_SDHCI_CMDRSP3, regs->cmdrsp3); + mcinfo(" PRSSTAT[%08x]: %08x\n", CXD56_SDHCI_PRSSTAT, regs->prsstat); + mcinfo(" PROCTL[%08x]: %08x\n", CXD56_SDHCI_PROCTL, regs->proctl); + mcinfo(" HOSTCTL[%08x]: %08x\n", CXD56_SDHCI_SYSCTL, regs->sysctl); + mcinfo(" IRQSTAT[%08x]: %08x\n", CXD56_SDHCI_IRQSTAT, regs->irqstat); + mcinfo("IRQSTATEN[%08x]: %08x\n", CXD56_SDHCI_IRQSTATEN, regs->irqstaten); + mcinfo(" IRQSIGEN[%08x]: %08x\n", CXD56_SDHCI_IRQSIGEN, regs->irqsigen); + mcinfo(" AC12ERR[%08x]: %08x\n", CXD56_SDHCI_AC12ERR, regs->ac12err); + mcinfo(" HTCAPBLT[%08x]: %08x\n", CXD56_SDHCI_HTCAPBLT, regs->htcapblt); + mcinfo(" ADMAES[%08x]: %08x\n", CXD56_SDHCI_ADMAES, regs->admaes); + mcinfo(" ADSADDR[%08x]: %08x\n", CXD56_SDHCI_ADSADDR, regs->adsaddr); + mcinfo(" HOSTVER[%08x]: %08x\n", CXD56_SDHCI_HOSTVER, regs->hostver); +} +#endif + +/**************************************************************************** + * Name: cxd56_dumpsamples + * + * Description: + * Dump all sampled register data + * + ****************************************************************************/ + +#ifdef CONFIG_SDIO_XFRDEBUG +static void cxd56_dumpsamples(struct cxd56_sdiodev_s *priv) +{ + cxd56_dumpsample(priv, &g_sampleregs[SAMPLENDX_BEFORE_SETUP], "Before setup"); + cxd56_dumpsample(priv, &g_sampleregs[SAMPLENDX_AFTER_SETUP], "After setup"); + cxd56_dumpsample(priv, &g_sampleregs[SAMPLENDX_END_TRANSFER], "End of transfer"); +} +#endif + +/**************************************************************************** + * Name: cxd56_showregs + * + * Description: + * Dump the current state of all registers + * + ****************************************************************************/ + +#ifdef CONFIG_SDIO_XFRDEBUG +static void cxd56_showregs(struct cxd56_sdiodev_s *priv, const char *msg) +{ + struct cxd56_sdhcregs_s regs; + + cxd56_sdhcsample(®s); + cxd56_dumpsample(priv, ®s, msg); +} +#endif + +/**************************************************************************** + * Data Transfer Helpers + ****************************************************************************/ + +/**************************************************************************** + * Name: cxd56_dataconfig + * + * Description: + * Configure the SDIO data path for the next data transfer + * + ****************************************************************************/ + +static void cxd56_dataconfig(struct cxd56_sdiodev_s *priv, bool bwrite, + unsigned int blocksize, unsigned int nblocks, + unsigned int timeout) +{ + //unsigned int watermark; + uint32_t regval = 0; + + /* Set the data timeout value in the SDHCI_SYSCTL field to the selected value */ + + regval = getreg32(CXD56_SDHCI_SYSCTL); + regval &= ~SDHCI_SYSCTL_DTOCV_MASK; + regval |= timeout << SDHCI_SYSCTL_DTOCV_SHIFT; + putreg32(regval, CXD56_SDHCI_SYSCTL); + + /* Set the block size and count in the SDHCI_BLKATTR register. The block + * size is only valid for multiple block transfers. + */ + + priv->blocksize = blocksize; + + regval = blocksize << SDHCI_BLKATTR_SIZE_SHIFT | + nblocks << SDHCI_BLKATTR_CNT_SHIFT; + putreg32(regval, CXD56_SDHCI_BLKATTR); +} + +/**************************************************************************** + * Name: cxd56_datadisable + * + * Description: + * Disable the SDIO data path setup by cxd56_dataconfig() and + * disable DMA. + * + ****************************************************************************/ + +static void cxd56_datadisable(void) +{ + uint32_t regval; + + /* Set the data timeout value in the SDHCI_SYSCTL field to the maximum value */ + + regval = getreg32(CXD56_SDHCI_SYSCTL); + regval &= ~SDHCI_SYSCTL_DTOCV_MASK; + regval |= SDHCI_DTOCV_MAXTIMEOUT << SDHCI_SYSCTL_DTOCV_SHIFT; + putreg32(regval, CXD56_SDHCI_SYSCTL); + + /* Set the block size to zero (no transfer) */ + + putreg32(0, CXD56_SDHCI_BLKATTR); +} + +/**************************************************************************** + * Name: cxd56_transmit + * + * Description: + * Send SDIO data in interrupt mode + * + * Input Parameters: + * priv - An instance of the SDIO device interface + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void cxd56_transmit(struct cxd56_sdiodev_s *priv) +{ + union + { + uint32_t w; + uint8_t b[4]; + } data; + + /* Loop while there is more data to be sent, waiting for buffer write + * ready (BWR) + */ + + if (priv->buffer == 0) + { + return; + } + + mcinfo("Entry: remaining: %d IRQSTAT: %08x\n", + priv->remaining, getreg32(CXD56_SDHCI_IRQSTAT)); + + while (priv->remaining > 0 && + (getreg32(CXD56_SDHCI_IRQSTAT) & SDHCI_INT_BWR) != 0) + { + /* Clear BWR. If there is more data in the buffer, writing to the + * buffer should reset BRR. + */ + + putreg32(SDHCI_INT_BWR, CXD56_SDHCI_IRQSTAT); + + while (priv->remaining > 0 && (getreg32(CXD56_SDHCI_PRSSTAT) & SDHCI_PRSSTAT_BWEN) != 0) + { + /* Is there a full word remaining in the user buffer? */ + + if (priv->remaining >= sizeof(uint32_t)) + { + /* Yes, transfer the word to the TX FIFO */ + + data.w = *priv->buffer++; + priv->remaining -= sizeof(uint32_t); + } + else + { + /* No.. transfer just the bytes remaining in the user buffer, + * padding with zero as necessary to extend to a full word. + */ + + uint8_t *ptr = (uint8_t *)priv->buffer; + int i; + + data.w = 0; + for (i = 0; i < priv->remaining; i++) + { + data.b[i] = *ptr++; + } + + /* Now the transfer is finished */ + + priv->remaining = 0; + } + + /* Put the word in the FIFO */ + + putreg32(data.w, CXD56_SDHCI_DATPORT); + } + } + + mcinfo("Exit: remaining: %d IRQSTAT: %08x\n", + priv->remaining, getreg32(CXD56_SDHCI_IRQSTAT)); +} + +/**************************************************************************** + * Name: cxd56_receive + * + * Description: + * Receive SDIO data in interrupt mode + * + * Input Parameters: + * priv - An instance of the SDIO device interface + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void cxd56_receive(struct cxd56_sdiodev_s *priv) +{ + union + { + uint32_t w; + uint8_t b[4]; + } data; + + /* Loop while there is space to store the data, waiting for buffer read + * ready (BRR) + */ + + if (priv->buffer == 0) + { + return; + } + + mcinfo("Entry: remaining: %d IRQSTAT: %08x\n", + priv->remaining, getreg32(CXD56_SDHCI_IRQSTAT)); + + while (priv->remaining > 0 && + (getreg32(CXD56_SDHCI_IRQSTAT) & SDHCI_INT_BRR) != 0) + { + /* Clear BRR. If there is more data in the buffer, reading from the + * buffer should reset BRR. + */ + + putreg32(SDHCI_INT_BRR, CXD56_SDHCI_IRQSTAT); + + while (priv->remaining > 0 && (getreg32(CXD56_SDHCI_PRSSTAT) & SDHCI_PRSSTAT_BREN) != 0) + { + /* Read the next word from the RX buffer */ + + data.w = getreg32(CXD56_SDHCI_DATPORT); + if (priv->remaining >= sizeof(uint32_t)) + { + /* Transfer the whole word to the user buffer */ + + *priv->buffer++ = data.w; + priv->remaining -= sizeof(uint32_t); + } + else + { + /* Transfer any trailing fractional word */ + + uint8_t *ptr = (uint8_t *)priv->buffer; + int i; + + for (i = 0; i < priv->remaining; i++) + { + *ptr++ = data.b[i]; + } + + /* Now the transfer is finished */ + + priv->remaining = 0; + } + } + } + +} + +/**************************************************************************** + * Name: cxd56_eventtimeout + * + * Description: + * The watchdog timeout setup when the event wait start has expired without + * any other waited-for event occurring. + * + * Input Parameters: + * argc - The number of arguments (should be 1) + * arg - The argument (state structure reference cast to uint32_t) + * + * Returned Value: + * None + * + * Assumptions: + * Always called from the interrupt level with interrupts disabled. + * + ****************************************************************************/ + +static void cxd56_eventtimeout(int argc, uint32_t arg) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)arg; + + DEBUGASSERT(argc == 1 && priv != NULL); + DEBUGASSERT((priv->waitevents & SDIOWAIT_TIMEOUT) != 0); + + /* Is a data transfer complete event expected? */ + + if ((priv->waitevents & SDIOWAIT_TIMEOUT) != 0) + { + /* Yes.. Sample registers at the time of the timeout */ + + cxd56_sample(priv, SAMPLENDX_END_TRANSFER); + + /* Wake up any waiting threads */ + + cxd56_endwait(priv, SDIOWAIT_TIMEOUT); + mcwarn("Timeout: remaining: %d\n", priv->remaining); + } +} + +/**************************************************************************** + * Name: cxd56_endwait + * + * Description: + * Wake up a waiting thread if the waited-for event has occurred. + * + * Input Parameters: + * priv - An instance of the SDIO device interface + * wkupevent - The event that caused the wait to end + * + * Returned Value: + * None + * + * Assumptions: + * Always called from the interrupt level with interrupts disabled. + * + ****************************************************************************/ + +static void cxd56_endwait(struct cxd56_sdiodev_s *priv, sdio_eventset_t wkupevent) +{ + /* Cancel the watchdog timeout */ + + (void)wd_cancel(priv->waitwdog); + + /* Disable event-related interrupts */ + + cxd56_configwaitints(priv, 0, 0, wkupevent); + + /* Wake up the waiting thread */ + + cxd56_givesem(priv); +} + +/**************************************************************************** + * Name: cxd56_endtransfer + * + * Description: + * Terminate a transfer with the provided status. This function is called + * only from the SDIO interrupt handler when end-of-transfer conditions + * are detected. + * + * Input Parameters: + * priv - An instance of the SDIO device interface + * wkupevent - The event that caused the transfer to end + * + * Returned Value: + * None + * + * Assumptions: + * Always called from the interrupt level with interrupts disabled. + * + ****************************************************************************/ + +static void cxd56_endtransfer(struct cxd56_sdiodev_s *priv, sdio_eventset_t wkupevent) +{ +#ifdef CONFIG_SDIO_DMA + uint32_t regval; +#endif + + if (priv->buffer == 0) + { + return; + } + + /* Disable all transfer related interrupts */ + + cxd56_configxfrints(priv, 0); + + /* Clearing pending interrupt status on all transfer related interrupts */ + + putreg32(SDHCI_XFRDONE_INTS, CXD56_SDHCI_IRQSTAT); + + /* If this was a DMA transfer, make sure that DMA is stopped */ + +#ifdef CONFIG_SDIO_DMA + /* Stop the DMA by resetting the data path */ + + regval = getreg32(CXD56_SDHCI_SYSCTL); + regval |= SDHCI_SYSCTL_RSTD; + putreg32(regval, CXD56_SDHCI_SYSCTL); + cxd56_sdhci_adma_dscr[0] = 0; + cxd56_sdhci_adma_dscr[1] = 0; + putreg32((uint32_t)cxd56_sdhci_adma_dscr, CXD56_SDHCI_ADSADDR); + putreg32(0, CXD56_SDHCI_ADSADDR_H); + priv->usedma = false; + priv->dmasend_prepare = false; + priv->dmasend_cmd = 0; + priv->dmasend_regcmd = 0; +#endif + + /* Mark the transfer finished */ + + if ((priv->waitevents & wkupevent & (SDIOWAIT_TRANSFERDONE | SDIOWAIT_RESPONSEDONE)) == 0) + { + priv->remaining = 0; + } + priv->buffer = 0; + + /* Debug instrumentation */ + + cxd56_sample(priv, SAMPLENDX_END_TRANSFER); + + /* Is a thread wait for these data transfer complete events? */ + + if ((priv->waitevents & wkupevent) != 0) + { + /* Yes.. wake up any waiting threads */ + + cxd56_endwait(priv, wkupevent); + } +} + +/**************************************************************************** + * Interrupt Handling + ****************************************************************************/ + +/**************************************************************************** + * Name: cxd56_interrupt + * + * Description: + * SDIO interrupt handler + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * + * Returned Value: + * None + * + ****************************************************************************/ + +static int cxd56_interrupt(int irq, FAR void *context, FAR void *arg) +{ + struct cxd56_sdiodev_s *priv = &g_sdhcdev; + uint32_t enabled; + uint32_t pending; + uint32_t regval; + + /* Check the SDHC IRQSTAT register. Mask out all bits that don't + * correspond to enabled interrupts. (This depends on the fact that bits + * are ordered the same in both the IRQSTAT and IRQSIGEN registers). If + * there are non-zero bits remaining, then we have work to do here. + */ + + regval = getreg32(CXD56_SDHCI_IRQSIGEN); + enabled = getreg32(CXD56_SDHCI_IRQSTAT) & regval; + mcinfo("IRQSTAT: %08x IRQSIGEN %08x enabled: %08x\n", + getreg32(CXD56_SDHCI_IRQSTAT), regval, enabled); + + /* Disable card interrupts to clear the card interrupt to the host system. */ + + regval &= ~(SDHCI_INT_CINT | enabled); + putreg32(regval, CXD56_SDHCI_IRQSIGEN); + + /* Clear all pending interrupts */ + + //putreg32(enabled, CXD56_SDHCI_IRQSTAT); + + /* Handle in progress, interrupt driven data transfers ********************/ + + pending = enabled & priv->xfrints; + if (pending != 0) + { + /* Is the RX buffer read ready? Is so then we must be processing a + * non-DMA receive transaction. + */ + + if ((pending & SDHCI_INT_BRR) != 0) + { + /* Receive data from the RX buffer */ + + cxd56_receive(priv); + } + + /* Otherwise, Is the TX buffer write ready? If so we must + * be processing a non-DMA send transaction. NOTE: We can't be + * processing both! + */ + + else if ((pending & SDHCI_INT_BWR) != 0) + { + /* Send data via the TX FIFO */ + + cxd56_transmit(priv); + } + + /* Handle transfer complete events */ + + if ((pending & SDHCI_INT_TC) != 0) + { + /* Terminate the transfer */ + + cxd56_endtransfer(priv, SDIOWAIT_TRANSFERDONE); + } + + /* Handle data block send/receive CRC failure */ + + else if ((pending & SDHCI_INT_DCE) != 0) + { + /* Terminate the transfer with an error */ + + mcerr("ERROR: Data block CRC failure, remaining: %d\n", priv->remaining); + cxd56_endtransfer(priv, SDIOWAIT_TRANSFERDONE | SDIOWAIT_ERROR); + } + + /* Handle data timeout error */ + + else if ((pending & SDHCI_INT_DTOE) != 0) + { + /* Terminate the transfer with an error */ + + mcerr("ERROR: Data timeout, remaining: %d\n", priv->remaining); + cxd56_endtransfer(priv, SDIOWAIT_TRANSFERDONE | SDIOWAIT_TIMEOUT); + } + } + +#ifdef CONFIG_CXD56_SDIO_ENABLE_MULTIFUNCTION + if (enabled & SDHCI_INT_CINT) + { + /* Handle card interrupt events */ + + putreg32(getreg32(CXD56_SDHCI_IRQSIGEN) & (~SDHCI_INT_CINT), CXD56_SDHCI_IRQSIGEN); + putreg32(getreg32(CXD56_SDHCI_IRQSTATEN) & (~SDHCI_INT_CINT), CXD56_SDHCI_IRQSTATEN); + work_cancel(HPWORK, &priv->cbwork); + (void)work_queue(HPWORK, &priv->cbwork, (worker_t)cxd56_sdhci_irq_handler, &priv->dev, 0); + } +#endif /* CONFIG_CXD56_SDIO_ENABLE_MULTIFUNCTION */ + + /* Handle wait events *****************************************************/ + + pending = enabled & priv->waitints; + if (pending != 0) + { + /* Is this a response completion event? */ + + if ((pending & SDHCI_RESPDONE_INTS) != 0) + { + /* Yes.. Is their a thread waiting for response done? */ + + if ((priv->waitevents & (SDIOWAIT_CMDDONE | SDIOWAIT_RESPONSEDONE)) != 0) + { + /* Yes.. mask further interrupts and wake the thread up */ + + regval = getreg32(CXD56_SDHCI_IRQSIGEN); + regval &= ~SDHCI_RESPDONE_INTS; + putreg32(regval, CXD56_SDHCI_IRQSIGEN); + + cxd56_endwait(priv, SDIOWAIT_RESPONSEDONE); + } + } + } + + /* Re-enable card interrupts */ + + regval = getreg32(CXD56_SDHCI_IRQSIGEN); + regval |= SDHCI_INT_CINT | enabled; + putreg32(regval, CXD56_SDHCI_IRQSIGEN); + + return OK; +} + +/**************************************************************************** + * SDIO Interface Methods + ****************************************************************************/ + +/**************************************************************************** + * Name: cxd56_sdio_lock + * + * Description: + * Locks the bus. Function calls low-level multiplexed bus routines to + * resolve bus requests and acknowledgement issues. + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * lock - TRUE to lock, FALSE to unlock. + * + * Returned Value: + * OK on success; a negated errno on failure + * + ****************************************************************************/ + +#ifdef CONFIG_SDIO_MUXBUS +static int cxd56_sdio_lock(FAR struct sdio_dev_s *dev, bool lock) +{ + /* Single SDIO instance so there is only one possibility. The multiplex + * bus is part of board support package. + */ + + cxd56_muxbus_sdio_lock(lock); + return OK; +} +#endif + +/**************************************************************************** + * Name: cxd56_sdio_sdhci_reset + * + * Description: + * Reset the SDIO controller. Undo all setup and initialization. + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void cxd56_sdio_sdhci_reset(FAR struct sdio_dev_s *dev) +{ + FAR struct cxd56_sdiodev_s *priv = (FAR struct cxd56_sdiodev_s *)dev; + uint32_t regval; + int32_t timeout = 100; + + /* Disable all interrupts so that nothing interferes with the following. */ + + putreg32(0, CXD56_SDHCI_IRQSIGEN); + + /* Reset the SDHC block, putting registers in their default, reset state. + * Initiate the reset by setting the RSTA bit in the SYSCTL register. + */ + + regval = getreg32(CXD56_SDHCI_SYSCTL); + regval |= SDHCI_SYSCTL_RSTA; + putreg32(regval, CXD56_SDHCI_SYSCTL); + + /* The SDHC will reset the RSTA bit to 0 when the capabilities + * registers are valid and the host driver can read them. + */ + + while ((getreg32(CXD56_SDHCI_SYSCTL) & SDHCI_SYSCTL_RSTA) != 0) + { + timeout--; + if (timeout < 1) + { + break; + } + up_mdelay(30); + } + + /* Make sure that all clocking is disabled */ + + cxd56_sdio_clock(dev, CLOCK_SDIO_DISABLED); + + /* Enable all status bits (these could not all be potential sources of + * interrupts. + */ + + putreg32(SDHCI_INT_ALL & (~SDHCI_INT_CINT), CXD56_SDHCI_IRQSTATEN); + + mcinfo("SYSCTL: %08x PRSSTAT: %08x IRQSTATEN: %08x\n", + getreg32(CXD56_SDHCI_SYSCTL), getreg32(CXD56_SDHCI_PRSSTAT), + getreg32(CXD56_SDHCI_IRQSTATEN)); + + /* The next phase of the hardware reset would be to set the SYSCTRL INITA + * bit to send 80 clock ticks for card to power up and then reset the card + * with CMD0. This is done elsewhere. + */ + + /* Reset state data */ + sem_init(&priv->waitsem, 0, 1); + priv->waitwdog = wd_create(); + DEBUGASSERT(priv->waitwdog); + sem_init(&priv->waitsem, 0, 1); + priv->waitevents = 0; /* Set of events to be waited for */ + priv->waitints = 0; /* Interrupt enables for event waiting */ + priv->wkupevent = 0; /* The event that caused the wakeup */ +#ifdef CONFIG_SDIO_DMA + priv->xfrflags = 0; /* Used to synchronize SDIO and DMA completion events */ +#endif + + wd_cancel(priv->waitwdog); /* Cancel any timeouts */ + + /* Interrupt mode data transfer support */ + + priv->buffer = 0; /* Address of current R/W buffer */ + priv->remaining = 0; /* Number of bytes remaining in the transfer */ + priv->xfrints = 0; /* Interrupt enables for data transfer */ + + priv->blocksize = CXD56_SDHCI_BUF_SIZE; +} + +/**************************************************************************** + * Name: cxd56_sdio_capabilities + * + * Description: + * Get capabilities (and limitations) of the SDIO driver (optional) + * + * Input Parameters: + * dev - Device-specific state data + * + * Returned Value: + * Returns a bitset of status values (see SDIO_CAPS_* defines) + * + ****************************************************************************/ + +static sdio_capset_t cxd56_sdio_capabilities(FAR struct sdio_dev_s *dev) +{ + sdio_capset_t caps = 0; + +#ifdef CONFIG_CXD56_SDIO_WIDTH_D1_ONLY + caps |= SDIO_CAPS_1BIT_ONLY; +#endif +#ifdef CONFIG_CXD56_SDIO_DMA + caps |= SDIO_CAPS_DMASUPPORTED; +#endif +#ifndef CONFIG_CXD56_SDIO_DMA + /* In case of non-DMA, add below capability to change the write single + * sequence with sending CMD24. If not, write is not completed. + */ + + caps |= SDIO_CAPS_DMABEFOREWRITE; +#endif + + return caps; +} + +/**************************************************************************** + * Name: cxd56_sdio_status + * + * Description: + * Get SDIO status. + * + * Input Parameters: + * dev - Device-specific state data + * + * Returned Value: + * Returns a bitset of status values (see cxd56_status_* defines) + * + ****************************************************************************/ + +static sdio_statset_t cxd56_sdio_status(FAR struct sdio_dev_s *dev) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + return priv->cdstatus; +} + +/**************************************************************************** + * Name: cxd56_sdio_widebus + * + * Description: + * 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 SDIO device interface + * wide - true: wide bus (4-bit) bus mode enabled + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void cxd56_sdio_widebus(FAR struct sdio_dev_s *dev, bool wide) +{ + uint32_t regval; + + /* Set the Data Transfer Width (DTW) field in the PROCTL register */ + + regval = getreg32(CXD56_SDHCI_PROCTL); + regval &= ~SDHCI_PROCTL_DTW_MASK; + if (wide) + { + regval |= SDHCI_PROCTL_DTW_4BIT; + } + else + { + regval |= SDHCI_PROCTL_DTW_1BIT; + } + putreg32(regval, CXD56_SDHCI_PROCTL); +} + +/**************************************************************************** + * Name: cxd56_sdio_frequency + * + * Description: + * Set the SD clock frequency + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * frequency - The frequency to use + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void cxd56_sdio_frequency(uint32_t frequency) +{ + uint32_t baseclk; + uint16_t i; + uint32_t regval; + uint16_t divisor; + + baseclk = cxd56_get_sdio_baseclock(); + if (frequency >= baseclk) + { + divisor = 0; + } + else + { + for (i=1; i<0x3ff; i++) + { + if (baseclk / (2 * i) < frequency) + { + break; + } + } + divisor = i; + } + + regval = getreg32(CXD56_SDHCI_SYSCTL); + regval &= ~SDHCI_SYSCTL_GENSEL; + regval &= ~(SDHCI_SYSCTL_SDCLKFS_MASK | SDHCI_SYSCTL_SDCLKFSUP_MASK); + regval |= (divisor << SDHCI_SYSCTL_SDCLKFS_SHIFT) & SDHCI_SYSCTL_SDCLKFS_MASK; + regval |= ((divisor >> 8) << SDHCI_SYSCTL_SDCLKFSUP_SHIFT) & SDHCI_SYSCTL_SDCLKFSUP_MASK; + putreg32(regval, CXD56_SDHCI_SYSCTL); +} + +static void cxd56_sdio_clock(FAR struct sdio_dev_s *dev, enum sdio_clock_e rate) +{ + uint32_t regval; + uint32_t frequency = 0; + uint32_t i; + + /* The SDCLK must be disabled before its frequency can be changed: "SDCLK + * frequency can be changed when this bit is 0. Then, the host controller + * shall maintain the same clock frequency until SDCLK is stopped (stop at + * SDCLK = 0). + */ + + regval = getreg32(CXD56_SDHCI_SYSCTL); + regval &= ~SDHCI_SYSCTL_SDCLKEN; + putreg32(regval, CXD56_SDHCI_SYSCTL); + mcinfo("SYSCTRL: %08x\n", getreg32(CXD56_SDHCI_SYSCTL)); + + /* sel_ttclk bit[16] */ + if (cxd56_get_sdio_baseclock() < 48*1000*1000) + { + putreg32(getreg32(CXD56_SDHCI_USERDEF2CTL) | (0x1 << 16), + CXD56_SDHCI_USERDEF2CTL); + } + else + { + putreg32(getreg32(CXD56_SDHCI_USERDEF2CTL) & ~(0x1 << 16), + CXD56_SDHCI_USERDEF2CTL); + } + + /* HS_SYNC_RISE bit[16] */ + putreg32(0x01010100, CXD56_SDHCI_OTHERIOLL); + + /* sdclk_dly_sel */ + if (rate <= CLOCK_SD_TRANSFER_4BIT) + putreg32((getreg32(CXD56_SDHCI_USERDEF2CTL) & ~(0x7))| 0x1, CXD56_SDHCI_USERDEF2CTL); + else + putreg32((getreg32(CXD56_SDHCI_USERDEF2CTL) & ~(0x7))| 0x0, CXD56_SDHCI_USERDEF2CTL); + + /* Select the new prescaler and divisor values based on the requested mode + * and the settings from the board.h file. + * + * TODO: Investigate using the automatically gated clocks to reduce power + * consumption. + */ + + switch (rate) + { + default: + case CLOCK_SDIO_DISABLED : /* Clock is disabled */ + { + /* Clear the prescaler and divisor settings and other clock + * enables as well. + */ + regval &= ~(SDHCI_SYSCTL_SDCLKFS_MASK | SDHCI_SYSCTL_SDCLKFSUP_MASK); + putreg32(regval, CXD56_SDHCI_SYSCTL); + cxd56_sdio_frequency(CONFIG_CXD56_IDMODE_FREQ); + mcinfo("SYSCTRL: %08x\n", getreg32(CXD56_SDHCI_SYSCTL)); + return; + } + + case CLOCK_IDMODE : /* Initial ID mode clocking (<400KHz) */ + frequency = CONFIG_CXD56_IDMODE_FREQ; + break; + + case CLOCK_MMC_TRANSFER : /* MMC normal operation clocking */ + frequency = CONFIG_CXD56_MMCXFR_FREQ; + break; + + case CLOCK_SD_TRANSFER_1BIT : /* SD normal operation clocking (narrow 1-bit mode) */ +#ifndef CONFIG_CXD56_SDIO_WIDTH_D1_ONLY + frequency = CONFIG_CXD56_SD1BIT_FREQ; + break; +#endif + + case CLOCK_SD_TRANSFER_4BIT : /* SD normal operation clocking (wide 4-bit mode) */ + frequency = CONFIG_CXD56_SD4BIT_FREQ; + break; + } + + cxd56_sdio_frequency(frequency); + + putreg32(getreg32(CXD56_SDHCI_SYSCTL) | SDHCI_SYSCTL_ICLKEN, CXD56_SDHCI_SYSCTL); + for (i=0;i<20;i++) + { + up_mdelay(50); + regval = getreg32(CXD56_SDHCI_SYSCTL); + if (regval & SDHCI_SYSCTL_ICLKSTA) + { + break; + } + } + do + { + putreg32(regval | SDHCI_SYSCTL_SDCLKEN, CXD56_SDHCI_SYSCTL); + } + while((getreg32(CXD56_SDHCI_SYSCTL) & SDHCI_SYSCTL_SDCLKEN) == 0); + mcinfo("SYSCTRL: %08x\n", getreg32(CXD56_SDHCI_SYSCTL)); +} + +/**************************************************************************** + * Name: cxd56_sdio_attach + * + * Description: + * Attach and prepare interrupts + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * + * Returned Value: + * OK on success; A negated errno on failure. + * + ****************************************************************************/ + +static int cxd56_sdio_attach(FAR struct sdio_dev_s *dev) +{ + int ret; + + /* Attach the SDIO interrupt handler */ + ret = irq_attach(CXD56_IRQ_SDIO, cxd56_interrupt, NULL); + if (ret == OK) + { + /* Disable all interrupts at the SDIO controller and clear all pending + * interrupts. + */ + + putreg32(0, CXD56_SDHCI_IRQSIGEN); + putreg32(SDHCI_INT_ALL, CXD56_SDHCI_IRQSTAT); + +#ifdef CONFIG_ARCH_IRQPRIO + /* Set the interrupt priority */ + + up_prioritize_irq(CXD56_IRQ_SDIO, CONFIG_CXD56_SDHCI_PRIO); +#endif + + /* Enable SDIO interrupts at the NVIC. They can now be enabled at + * the SDIO controller as needed. + */ + + up_enable_irq(CXD56_IRQ_SDIO); + } + + return ret; +} + +/**************************************************************************** + * Name: cxd56_sdio_sendcmd + * + * Description: + * Send the SDIO command + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * cmd - The command to send (32-bits, encoded) + * arg - 32-bit argument required with some commands + * + * Returned Value: + * None + * + ****************************************************************************/ + +static int cxd56_sdio_sendcmd(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t arg) +{ +#ifdef CONFIG_SDIO_DMA + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; +#endif + uint32_t regval; + uint32_t cmdidx; + int32_t timeout; + + /* Initialize the command index */ + + cmdidx = (cmd & MMCSD_CMDIDX_MASK) >> MMCSD_CMDIDX_SHIFT; + regval = cmdidx << SDHCI_XFERTYP_CMDINX_SHIFT; + + /* Does a data transfer accompany the command? */ + + if ((cmd & MMCSD_DATAXFR) != 0) + { + /* Yes.. Configure the data transfer */ + + switch (cmd & MMCSD_DATAXFR_MASK) + { + default: + case MMCSD_NODATAXFR : /* No.. no data transfer */ + break; + + /* The following two cases are probably missing some setup logic */ + + case MMCSD_RDSTREAM : /* Yes.. streaming read data transfer */ + regval |= (SDHCI_XFERTYP_DPSEL | SDHCI_XFERTYP_DTDSEL); + break; + + case MMCSD_WRSTREAM : /* Yes.. streaming write data transfer */ + regval |= SDHCI_XFERTYP_DPSEL; + break; + + case MMCSD_RDDATAXFR : /* Yes.. normal read data transfer */ + regval |= (SDHCI_XFERTYP_DPSEL | SDHCI_XFERTYP_DTDSEL); + break; + + case MMCSD_WRDATAXFR : /* Yes.. normal write data transfer */ + regval |= SDHCI_XFERTYP_DPSEL; + break; + } + + /* Is it a multi-block transfer? */ + + if ((cmd & MMCSD_MULTIBLOCK) != 0) + { + /* Yes.. should the transfer be stopped with ACMD12? */ + + if ((cmd & MMCSD_STOPXFR) != 0) + { + /* Yes.. Indefinite block transfer */ + + regval |= (SDHCI_XFERTYP_MSBSEL | SDHCI_XFERTYP_AC12EN); + } + else + { + /* No.. Fixed block transfer */ + + regval |= (SDHCI_XFERTYP_MSBSEL | SDHCI_XFERTYP_BCEN); + } + } + } + + /* Configure response type bits */ + + switch (cmd & MMCSD_RESPONSE_MASK) + { + case MMCSD_NO_RESPONSE: /* No response */ + regval |= SDHCI_XFERTYP_RSPTYP_NONE; + break; + + case MMCSD_R1B_RESPONSE: /* Response length 48, check busy & cmdindex */ + regval |= (SDHCI_XFERTYP_RSPTYP_LEN48BSY | SDHCI_XFERTYP_CICEN | + SDHCI_XFERTYP_CCCEN); + break; + + case MMCSD_R1_RESPONSE: /* Response length 48, check cmdindex */ + case MMCSD_R5_RESPONSE: + case MMCSD_R6_RESPONSE: + regval |= (SDHCI_XFERTYP_RSPTYP_LEN48 | SDHCI_XFERTYP_CICEN | + SDHCI_XFERTYP_CCCEN); + break; + + case MMCSD_R2_RESPONSE: /* Response length 136, check CRC */ + regval |= (SDHCI_XFERTYP_RSPTYP_LEN136 | SDHCI_XFERTYP_CCCEN); + break; + + case MMCSD_R3_RESPONSE: /* Response length 48 */ + case MMCSD_R4_RESPONSE: + case MMCSD_R7_RESPONSE: + regval |= SDHCI_XFERTYP_RSPTYP_LEN48; + break; + } + + /* Enable DMA */ + +#ifdef CONFIG_SDIO_DMA + /* Internal DMA is used */ + priv->dmasend_prepare = false; + priv->dmasend_cmd = 0; + priv->dmasend_regcmd = 0; + if (((cmd & MMCSD_DATAXFR_MASK) != MMCSD_NODATAXFR) && priv->usedma) + { + regval |= SDHCI_XFERTYP_DMAEN; + } + else if (cmdidx == MMCSD_CMDIDX24 || cmdidx == MMCSD_CMDIDX25) + { + regval |= SDHCI_XFERTYP_DMAEN; + priv->usedma = true; + priv->dmasend_prepare = true; + } +#endif + + /* Other bits? What about CMDTYP? */ + + mcinfo("cmd: %08x arg: %08x regval: %08x\n", cmd, arg, regval); + + /* The Command Inhibit (CIHB) bit is set in the PRSSTAT bit immediately + * after the transfer type register is written. This bit is cleared when + * the command response is received. If this status bit is 0, it + * indicates that the CMD line is not in use and the SDHC can issue a + * SD/MMC Command using the CMD line. + * + * CIHB should always be set when this function is called. + */ + + timeout = SDHCI_CMDTIMEOUT; + while ((getreg32(CXD56_SDHCI_PRSSTAT) & SDHCI_PRSSTAT_CIHB) != 0) + { + if (--timeout <= 0) + { + mcerr("ERROR: Timeout cmd: %08x PRSSTAT: %08x\n", + cmd, getreg32(CXD56_SDHCI_PRSSTAT)); + + return -EBUSY; + } + } + + if ((cmd & MMCSD_DATAXFR_MASK) != MMCSD_NODATAXFR) + { + timeout = SDHCI_CMDTIMEOUT; + while ((getreg32(CXD56_SDHCI_PRSSTAT) & SDHCI_PRSSTAT_CDIHB) != 0) + { + if (--timeout <= 0) + { + mcerr("ERROR: Timeout cmd data: %08x PRSSTAT: %08x\n", + cmd, getreg32(CXD56_SDHCI_PRSSTAT)); + + return -EBUSY; + } + } + } + + /* Set the SDHC Argument value */ + putreg32(arg, CXD56_SDHCI_CMDARG); + + /* Clear interrupt status and write the SDHC CMD */ + putreg32(SDHCI_RESPDONE_INTS, CXD56_SDHCI_IRQSTAT); +#ifdef CONFIG_SDIO_DMA + priv->dma_cmd = cmd; + if (priv->dmasend_prepare) + { + priv->dmasend_regcmd = regval; + priv->dmasend_cmd = cmd; + } + else +#endif + { + putreg32(regval, CXD56_SDHCI_XFERTYP); + } + + return OK; +} + +/**************************************************************************** + * Name: cxd56_blocksetup + * + * Description: + * Some hardward needs to be informed of the selected blocksize. + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * blocklen - The selected block size. + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void cxd56_blocksetup(FAR struct sdio_dev_s *dev, unsigned int blocklen, + unsigned int nblocks) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + uint32_t regval; + + DEBUGASSERT(dev != NULL && nblocks > 0 && nblocks < 65535); + DEBUGASSERT(blocklen < 65535); + + priv->blocksize = blocklen; + + /* Set the block size and count */ + + regval = (blocklen << SDHCI_BLKATTR_SIZE_SHIFT) | + (nblocks << SDHCI_BLKATTR_CNT_SHIFT); + putreg32(regval, CXD56_SDHCI_BLKATTR); +} + +/**************************************************************************** + * Name: cxd56_sdio_recvsetup + * + * Description: + * Setup hardware in preparation for data transfer from the card in non-DMA + * (interrupt driven mode). This method will do whatever controller setup + * is necessary. This would be called for SD memory just BEFORE sending + * CMD13 (SEND_STATUS), CMD17 (READ_SINGLE_BLOCK), CMD18 + * (READ_MULTIPLE_BLOCKS), ACMD51 (SEND_SCR), etc. Normally, SDIO_WAITEVENT + * will be called to receive the indication that the transfer is complete. + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * buffer - Address of the buffer in which to receive the data + * nbytes - The number of bytes in the transfer + * + * Returned Value: + * Number of bytes sent on success; a negated errno on failure + * + ****************************************************************************/ + +static int cxd56_sdio_recvsetup(FAR struct sdio_dev_s *dev, FAR uint8_t *buffer, + size_t nbytes) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + + DEBUGASSERT(priv != NULL && buffer != NULL && nbytes > 0); + DEBUGASSERT(((uint32_t)buffer & 3) == 0); + +#ifdef CONFIG_SDIO_DMA + priv->usedma = false; +#endif + + /* Reset the DPSM configuration */ + + cxd56_datadisable(); + cxd56_sampleinit(); + cxd56_sample(priv, SAMPLENDX_BEFORE_SETUP); + + /* Save the destination buffer information for use by the interrupt handler */ + + priv->buffer = (uint32_t *)buffer; + priv->remaining = nbytes; + + /* Then set up the SDIO data path */ + + cxd56_dataconfig(priv, false, nbytes, 1, SDHCI_DTOCV_DATATIMEOUT); + + /* And enable interrupts */ + + cxd56_configxfrints(priv, SDHCI_RCVDONE_INTS); + cxd56_sample(priv, SAMPLENDX_AFTER_SETUP); + return OK; +} + +/**************************************************************************** + * Name: cxd56_sdio_sendsetup + * + * Description: + * Setup hardware in preparation for data transfer from the card. This method + * will do whatever controller setup is necessary. This would be called + * for SD memory just AFTER sending CMD24 (WRITE_BLOCK), CMD25 + * (WRITE_MULTIPLE_BLOCK), ... and before SDIO_SENDDATA is called. + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * buffer - Address of the buffer containing the data to send + * nbytes - The number of bytes in the transfer + * + * Returned Value: + * Number of bytes sent on success; a negated errno on failure + * + ****************************************************************************/ + +static int cxd56_sdio_sendsetup(FAR struct sdio_dev_s *dev, FAR const uint8_t *buffer, + size_t nbytes) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + + DEBUGASSERT(priv != NULL && buffer != NULL && nbytes > 0); + DEBUGASSERT(((uint32_t)buffer & 3) == 0); + +#ifdef CONFIG_SDIO_DMA + priv->usedma = false; +#endif + + /* Reset the DPSM configuration */ + + cxd56_datadisable(); + cxd56_sampleinit(); + cxd56_sample(priv, SAMPLENDX_BEFORE_SETUP); + + /* Save the source buffer information for use by the interrupt handler */ + + priv->buffer = (uint32_t *)buffer; + priv->remaining = nbytes; + + /* Then set up the SDIO data path */ + + cxd56_dataconfig(priv, true, nbytes, 1, SDHCI_DTOCV_DATATIMEOUT); + + /* Enable TX interrupts */ + + cxd56_configxfrints(priv, SDHCI_SNDDONE_INTS); + cxd56_sample(priv, SAMPLENDX_AFTER_SETUP); + return OK; +} + +/**************************************************************************** + * Name: cxd56_sdio_cancel + * + * Description: + * Cancel the data transfer setup of SDIO_RECVSETUP, SDIO_SENDSETUP, + * SDIO_DMARECVSETUP or SDIO_DMASENDSETUP. This must be called to cancel + * the data transfer setup if, for some reason, you cannot perform the + * transfer. + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * + * Returned Value: + * OK is success; a negated errno on failure + * + ****************************************************************************/ + +static int cxd56_sdio_cancel(FAR struct sdio_dev_s *dev) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + uint32_t regval; + +#ifdef CONFIG_SDIO_DMA + /* Release allocated buffer */ + if (priv->aligned_buffer) + { + /* Free aligned buffer */ + + kmm_free(priv->aligned_buffer); + + priv->aligned_buffer = NULL; + } +#endif + + /* Disable all transfer- and event- related interrupts */ + + cxd56_configxfrints(priv, 0); + cxd56_configwaitints(priv, 0, 0, 0); + + /* Clearing pending interrupt status on all transfer- and event- related + * interrupts + */ + + putreg32(SDHCI_WAITALL_INTS, CXD56_SDHCI_IRQSTAT); + + /* Cancel any watchdog timeout */ + + (void)wd_cancel(priv->waitwdog); + + /* If this was a DMA transfer, make sure that DMA is stopped */ + +#ifdef CONFIG_SDIO_DMA + /* Stop the DMA by resetting the data path */ + + regval = getreg32(CXD56_SDHCI_SYSCTL); + regval |= SDHCI_SYSCTL_RSTD; + putreg32(regval, CXD56_SDHCI_SYSCTL); + priv->usedma = false; + priv->dmasend_prepare = false; + priv->dmasend_cmd = 0; + priv->dmasend_regcmd = 0; + cxd56_sdhci_adma_dscr[0] = 0; + cxd56_sdhci_adma_dscr[1] = 0; + putreg32((uint32_t)cxd56_sdhci_adma_dscr, CXD56_SDHCI_ADSADDR); + putreg32(0, CXD56_SDHCI_ADSADDR_H); +#endif + regval = getreg32(CXD56_SDHCI_SYSCTL); + regval |= SDHCI_SYSCTL_RSTC; + putreg32(regval, CXD56_SDHCI_SYSCTL); + regval = getreg32(CXD56_SDHCI_SYSCTL); + regval |= SDHCI_SYSCTL_RSTD; + putreg32(regval, CXD56_SDHCI_SYSCTL); + + while ((getreg32(CXD56_SDHCI_SYSCTL) & SDHCI_SYSCTL_RSTC) != 0); + while ((getreg32(CXD56_SDHCI_SYSCTL) & SDHCI_SYSCTL_RSTD) != 0); + + /* Mark no transfer in progress */ + priv->remaining = 0; + + return OK; +} + +/**************************************************************************** + * Name: cxd56_sdio_waitresponse + * + * Description: + * Poll-wait for the response to the last command to be ready. This + * function should be called even after sending commands that have no + * response (such as CMD0) to make sure that the hardware is ready to + * receive the next command. + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * cmd - The command that was sent. See 32-bit command definitions above. + * + * Returned Value: + * OK is success; a negated errno on failure + * + ****************************************************************************/ + +static int cxd56_sdio_waitresponse(FAR struct sdio_dev_s *dev, uint32_t cmd) +{ + uint32_t errors; + int32_t timeout = SDHCI_CMDTIMEOUT; + int ret = OK; + +#ifdef CONFIG_SDIO_DMA + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + + if (priv->dmasend_prepare) + { + return OK; + } +#endif + + switch (cmd & MMCSD_RESPONSE_MASK) + { + case MMCSD_NO_RESPONSE: + timeout = SDHCI_CMDTIMEOUT; + errors = 0; + return OK; + + case MMCSD_R1_RESPONSE: + case MMCSD_R1B_RESPONSE: + case MMCSD_R2_RESPONSE: + case MMCSD_R6_RESPONSE: + timeout = SDHCI_LONGTIMEOUT; + errors = SDHCI_RESPERR_INTS; + break; + + case MMCSD_R4_RESPONSE: + case MMCSD_R5_RESPONSE: + case MMCSD_R3_RESPONSE: + case MMCSD_R7_RESPONSE: + timeout = SDHCI_CMDTIMEOUT; + errors = SDHCI_RESPERR_INTS; + break; + + default: + return -EINVAL; + } + + /* Then wait for the Command Complete (CC) indication (or timeout). The + * CC bit is set when the end bit of the command response is received + * (except Auto CMD12). + */ + + while ((getreg32(CXD56_SDHCI_IRQSTAT) & SDHCI_INT_CC) == 0) + { + timeout -= 1; + if (timeout <= 0) + { + mcerr("ERROR: Timeout cmd: %08x IRQSTAT: %08x\n", + cmd, getreg32(CXD56_SDHCI_IRQSTAT)); + putreg32(0,CXD56_SDHCI_IRQSIGEN); + + return -ETIMEDOUT; + } + } + + /* Check for hardware detected errors */ + + if ((getreg32(CXD56_SDHCI_IRQSTAT) & errors) != 0) + { + mcerr("ERROR: cmd: %08x errors: %08x IRQSTAT: %08x\n", + cmd, errors, getreg32(CXD56_SDHCI_IRQSTAT)); + ret = -EIO; + } + + /* Clear the response wait status bits */ + if ((cmd & MMCSD_DATAXFR_MASK) == MMCSD_NODATAXFR) + { + putreg32((SDHCI_INT_TC & getreg32(CXD56_SDHCI_IRQSTAT))| SDHCI_RESPDONE_INTS, + CXD56_SDHCI_IRQSTAT); + } + else + { + putreg32(SDHCI_RESPDONE_INTS, CXD56_SDHCI_IRQSTAT); + } + + return ret; +} + +/**************************************************************************** + * Name: cxd56_sdio_recvRx + * + * Description: + * Receive response to SDIO command. Only the critical payload is + * returned -- that is 32 bits for 48 bit status and 128 bits for 136 bit + * status. The driver implementation should verify the correctness of + * the remaining, non-returned bits (CRCs, CMD index, etc.). + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * Rx - Buffer in which to receive the response + * + * Returned Value: + * Number of bytes sent on success; a negated errno on failure. Here a + * failure means only a faiure to obtain the requested reponse (due to + * transport problem -- timeout, CRC, etc.). The implementation only + * assures that the response is returned intacta and does not check errors + * within the response itself. + * + ****************************************************************************/ + +static int cxd56_sdio_recvshortcrc(FAR struct sdio_dev_s *dev, uint32_t cmd, + uint32_t *rshort) +{ + uint32_t regval; + int ret = OK; +#ifdef CONFIG_SDIO_DMA + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; +#endif + + /* R1 Command response (48-bit) + * 47 0 Start bit + * 46 0 Transmission bit (0=from card) + * 45:40 bit5 - bit0 Command index (0-63) + * 39:8 bit31 - bit0 32-bit card status + * 7:1 bit6 - bit0 CRC7 + * 0 1 End bit + * + * R1b Identical to R1 with the additional busy signalling via the data + * line. + * + * R6 Published RCA Response (48-bit, SD card only) + * 47 0 Start bit + * 46 0 Transmission bit (0=from card) + * 45:40 bit5 - bit0 Command index (0-63) + * 39:8 bit31 - bit0 32-bit Argument Field, consisting of: + * [31:16] New published RCA of card + * [15:0] Card status bits {23,22,19,12:0} + * 7:1 bit6 - bit0 CRC7 + * 0 1 End bit + */ + + if (rshort) + { + *rshort = 0; + } + +#ifdef CONFIG_SDIO_DMA + if (priv->dmasend_prepare) + { + return OK; + } +#endif +#ifdef CONFIG_DEBUG_FEATURES + if (!rshort) + { + mcerr("ERROR: rshort=NULL\n"); + ret = -EINVAL; + } + + /* Check that this is the correct response to this command */ + + else if ((cmd & MMCSD_RESPONSE_MASK) != MMCSD_R1_RESPONSE && + (cmd & MMCSD_RESPONSE_MASK) != MMCSD_R1B_RESPONSE && + (cmd & MMCSD_RESPONSE_MASK) != MMCSD_R6_RESPONSE) + { + mcerr("ERROR: Wrong response CMD=%08x\n", cmd); + ret = -EINVAL; + } + else +#endif + { + /* Check if a timeout or CRC error occurred */ + + regval = getreg32(CXD56_SDHCI_IRQSTAT); + if ((regval & SDHCI_INT_CTOE) != 0) + { + mcerr("ERROR: Command timeout: %08x\n", regval); + ret = -ETIMEDOUT; + } + else if ((regval & SDHCI_INT_CCE) != 0) + { + mcerr("ERROR: CRC failure: %08x\n", regval); + ret = -EIO; + } + } + + /* Return the R1/R1b/R6 response. These responses are returned in + * CDMRSP0. NOTE: This is not true for R1b (Auto CMD12 response) which + * is returned in CMDRSP3. + */ + + *rshort = getreg32(CXD56_SDHCI_CMDRSP0); + + return ret; +} + +static int cxd56_sdio_recvlong(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t rlong[4]) +{ + uint32_t regval; + int ret = OK; + + /* R2 CID, CSD register (136-bit) + * 135 0 Start bit + * 134 0 Transmission bit (0=from card) + * 133:128 bit5 - bit0 Reserved + * 127:1 bit127 - bit1 127-bit CID or CSD register + * (including internal CRC) + * 0 1 End bit + */ + + if (rlong) + { + rlong[0] = 0; + rlong[1] = 0; + rlong[2] = 0; + rlong[3] = 0; + } +#ifdef CONFIG_DEBUG_FEATURES + /* Check that R1 is the correct response to this command */ + + if ((cmd & MMCSD_RESPONSE_MASK) != MMCSD_R2_RESPONSE) + { + mcerr("ERROR: Wrong response CMD=%08x\n", cmd); + ret = -EINVAL; + } + else +#endif + { + /* Check if a timeout or CRC error occurred */ + + regval = getreg32(CXD56_SDHCI_IRQSTAT); + if (regval & SDHCI_INT_CTOE) + { + mcerr("ERROR: Timeout IRQSTAT: %08x\n", regval); + ret = -ETIMEDOUT; + } + else if (regval & SDHCI_INT_CCE) + { + mcerr("ERROR: CRC fail IRQSTAT: %08x\n", regval); + ret = -EIO; + } + } + + /* Return the long response in CMDRSP3..0 */ + + if (rlong) + { + rlong[0] = getreg32(CXD56_SDHCI_CMDRSP3); + rlong[1] = getreg32(CXD56_SDHCI_CMDRSP2); + rlong[2] = getreg32(CXD56_SDHCI_CMDRSP1); + rlong[3] = getreg32(CXD56_SDHCI_CMDRSP0); + } + if (1) + { + rlong[0] = ((rlong[0] << 8) & 0xffffff00) | ((rlong[1] >> 24) & 0x000000FF); + rlong[1] = ((rlong[1] << 8) & 0xffffff00) | ((rlong[2] >> 24) & 0x000000FF); + rlong[2] = ((rlong[2] << 8) & 0xffffff00) | ((rlong[3] >> 24) & 0x000000FF); + rlong[3] = (rlong[3] << 8) & 0xffffff00; + } + return ret; +} + +static int cxd56_sdio_recvshort(FAR struct sdio_dev_s *dev, uint32_t cmd, uint32_t *rshort) +{ + uint32_t regval; + int ret = OK; + + /* R3 OCR (48-bit) + * 47 0 Start bit + * 46 0 Transmission bit (0=from card) + * 45:40 bit5 - bit0 Reserved + * 39:8 bit31 - bit0 32-bit OCR register + * 7:1 bit6 - bit0 Reserved + * 0 1 End bit + */ + + /* R4 Response (48-bit) + * 47 0 Start bit + * 46 0 Direction bit(0=card to host) + * 45:40 bit5 - bit0 Reserved + * 39 1 Set to 1 if Card is ready to operate after initialization + * 38:36 bit2 - bit0 Number of I/O functions + * 35 1 Memory Present + * 34:32 bit2 - bit0 Stuff Bits + * 31:8 bit23 - bit0 I/O OCR + * 7:1 bit6 - bit0 Reserved + * 0 1 End bit + */ + + /* R5 Response (48-bit) + * 47 0 Start bit + * 46 0 Direction bit(0=card to host) + * 45:40 bit5 - bit0 Command Index + * 39:24 bit15 - bit0 16-bit Stuff Bits + * 23:16 bit7 - bit0 Response Flags + * 15:8 bit7 - bit0 Read or Write Data + * 7:1 bit6 - bit0 CRC + * 0 1 End bit + */ + + if (!rshort) + { + *rshort = 0; + } + /* Check that this is the correct response to this command */ +#ifdef CONFIG_DEBUG_FEATURES + if ((cmd & MMCSD_RESPONSE_MASK) != MMCSD_R3_RESPONSE && + (cmd & MMCSD_RESPONSE_MASK) != MMCSD_R4_RESPONSE && + (cmd & MMCSD_RESPONSE_MASK) != MMCSD_R5_RESPONSE && + (cmd & MMCSD_RESPONSE_MASK) != MMCSD_R7_RESPONSE) + { + mcerr("ERROR: Wrong response CMD=%08x\n", cmd); + ret = -EINVAL; + } + else +#endif + { + /* Check if a timeout occurred (Apparently a CRC error can terminate + * a good response) + */ + + regval = getreg32(CXD56_SDHCI_IRQSTAT); + if (regval & SDHCI_INT_CTOE) + { + mcerr("ERROR: Timeout IRQSTAT: %08x\n", regval); + ret = -ETIMEDOUT; + } + } + + /* Return the short response in CMDRSP0 */ + + if (rshort) + { + *rshort = getreg32(CXD56_SDHCI_CMDRSP0); + } + + return ret; +} + +/**************************************************************************** + * Name: cxd56_sdio_waitenable + * + * Description: + * Enable/disable of a set of SDIO wait events. This is part of the + * the SDIO_WAITEVENT sequence. The set of to-be-waited-for events is + * configured before calling cxd56_eventwait. This is done in this way + * to help the driver to eliminate race conditions between the command + * setup and the subsequent events. + * + * The enabled events persist until either (1) SDIO_WAITENABLE is called + * again specifying a different set of wait events, or (2) SDIO_EVENTWAIT + * returns. + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * eventset - A bitset of events to enable or disable (see SDIOWAIT_* + * definitions). 0=disable; 1=enable. + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void cxd56_sdio_waitenable(FAR struct sdio_dev_s *dev, + sdio_eventset_t eventset) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + uint32_t waitints; + + DEBUGASSERT(priv != NULL); + + /* Disable event-related interrupts */ + + cxd56_configwaitints(priv, 0, 0, 0); + + /* Select the interrupt mask that will give us the appropriate wakeup + * interrupts. + */ + + waitints = 0; + if ((eventset & (SDIOWAIT_CMDDONE | SDIOWAIT_RESPONSEDONE)) != 0) + { + waitints |= SDHCI_RESPDONE_INTS; + } + + if ((eventset & SDIOWAIT_TRANSFERDONE) != 0) + { + waitints |= SDHCI_XFRDONE_INTS; + } + + /* Enable event-related interrupts */ + + cxd56_configwaitints(priv, waitints, eventset, 0); +} + +/**************************************************************************** + * Name: cxd56_sdio_eventwait + * + * Description: + * Wait for one of the enabled events to occur (or a timeout). Note that + * all events enabled by SDIO_WAITEVENTS are disabled when cxd56_eventwait + * returns. SDIO_WAITEVENTS must be called again before cxd56_eventwait + * can be used again. + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * timeout - Maximum time in milliseconds to wait. Zero means immediate + * timeout with no wait. The timeout value is ignored if + * SDIOWAIT_TIMEOUT is not included in the waited-for eventset. + * + * Returned Value: + * Event set containing the event(s) that ended the wait. Should always + * be non-zero. All events are disabled after the wait concludes. + * + ****************************************************************************/ + +static sdio_eventset_t cxd56_sdio_eventwait(FAR struct sdio_dev_s *dev, + uint32_t timeout) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + sdio_eventset_t wkupevent = 0; + int ret; + + /* There is a race condition here... the event may have completed before + * we get here. In this case waitevents will be zero, but wkupevents will + * be non-zero (and, hopefully, the semaphore count will also be non-zero. + */ + + DEBUGASSERT((priv->waitevents != 0 && priv->wkupevent == 0) || + (priv->waitevents == 0 && priv->wkupevent != 0)); + + /* Check if the timeout event is specified in the event set */ + + if ((priv->waitevents & SDIOWAIT_TIMEOUT) != 0) + { + int delay; + + /* Yes.. Handle a corner case */ + + if (!timeout) + { + return SDIOWAIT_TIMEOUT; + } + + /* Start the watchdog timer */ + + delay = MSEC2TICK(timeout); + ret = wd_start(priv->waitwdog, delay, (wdentry_t)cxd56_eventtimeout, + 1, (uint32_t)priv); + if (ret != OK) + { + mcerr("ERROR: wd_start failed: %d\n", ret); + } + } + + /* Loop until the event (or the timeout occurs). Race conditions are avoided + * by calling cxd56_waitenable prior to triggering the logic that will cause + * the wait to terminate. Under certain race conditions, the waited-for + * may have already occurred before this function was called! + */ + + for (; ; ) + { + /* Wait for an event in event set to occur. If this the event has already + * occurred, then the semaphore will already have been incremented and + * there will be no wait. + */ + + cxd56_takesem(priv); + wkupevent = priv->wkupevent; + + /* Check if the event has occurred. When the event has occurred, then + * evenset will be set to 0 and wkupevent will be set to a non-zero value. + */ + + if (wkupevent != 0) + { + /* Yes... break out of the loop with wkupevent non-zero */ + if (wkupevent & ( SDIOWAIT_RESPONSEDONE | SDIOWAIT_TRANSFERDONE)) + { + if (priv->remaining > 0) + { + priv->remaining = 0; + } + } + if (wkupevent & (SDIOWAIT_TIMEOUT | SDIOWAIT_ERROR)) + { + cxd56_sdio_cancel(&(priv->dev)); + } + break; + } + } + + + /* Disable event-related interrupts */ + + cxd56_configwaitints(priv, 0, 0, 0); +#ifdef CONFIG_SDIO_DMA + priv->xfrflags = 0; + if (priv->aligned_buffer) + { + if (priv->dma_cmd == MMCSD_CMD17 || priv->dma_cmd == MMCSD_CMD18) + { + /* Copy receive buffer from aligned address */ + + memcpy(priv->receive_buffer, priv->aligned_buffer, priv->receive_size); + } + + /* Free aligned buffer */ + + kmm_free(priv->aligned_buffer); + + priv->aligned_buffer = NULL; + } +#endif + + cxd56_dumpsamples(priv); + return wkupevent; +} + +/**************************************************************************** + * Name: cxd56_sdio_callbackenable + * + * Description: + * Enable/disable of a set of SDIO callback events. This is part of the + * the SDIO callback sequence. The set of events is configured to enabled + * callbacks to the function provided in cxd56_registercallback. + * + * Events are automatically disabled once the callback is performed and no + * further callback events will occur until they are again enabled by + * calling this method. + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * eventset - A bitset of events to enable or disable (see SDIOMEDIA_* + * definitions). 0=disable; 1=enable. + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void cxd56_sdio_callbackenable(FAR struct sdio_dev_s *dev, + sdio_eventset_t eventset) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + + mcinfo("eventset: %02x\n", eventset); + DEBUGASSERT(priv != NULL); + + priv->cbevents = eventset; + cxd56_sdio_callback(priv); +} + +/**************************************************************************** + * Name: cxd56_sdio_registercallback + * + * Description: + * Register a callback that that will be invoked on any media status + * change. Callbacks should not be made from interrupt handlers, rather + * interrupt level events should be handled by calling back on the work + * thread. + * + * When this method is called, all callbacks should be disabled until they + * are enabled via a call to SDIO_CALLBACKENABLE + * + * Input Parameters: + * dev - Device-specific state data + * callback - The function 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. + * + ****************************************************************************/ + +static int cxd56_sdio_registercallback(FAR struct sdio_dev_s *dev, + worker_t callback, void *arg) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + + /* Disable callbacks and register this callback and is argument */ + + mcinfo("Register %p(%p)\n", callback, arg); + DEBUGASSERT(priv != NULL); + + priv->cbevents = 0; + priv->cbarg = arg; + priv->callback = callback; + return OK; +} + +/**************************************************************************** + * Name: cxd56_sdio_admasetup + * + * Description: + * Setup to perform ADMA. If the processor supports a data cache, + * then this method will also make sure that the contents of the DMA memory + * and the data cache are coherent. + * + * Input Parameters: + * buffer - The memory to/from DMA + * buflen - The size of the DMA transfer in bytes + * + * Returned Value: + * OK on success; a negated errno on failure + * + ****************************************************************************/ + +#ifdef CONFIG_SDIO_DMA +static int cxd56_sdio_admasetup(FAR const uint8_t *buffer, size_t buflen) +{ + uint32_t dscr_top = (uint32_t)cxd56_sdhci_adma_dscr; + uint32_t dscr_l; + uint32_t i, remaining, len; + uint32_t data_addr = (uint32_t)buffer; + remaining = buflen; + + putreg32(0x0, CXD56_SDHCI_ADSADDR_H); + putreg32(dscr_top, CXD56_SDHCI_ADSADDR); + for (i=0;i 0) + { + return -EIO; + } + else + { + return OK; + } +} +#endif + +/**************************************************************************** + * Name: cxd56_sdio_dmarecvsetup + * + * Description: + * Setup to perform a read DMA. If the processor supports a data cache, + * then this method will also make sure that the contents of the DMA memory + * and the data cache are coherent. For read transfers this may mean + * invalidating the data cache. + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * buffer - The memory to DMA from + * buflen - The size of the DMA transfer in bytes + * + * Returned Value: + * OK on success; a negated errno on failure + * + ****************************************************************************/ + +#ifdef CONFIG_SDIO_DMA +static int cxd56_sdio_dmarecvsetup(FAR struct sdio_dev_s *dev, FAR uint8_t *buffer, + size_t buflen) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + unsigned int blocksize; + int ret = OK; + + DEBUGASSERT(priv != NULL && buffer != NULL && buflen > 0); + DEBUGASSERT(((uint32_t)buffer & 3) == 0); + + if ((uint32_t)buffer & 3) + { + if (priv->aligned_buffer) + { + /* If buffer not freed, free it */ + + kmm_free(priv->aligned_buffer); + + priv->aligned_buffer = NULL; + } + + /* Allocate aligned buffer */ + + priv->aligned_buffer = (uint8_t *) kmm_malloc(sizeof(uint8_t) * buflen); + + /* Keep receive buffer address */ + + priv->receive_buffer = buffer; + + /* Keep receive data size */ + + priv->receive_size = buflen; + + /* Switch to aligned buffer */ + + buffer = priv->aligned_buffer; + } + + /* Reset the DPSM configuration */ + + cxd56_datadisable(); + + /* Begin sampling register values */ + + cxd56_sampleinit(); + cxd56_sample(priv, SAMPLENDX_BEFORE_SETUP); + + /* Save the destination buffer information for use by the interrupt handler */ + + priv->buffer = (uint32_t *)buffer; + priv->remaining = buflen; + + /* Then set up the SDIO data path */ + + blocksize = getreg32(CXD56_SDHCI_BLKATTR) & SDHCI_BLKATTR_SIZE_MASK; + if (blocksize == 0) + { + if (priv->blocksize != 0) + { + blocksize = priv->blocksize; + } + else + { + ret = -EIO; + goto error; + } + } + cxd56_dataconfig(priv, false, blocksize, buflen / blocksize, SDHCI_DTOCV_DATATIMEOUT); + + /* Configure the RX DMA */ + + cxd56_sdio_admasetup(buffer, buflen); + priv->usedma = true; + + cxd56_configxfrints(priv, SDHCI_DMADONE_INTS); + putreg32((uint32_t)buffer, CXD56_SDHCI_DSADDR); + + /* Sample the register state */ + + cxd56_sample(priv, SAMPLENDX_AFTER_SETUP); + return OK; +error: + /* Free allocated align buffer */ + + kmm_free(priv->aligned_buffer); + + priv->aligned_buffer = NULL; + return ret; +} +#endif + +/**************************************************************************** + * Name: cxd56_sdio_dmasendsetup + * + * Description: + * Setup to perform a write DMA. If the processor supports a data cache, + * then this method will also make sure that the contents of the DMA memory + * and the data cache are coherent. For write transfers, this may mean + * flushing the data cache. + * + * Input Parameters: + * dev - An instance of the SDIO device interface + * buffer - The memory to DMA into + * buflen - The size of the DMA transfer in bytes + * + * Returned Value: + * OK on success; a negated errno on failure + * + ****************************************************************************/ + +#ifdef CONFIG_SDIO_DMA +static int cxd56_sdio_dmasendsetup(FAR struct sdio_dev_s *dev, + FAR const uint8_t *buffer, size_t buflen) +{ + uint32_t r1; + int ret = OK; + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + unsigned int blocksize; + + DEBUGASSERT(priv != NULL && buffer != NULL && buflen > 0); + DEBUGASSERT(((uint32_t)buffer & 3) == 0); + + if ((uint32_t)buffer & 3) + { + if (priv->aligned_buffer) + { + /* If buffer not freed, free it */ + + kmm_free(priv->aligned_buffer); + + priv->aligned_buffer = NULL; + } + + /* Allocate aligned buffer */ + + priv->aligned_buffer = (uint8_t *) kmm_malloc(sizeof(uint8_t) * buflen); + + /* Copy buffer to aligned address */ + + memcpy(priv->aligned_buffer, buffer, buflen); + + /* Switch to aligned buffer */ + + buffer = priv->aligned_buffer; + } + + /* Reset the DPSM configuration */ + + cxd56_datadisable(); + + /* Begin sampling register values */ + + cxd56_sampleinit(); + cxd56_sample(priv, SAMPLENDX_BEFORE_SETUP); + + /* Save the source buffer information for use by the interrupt handler */ + + priv->buffer = (uint32_t *)buffer; + priv->remaining = buflen; + + /* Then set up the SDIO data path */ + + blocksize = getreg32(CXD56_SDHCI_BLKATTR) & SDHCI_BLKATTR_SIZE_MASK; + if (blocksize == 0) + { + if (priv->blocksize != 0) + { + blocksize = priv->blocksize; + } + else + { + ret = -EIO; + goto error; + } + } + cxd56_dataconfig(priv, true, blocksize, buflen / blocksize, SDHCI_DTOCV_DATATIMEOUT); + + /* Configure the TX DMA */ + + cxd56_sdio_admasetup(buffer, buflen); + priv->usedma = true; + if (priv->dmasend_prepare) + { + putreg32(priv->dmasend_regcmd, CXD56_SDHCI_XFERTYP); + priv->dmasend_prepare = false; + cxd56_sdio_waitresponse(dev, priv->dmasend_cmd); + ret = cxd56_sdio_recvshortcrc(dev, priv->dmasend_cmd, &r1); + if (ret != OK) + { + goto error; + } + } + + /* Sample the register state */ + + cxd56_sample(priv, SAMPLENDX_AFTER_SETUP); + + /* Enable TX interrupts */ + + cxd56_configxfrints(priv, SDHCI_DMADONE_INTS); + + return OK; +error: + /* Free allocated align buffer */ + + kmm_free(priv->aligned_buffer); + + priv->aligned_buffer = NULL; + return ret; +} +#endif + +/**************************************************************************** + * Initialization/uninitialization/reset + ****************************************************************************/ +static inline void cxd56_sdio_poweron(void *arg) +{ + uint32_t regval; + + /* Power ON for SDCARD */ + + regval = getreg32(CXD56_SDHCI_PROCTL); + regval |= 0xf << 8; + putreg32(regval, CXD56_SDHCI_PROCTL); + + board_sdcard_pin_enable(); +} + +static inline void cxd56_sdio_poweroff(void *arg) +{ + uint32_t regval; + + board_sdcard_pin_disable(); + + /* Power OFF for SDCARD */ + + regval = getreg32(CXD56_SDHCI_PROCTL); + regval &= ~(0x1 << 8); + putreg32(regval, CXD56_SDHCI_PROCTL); +} + +/**************************************************************************** + * Name: cxd56_sdio_callback + * + * Description: + * Perform callback. + * + * Assumptions: + * This function does not execute in the context of an interrupt handler. + * It may be invoked on any user thread or scheduled on the work thread + * from an interrupt handler. + * + ****************************************************************************/ + +static void cxd56_sdio_callback(void *arg) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)arg; + uint32_t delay = 0; + irqstate_t flags; + + /* Is a callback registered? */ + + DEBUGASSERT(priv != NULL); + mcinfo("Callback %p(%p) cbevents: %02x cdstatus: %02x\n", + priv->callback, priv->cbarg, priv->cbevents, priv->cdstatus); + + flags = enter_critical_section(); + if (priv->callback) + { + /* Yes.. Check for enabled callback events */ + + if ((priv->cdstatus & SDIO_STATUS_PRESENT) != 0) + { + /* Media is present. Is the media inserted event enabled? */ + + if ((priv->cbevents & SDIOMEDIA_INSERTED) == 0) + { + /* No... return without performing the callback */ + + leave_critical_section(flags); + return; + } + /* Power ON for SDCARD */ + cxd56_sdio_poweron(priv); + putreg32(SDHCI_INT_CINS, CXD56_SDHCI_IRQSTAT); + delay = SDHCI_WAIT_POWERON; + } + else + { + /* Media is not present. Is the media eject event enabled? */ + + if ((priv->cbevents & SDIOMEDIA_EJECTED) == 0) + { + /* No... return without performing the callback */ + + leave_critical_section(flags); + return; + } + /* Power OFF for SDCARD */ + cxd56_sdio_poweroff(arg); + putreg32(SDHCI_INT_CRM | SDHCI_INT_CINT, CXD56_SDHCI_IRQSTAT); + delay = SDHCI_WAIT_POWEROFF; + } + + /* Perform the callback, disabling further callbacks. Of course, the + * the callback can (and probably should) re-enable callbacks. + */ + + priv->cbevents = 0; + leave_critical_section(flags); + + /* Callbacks cannot be performed in the context of an interrupt handler. + * If we are in an interrupt handler, then queue the callback to be + * performed later on the work thread. + */ + + if (up_interrupt_context())/* (1) */ + { + /* Yes.. queue it */ + work_cancel(HPWORK, &priv->cbwork);// + mcinfo("Queuing callback to %p(%p)\n", priv->callback, priv->cbarg); + (void)work_queue(HPWORK, &priv->cbwork, (worker_t)priv->callback, priv->cbarg, delay); + } + else + { + /* No.. then just call the callback here */ + + up_mdelay(delay); + mcinfo("Callback to %p(%p)\n", priv->callback, priv->cbarg); + priv->callback(priv->cbarg); + } + } +} + +#ifdef CONFIG_CXD56_SDIO_ENABLE_MULTIFUNCTION +static void cxd56_sdio_takesem(FAR struct cxd56_sdiodev_s *priv) +{ + /* Take the semaphore, giving exclusive access to the driver (perhaps + * waiting) + */ + + while (sem_wait(&priv->sc.sem) != 0) + { + /* The only case that an error should occur here is if the wait was + * awakened by a signal. + */ + + ASSERT(errno == EINTR); + } +} + +/**************************************************************************** + * Name: cxd56_sdio_make_cmd52arg + * + * Description: + * Create argument parameters for CMD52 + * + ****************************************************************************/ + +static uint32_t cxd56_sdio_make_cmd52arg(uint32_t addr, uint8_t val_w, FAR uint8_t * out, + int32_t write, uint32_t func_num) +{ + uint32_t arg = 0; + + arg = write ? SDIO_CMD5253_WRITE : SDIO_CMD5253_READ; + arg |= func_num << SDIO_CMD5253_FUNC_SHIFT; + arg |= (write && out) ? 0x08000000 : 0x00000000; + arg |= addr << SDIO_CMD52_REG_SHIFT; + if (write) + { + arg |= (val_w & SDIO_CMD52_DATA_MASK) << 0; + } + + return arg; +} + +/**************************************************************************** + * Name: cxd56_sdio_make_cmd53arg + * + * Description: + * Create argument parameters for CMD53 + * + ****************************************************************************/ + +static uint32_t cxd56_sdio_make_cmd53arg(int32_t write, uint32_t func_num, + uint32_t addr, int32_t incr_addr, + uint32_t blocks, uint32_t bytesz) +{ + uint32_t arg = 0; + + arg = write ? SDIO_CMD5253_WRITE : SDIO_CMD5253_READ; + arg |= func_num << SDIO_CMD5253_FUNC_SHIFT; + arg |= incr_addr ? 0x04000000 : 0x00000000; + arg |= addr << SDIO_CMD52_REG_SHIFT; + if (blocks == 0) + { + arg |= (bytesz == 512) ? 0 : bytesz; /* byte mode */ + } + else + { + arg |= 0x08000000 | blocks; /* block mode */ + } + + return arg; +} + +/**************************************************************************** + * Name: cxd56_sdio_sendcmdpoll + * + * Description: + * Send a command and poll-wait for the response. + * + ****************************************************************************/ + +static int cxd56_sdio_sendcmdpoll(FAR struct cxd56_sdiodev_s *priv, uint32_t cmd, + uint32_t arg) +{ + int ret; + + /* Send the command */ + + ret = cxd56_sdio_sendcmd(&priv->dev, cmd, arg); + if (ret == OK) + { + /* Then poll-wait until the response is available */ + + ret = cxd56_sdio_waitresponse(&priv->dev, cmd); + if (ret != OK) + { + mcerr("ERROR: Wait for response to cmd: %08x failed: %d\n", cmd, ret); + } + } + + return ret; +} + +/**************************************************************************** + * Name: cxd56_sdio_readb_internal + * + * Description: + * Read a byte of data. + * + ****************************************************************************/ + +static uint32_t cxd56_sdio_readb_internal(FAR struct sdio_function_s * sf, uint32_t addr, + FAR uint8_t * rdata) +{ + uint32_t response; + uint32_t cmd52arg; + struct cxd56_sdiodev_s *priv = &g_sdhcdev; + int ret; + + DEBUGASSERT((NULL != rdata) && (NULL != sf)); + + cmd52arg = cxd56_sdio_make_cmd52arg(addr, 0, NULL, 0, sf->number); + ret = cxd56_sdio_sendcmdpoll(priv, SDIO_ACMD52, cmd52arg /* SDIO_ADD16_RD_CMD52 */ ); + if (ret == OK) + { + cxd56_sdio_recvshort(&priv->dev, SDIO_ACMD52, &response); + if (ret != OK) + { + mcerr("ERROR: Addr:0x%x, recv R5 error\n", addr); + goto READB_ERR; + } + } + else + { + mcerr("ERROR: Send cmd52 addr:0x%x error\n", addr); + goto READB_ERR; + } + if ((!CMD52_RESP_OK(response)) || (response == 0xffffffff)) + { + mcerr("ERROR: Fail resp %u\n", response); + goto READB_ERR; + } + if (rdata) + { + *rdata = response & 0xff; + } + + return 0; + +READB_ERR: + return ret; +} + +/**************************************************************************** + * Name: cxd56_sdio_writeb_internal + * + * Description: + * Write a byte of data. + * + ****************************************************************************/ + +static uint32_t cxd56_sdio_writeb_internal(FAR struct sdio_function_s * sf, uint32_t addr, uint8_t data, + FAR uint8_t * rdata) +{ + uint32_t response; + uint32_t cmd52arg; + struct cxd56_sdiodev_s *priv = &g_sdhcdev; + int ret; + + DEBUGASSERT(NULL != sf); + + cmd52arg = cxd56_sdio_make_cmd52arg(addr, data, rdata, 1, 0); + ret = cxd56_sdio_sendcmdpoll(priv, SDIO_ACMD52, cmd52arg); + if (ret == OK) + { + cxd56_sdio_recvshort(&priv->dev, SDIO_ACMD52, &response); + if (ret != OK) + { + mcerr("ERROR: Addr:0x%x, recv R5 error\n", addr); + goto WRITEB_ERR; + } + } + else + { + mcerr("ERROR: Send cmd52 addr:0x%x error\n", addr); + goto WRITEB_ERR; + } + if ((!CMD52_RESP_OK(response)) || (response == 0xffffffff)) + { + mcerr("ERROR: Fail resp %u\n", response); + goto WRITEB_ERR; + } + if (rdata) + { + *rdata = response & 0xff; + } + + return 0; +WRITEB_ERR: + return ret; +} + +/**************************************************************************** + * Name: mmcsd_io_changeclock + * + * Description: + * change the sdio clock. + * + ****************************************************************************/ + +static int cxd56_sdio_changeclock(FAR struct cxd56_sdiodev_s *priv) +{ + int ret; + uint32_t response = 0; + + ret = cxd56_sdio_sendcmdpoll(priv, SDIO_ACMD52, 0x08<<9); + if (ret == OK) + { + cxd56_sdio_recvshort(&priv->dev, SDIO_ACMD52, &response); + } + else + { + mcerr("ERROR: Send cmd52, getclock error\n"); + return ret; + } +#if 0 + mcinfo("Force 400Khz SDIO clock\n"); + if (TRUE || (response & 0x40) != 0) +#else + if ((response & 0x40) != 0) +#endif + { + mcinfo("Set clock to 400KHz\n"); + cxd56_sdio_clock(&priv->dev, CLOCK_IDMODE); + } + else + { + mcinfo("Set clock to 25MHz\n"); + cxd56_sdio_clock(&priv->dev, CLOCK_SD_TRANSFER_4BIT); + } + return ret; +} + +/**************************************************************************** + * Name: cxd56_sdio_function_alloc + * + * Description: + * Allocate space for each function. + * + ****************************************************************************/ + +static FAR struct sdio_function_s *cxd56_sdio_function_alloc(FAR struct sdio_softc_s *sc) +{ + FAR struct sdio_function_s *sf; + + DEBUGASSERT(sc); + sf = (FAR struct sdio_function_s *)kmm_malloc(sizeof(struct sdio_function_s)); + if (!sf) + { + mcerr("ERROR: Failed\n"); + return NULL; + } + memset(sf, 0, sizeof(struct sdio_function_s)); + sf->sc = sc; + sf->number = -1; + sf->cis.manufacturer = 0xffff; + sf->cis.product = 0xffff; + sf->cis.function = 0xff; + sf->irq_callback = NULL; + return sf; +} + +/**************************************************************************** + * Name: cxd56_sdio_read_cis + * + * Description: + * Read the card information structure. + * + ****************************************************************************/ + +static uint32_t cxd56_sdio_read_cis(FAR struct sdio_function_s * sf, FAR struct sdio_cis_s * cis) +{ + int i; + FAR struct sdio_function_s *sf0; + uint8_t tplcode; + uint8_t tpllen; + uint32_t ret; + uint32_t cisptr = 0; + uint8_t response = 0; + uint32_t addr; + + mcinfo("I/O func's num:%d\n", sf->number); + + DEBUGASSERT(sf && cis); + sf0 = sf->sc->fn[0]; + addr = SDIO_CCCR_CCP + (sf->number * SDIO_CCCR_SIZE); + for(i=0; i<3; i++) + { + ret = cxd56_sdio_readb_internal(sf0, (addr+i), &response); + if (ret == 0) + { + cisptr |= (response << (8*i)); + } + } + if ((cisptr < SDIO_CIS_START) || (cisptr >= SDIO_CIS_END)) + { + mcerr("ERROR: Bad cis ptr %#x\n", cisptr); + return 1; + } + for(;;) + { + ret = cxd56_sdio_readb_internal(sf0, cisptr++, &tplcode); + if (ret != 0) + { + return ret; + } + if (tplcode == SDIO_CISTPL_END) + { + break; + } + else if (tplcode == SDIO_CISTPL_NULL) + { + continue; + } + ret = cxd56_sdio_readb_internal(sf0, cisptr++, &tpllen); + if (ret != 0) + { + return ret; + } + if (tpllen == 0) + { + mcerr("ERROR: Cis error reg %d tpl %#x len %d\n", cisptr, tplcode, tpllen); + break; + } + + switch (tplcode) + { + case SDIO_CISTPL_FUNCID: + if (tpllen < 2) + { + mcerr("ERROR: Bad funcid length\n"); + cisptr += tpllen; + break; + } + ret = cxd56_sdio_readb_internal(sf0, cisptr++, &response); + if (ret != 0) + { + return ret; + } + cis->function = response; + cisptr += tpllen; + mcinfo("get funcid 0x%x, len %d\n", cis->function, tpllen); + break; + case SDIO_CISTPL_MANFID: + if (tpllen < 4) + { + mcerr("ERROR: Bad manfid length\n"); + cisptr += tpllen; + break; + } + ret = cxd56_sdio_readb_internal(sf0, cisptr++, &response); + if (ret != 0) + { + return ret; + } + cis->manufacturer = response; + ret = cxd56_sdio_readb_internal(sf0, cisptr++, &response); + if (ret != 0) + { + return ret; + } + cis->manufacturer |= response << 8; + ret = cxd56_sdio_readb_internal(sf0, cisptr++, &response); + if (ret != 0) + { + return ret; + } + cis->product = response; + ret = cxd56_sdio_readb_internal(sf0, cisptr++, &response); + if (ret != 0) + { + return ret; + } + cis->product = response << 8; + mcinfo("manufacturer/product ID: %x:%x, len %d\n", + cis->manufacturer, + cis->product, + tpllen); + break; + default: + mcinfo("unknown tuple code %#x, length %d\n", tplcode, tpllen); + cisptr += tpllen; + break; + } + } + return OK; +} + +/**************************************************************************** + * Name: cxd56_sdio_enable_cardint + * + * Description: + * Enable the card interrupt bit of the CXD56_SDHCI_IRQSIGEN and + * CXD56_SDHCI_IRQSTATEN register. + * + ****************************************************************************/ + +static int cxd56_sdio_enable_cardint(void) +{ + irqstate_t flags; + + flags = enter_critical_section(); + putreg32(getreg32(CXD56_SDHCI_IRQSIGEN) | SDHCI_INT_CINT, CXD56_SDHCI_IRQSIGEN); + putreg32(getreg32(CXD56_SDHCI_IRQSTATEN) | SDHCI_INT_CINT, CXD56_SDHCI_IRQSTATEN); + leave_critical_section(flags); + return OK; +} + +/**************************************************************************** + * Name: cxd56_sdhci_irq_handler + * + * Description: + * Wait for the card interrupt and run the function's irq callback. + * + ****************************************************************************/ + +static int cxd56_sdhci_irq_handler(FAR struct sdio_dev_s *dev) +{ + int ret = 0; + FAR struct sdio_softc_s *sc; + FAR struct sdio_function_s *sf0; + FAR struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + uint8_t response; + int i; + + sc = &priv->sc; + sf0 = priv->sc.fn[0]; + ret = cxd56_sdio_readb_internal(sf0, SDIO_CCCR_INTPEND, &response); + for (i=1; i<8; i++) + { + if (response & (1<fn[i]->irq_callback) + { + sc->fn[i]->irq_callback(&priv->dev); + } + } + } + cxd56_sdio_enable_cardint(); + + return ret; +} + +/**************************************************************************** + * Name: cxd56_sdio_register_irq + * + * Description: + * Register the func interrupt handler. + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * func_num - I/O Function's num + * handler - The function's irq callback handler + * + ****************************************************************************/ + +static int cxd56_sdio_register_irq(FAR struct sdio_dev_s *dev, int func_num, + FAR sdio_irqhandler_t * handler) +{ + int ret; + uint8_t reg, regorg; + FAR struct sdio_function_s *sf0; + FAR struct sdio_function_s *sf; + FAR struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + + DEBUGASSERT(handler); + + sf = priv->sc.fn[func_num]; + sf0 = priv->sc.fn[0]; + + if (NULL != sf->irq_callback) + { + mcerr("ERROR: Already registered a sdio callback, fn number: %d\n", + sf->number); + return -EBUSY; + } + cxd56_sdio_takesem(priv); + /* enable irq in device side */ + ret = cxd56_sdio_readb_internal(sf0, SDIO_CCCR_INTEN, ®); + if (ret) + { + goto REG_IRQ_FAIL; + } + + sf->irq_callback = handler; + + regorg = reg; + reg |= ((1 << sf->number) | (1 << 0)); + + ret = cxd56_sdio_writeb_internal(sf0, SDIO_CCCR_INTEN, reg, NULL); + if (ret) + { + cxd56_sdio_writeb_internal(sf0, SDIO_CCCR_INTEN, regorg, NULL); + goto REG_IRQ_FAIL; + } + sem_post(&priv->sc.sem); + return ret; + +REG_IRQ_FAIL: + sf->irq_callback = NULL; + mcerr("ERROR: Ret: %d\n", ret); + sem_post(&priv->sc.sem); + return ret; +} + +/**************************************************************************** + * Name: cxd56_sdio_blocksize + * + * Description: + * Set I/O block size for Function. + * + ****************************************************************************/ + +static int cxd56_sdio_blocksize(FAR struct sdio_function_s * sf, uint32_t size) +{ + uint32_t cmd52arg; + uint32_t blksz_addr; + struct cxd56_sdiodev_s *priv = &g_sdhcdev; + + blksz_addr = sf->number * SDIO_FBR_START + 0x10; + + cmd52arg = cxd56_sdio_make_cmd52arg(blksz_addr, (size & 0xFF), NULL, true, 0); + cxd56_sdio_sendcmdpoll(priv, SDIO_ACMD52, cmd52arg); + + cmd52arg = cxd56_sdio_make_cmd52arg(blksz_addr+1, ((size >> 8) & 0xFF), NULL, true, 0); + cxd56_sdio_sendcmdpoll(priv, SDIO_ACMD52, cmd52arg); + + return 0; +} + +/**************************************************************************** + * Name: cxd56_sdio_func_ready + * + * Description: + * Function will become ready, and FN0 is always ready. + * + ****************************************************************************/ + +static int cxd56_sdio_func_ready(FAR struct sdio_function_s * sf) +{ + FAR struct sdio_softc_s *sc; + FAR struct sdio_function_s *sf0; + uint8_t rv; + int ret; + + DEBUGASSERT(NULL != sf); + if (sf->number == 0) + { + return 1; /* FN0 is always ready */ + } + + sc = sf->sc; + sf0 = sc->fn[0]; + ret = cxd56_sdio_readb_internal(sf0, SDIO_CCCR_IORDY, &rv); + if (0 == ret) + { + return (rv & (1 << sf->number)) != 0; + } + return 0; +} + +/**************************************************************************** + * Name: cxd56_sdio_function_disable + * + * Description: + * Function will be disabled, and FN0 is always enabled. + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * func_num - I/O Function's num + * + ****************************************************************************/ + +static int cxd56_sdio_function_disable(FAR struct sdio_dev_s *dev, int func_num) +{ + FAR struct sdio_function_s *sf0; + FAR struct sdio_function_s *sf; + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + uint8_t rv; + int ret; + + sf = priv->sc.fn[func_num]; + sf0 = priv->sc.fn[0]; + mcinfo("I/O func's num:%d\n", sf->number); + + cxd56_sdio_takesem(priv); + ret = cxd56_sdio_readb_internal(sf0, SDIO_CCCR_IOEN, &rv); + if (ret) + { + goto FUNC_DIS_ERR; + } + + rv &= ~(1 << sf->number); + ret = cxd56_sdio_writeb_internal(sf0, SDIO_CCCR_IOEN, rv, NULL); + if (ret) + { + goto FUNC_DIS_ERR; + } + sem_post(&priv->sc.sem); + return 0; +FUNC_DIS_ERR: + mcerr("ERROR: Io fail ret %u\n", ret); + sem_post(&priv->sc.sem); + return ret; +} + +/**************************************************************************** + * Name: cxd56_sdio_function_enable + * + * Description: + * Function will be enabled. + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * func_num - I/O Function's num + * + ****************************************************************************/ + +static int cxd56_sdio_function_enable(FAR struct sdio_dev_s *dev, int func_num) +{ + FAR struct sdio_function_s *sf0; + FAR struct sdio_function_s *sf; + uint8_t rv; + int retry = 10; + int ret = 0; + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + + sf = priv->sc.fn[func_num]; + sf0 = priv->sc.fn[0]; + mcinfo("I/O func's num:%d\n", sf->number); + if (sf->number == 0) + { + return 0; + } + cxd56_sdio_takesem(priv); + ret = cxd56_sdio_readb_internal(sf0, SDIO_CCCR_IOEN, &rv); + if (ret) + { + goto FUNC_EN_ERR; + } + rv |= (1 << sf->number); + /* according to sdio_rw_direct(), set NULL to rdata */ + ret = cxd56_sdio_writeb_internal(sf0, SDIO_CCCR_IOEN, rv, NULL); + if (ret) + { + goto FUNC_EN_ERR; + } + cxd56_sdio_blocksize(sf, priv->blocksize);/* Optimize SDIO transmission speed, so set blocksize here */ + + while (!cxd56_sdio_func_ready(sf) && retry-- > 0) + { + up_udelay(5 * 1000); + } + ret = (retry >= 0) ? 0 : -ETIMEDOUT; + + if (0 == ret) + { + sem_post(&priv->sc.sem); + return 0; + } +FUNC_EN_ERR: + mcerr("ERROR: Io fail ret %u\n", ret); + sem_post(&priv->sc.sem); + return -EIO; +} + +/**************************************************************************** + * Name: cxd56_sdio_readb + * + * Description: + * Read a byte of data. + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * func_num - I/O Function's num + * addr - This is the address of the byte of data inside of the selected + * function to read or write + * rdata - the actual value read from that I/O location is returned + * in this field + * + ****************************************************************************/ + +static int cxd56_sdio_readb(FAR struct sdio_dev_s *dev, int func_num, + uint32_t addr, FAR uint8_t * rdata) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + int ret; + + cxd56_sdio_takesem(priv); + ret = cxd56_sdio_readb_internal(priv->sc.fn[func_num], addr, rdata); + sem_post(&priv->sc.sem); + return ret; +} + +/**************************************************************************** + * Name: cxd56_sdio_writeb + * + * Description: + * Write a byte of data. + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * func_num - I/O Function's num + * addr - This is the address of the byte of data inside of the selected + * function to read or write + * data - This is the byte that is written to the selected address + * rdata - The value of the register after the write + * + ****************************************************************************/ + +static int cxd56_sdio_writeb(FAR struct sdio_dev_s *dev, int func_num, + uint32_t addr, uint8_t data, FAR uint8_t * rdata) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + int ret; + + cxd56_sdio_takesem(priv); + ret = cxd56_sdio_writeb_internal(priv->sc.fn[func_num], addr, data, rdata); + sem_post(&priv->sc.sem); + return ret; +} + +/**************************************************************************** + * Name: cxd56_sdio_write + * + * Description: + * Write large number data. + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * func_num - I/O Function's num + * addr - Start Address of I/O register to write + * data - This is the large number data that is written to the selected + * address + * size - The size of the written data + * + ****************************************************************************/ + +static int cxd56_sdio_write(FAR struct sdio_dev_s *dev, int func_num, uint32_t addr, + FAR uint8_t * data, uint32_t size) +{ + uint32_t remainder = size; + int ret; + uint32_t cmd53arg; + sdio_eventset_t wkupevent; + FAR struct sdio_function_s *sf; + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + + sf = priv->sc.fn[func_num]; + mcinfo("sf->number = %d\n", sf->number); + /* Do the bulk of the transfer using block mode (if supported). */ + cxd56_sdio_takesem(priv); + if (size >= SDIO_BLOCK_SIZE) + { + while (remainder >= SDIO_BLOCK_SIZE) + { + uint32_t blocks; + blocks = MIN(remainder / SDIO_BLOCK_SIZE, 8); + size = blocks * SDIO_BLOCK_SIZE; + cxd56_blocksetup(&priv->dev, SDIO_BLOCK_SIZE, blocks); + cxd56_sdio_waitenable(&priv->dev, SDIOWAIT_TRANSFERDONE | SDIOWAIT_TIMEOUT | SDIOWAIT_ERROR); +#ifdef CONFIG_SDIO_DMA + if (priv->sc.dma) + { + ret = cxd56_sdio_dmasendsetup(&priv->dev, data, size); + if (ret != OK) + { + mcerr("ERROR: SDIO_DMASENDSETUP: error %d\n", ret); + goto WRITE_ERR; + } + } + else +#endif + { + cxd56_sdio_sendsetup(&priv->dev, data, size); + } + cmd53arg = cxd56_sdio_make_cmd53arg(1, sf->number, addr, 1, blocks, priv->blocksize); + ret = cxd56_sdio_sendcmdpoll(priv, SDIO_ACMD53 | MMCSD_MULTIBLOCK | MMCSD_WRDATAXFR, cmd53arg); + if (ret != OK) + { + mcerr("ERROR: Send cmd53 error\n"); + goto WRITE_ERR; + } + wkupevent = cxd56_sdio_eventwait(&priv->dev, SDIO_BLOCK_TIMEOUT * blocks); + if ((wkupevent & (SDIOWAIT_TIMEOUT | SDIOWAIT_ERROR)) != 0) + { + mcerr("ERROR: Sdio write time out %x\n", wkupevent); + goto WRITE_TIME_OUT; + } + remainder -= size; + data += size; + addr += size; + } + } + + /* Write the remainder using byte mode. */ + while (remainder > 0) + { + size = MIN(remainder, 64); + cxd56_blocksetup(&priv->dev, size, 1); + cxd56_sdio_waitenable(&priv->dev, SDIOWAIT_TRANSFERDONE | SDIOWAIT_TIMEOUT | SDIOWAIT_ERROR); +#ifdef CONFIG_SDIO_DMA + if (priv->sc.dma) + { + ret = cxd56_sdio_dmasendsetup(&priv->dev, data, size); + if (ret != OK) + { + mcerr("ERROR: SDIO_DMASENDSETUP: error %d\n", ret); + goto WRITE_ERR; + } + } + else +#endif + { + cxd56_sdio_sendsetup(&priv->dev, data, size); + } + cmd53arg = cxd56_sdio_make_cmd53arg(1, sf->number, addr, 1, 0, size); + ret = cxd56_sdio_sendcmdpoll(priv, SDIO_ACMD53 | MMCSD_WRDATAXFR, cmd53arg); + if (ret != OK) + { + mcerr("ERROR: Send cmd53 error\n"); + goto WRITE_ERR; + } + wkupevent = cxd56_sdio_eventwait(&priv->dev, SDIO_BLOCK_TIMEOUT); + if ((wkupevent & (SDIOWAIT_TIMEOUT | SDIOWAIT_ERROR)) != 0) + { + mcerr("ERROR: Sdio write time out %x\n", wkupevent); + goto WRITE_TIME_OUT; + } + remainder -= size; + data += size; + addr += size; + } + sem_post(&priv->sc.sem); + return 0; +WRITE_TIME_OUT: + sem_post(&priv->sc.sem); + return wkupevent & SDIOWAIT_TIMEOUT ? -ETIMEDOUT : -EIO; +WRITE_ERR: + sem_post(&priv->sc.sem); + return ret; +} + +/**************************************************************************** + * Name: cxd56_sdio_read + * + * Description: + * Read large number data. + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * func_num - I/O Function's num + * addr - Start Address of I/O register to read + * data - the large number data read from that I/O location is returned + * in this field + * size - The size of the read data + * + ****************************************************************************/ + +static int cxd56_sdio_read(FAR struct sdio_dev_s *dev, int func_num, uint32_t addr, + FAR uint8_t * data, uint32_t size) +{ + uint32_t remainder = size; + int ret; + uint32_t cmd53arg; + sdio_eventset_t wkupevent; + FAR struct sdio_function_s *sf; + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + + sf = priv->sc.fn[func_num]; + mcinfo("sf->number = %d\n", sf->number); + /* Do the bulk of the transfer using block mode (if supported). */ + cxd56_sdio_takesem(priv); + if (size >= SDIO_BLOCK_SIZE) + { + while (remainder >= SDIO_BLOCK_SIZE) + { + uint32_t blocks; + blocks = MIN(remainder / SDIO_BLOCK_SIZE, 8); + size = blocks * SDIO_BLOCK_SIZE; + cxd56_blocksetup(&priv->dev, SDIO_BLOCK_SIZE, blocks); + cxd56_sdio_waitenable(&priv->dev, SDIOWAIT_TRANSFERDONE | SDIOWAIT_TIMEOUT | SDIOWAIT_ERROR); +#ifdef CONFIG_SDIO_DMA + if (priv->sc.dma) + { + ret = cxd56_sdio_dmarecvsetup(&priv->dev, data, size); + if (ret != OK) + { + mcerr("ERROR: SDIO_DMASENDSETUP: error %d\n", ret); + goto READ_ERR; + } + } + else +#endif + { + cxd56_sdio_recvsetup(&priv->dev, data, size); + } + cmd53arg = cxd56_sdio_make_cmd53arg(0, sf->number, addr, 1, blocks, priv->blocksize); + ret = cxd56_sdio_sendcmdpoll(priv, SDIO_ACMD53 | MMCSD_MULTIBLOCK | MMCSD_RDDATAXFR, cmd53arg); + if (ret != OK) + { + mcerr("ERROR: Send cmd53 error\n"); + goto READ_ERR; + } + wkupevent = cxd56_sdio_eventwait(&priv->dev, SDIO_BLOCK_TIMEOUT * blocks); + if ((wkupevent & (SDIOWAIT_TIMEOUT | SDIOWAIT_ERROR)) != 0) + { + mcerr("ERROR: Sdio read time out %x\n", wkupevent); + goto READ_TIME_OUT; + } + remainder -= size; + data += size; + addr += size; + } + } + + /* Write the remainder using byte mode. */ + while (remainder > 0) + { + size = MIN(remainder, 64); + cxd56_blocksetup(&priv->dev, size, 1); + cxd56_sdio_waitenable(&priv->dev, SDIOWAIT_TRANSFERDONE | SDIOWAIT_TIMEOUT | SDIOWAIT_ERROR); +#ifdef CONFIG_SDIO_DMA + if (priv->sc.dma) + { + ret = cxd56_sdio_dmarecvsetup(&priv->dev, data, size); + if (ret != OK) + { + mcerr("ERROR: SDIO_DMASENDSETUP: error %d\n", ret); + goto READ_ERR; + } + } + else +#endif + { + cxd56_sdio_recvsetup(&priv->dev, data, size); + } + cmd53arg = cxd56_sdio_make_cmd53arg(0, sf->number, addr, 1, 0, size); + ret = cxd56_sdio_sendcmdpoll(priv, SDIO_ACMD53 | MMCSD_RDDATAXFR, cmd53arg); + if (ret != OK) + { + mcerr("ERROR: Send cmd53 error\n"); + goto READ_ERR; + } + wkupevent = cxd56_sdio_eventwait(&priv->dev, SDIO_BLOCK_TIMEOUT); + if ((wkupevent & (SDIOWAIT_TIMEOUT | SDIOWAIT_ERROR)) != 0) + { + mcerr("ERROR: Sdio read time out %x\n", wkupevent); + goto READ_TIME_OUT; + } + remainder -= size; + data += size; + addr += size; + } + sem_post(&priv->sc.sem); + return 0; +READ_TIME_OUT: + sem_post(&priv->sc.sem); + return wkupevent & SDIOWAIT_TIMEOUT ? -ETIMEDOUT : -EIO; +READ_ERR: + sem_post(&priv->sc.sem); + return ret; +} + +/**************************************************************************** + * Name: cxd56_sdio_get_cis + * + * Description: + * get SDIO Card Information Structure. + * + ****************************************************************************/ + +static int cxd56_sdio_get_cis(FAR struct sdio_dev_s *dev, int func_num, FAR struct sdio_cis_s * cis) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + + if (cis) + { + *cis = priv->sc.fn[func_num]->cis; + } + return OK; +} + +/**************************************************************************** + * Name: cxd56_sdio_initialize + * + * Description: + * We believe that there is A sdio device in the slot.initialize the sdio + * device. + * + ****************************************************************************/ + +static int cxd56_sdio_initialize(struct cxd56_sdiodev_s *priv) +{ + int ret, i; + uint32_t response; + FAR struct sdio_function_s *fn; + + priv->sc.func_num = 1; + priv->sc.full_speed = false; + priv->blocksize = SDIO_BLOCK_SIZE; + + sem_init(&priv->sc.sem, 0, 1); +#ifdef CONFIG_SDIO_DMA + priv->sc.dma = true; +#endif + cxd56_sdio_attach(&priv->dev); + ret = cxd56_sdio_sendcmdpoll(priv, SDIO_CMD5, 0x0); + + if (ret == OK) + { + ret = cxd56_sdio_recvshort(&priv->dev, SDIO_CMD5, &response); + if (ret != OK) + { + mcerr("ERROR: Recv R4 error\n"); + return ret; + } + } + else + { + mcerr("ERROR: Send cmd5 error\n"); + return ret; + } + mcinfo("response = 0x%x, card has %d function\n", response, (response >> 28) & 7); + mcinfo("send cmd5 again to set card ready\n"); + if (response != 0xffffffff) + { + do + { + ret = cxd56_sdio_sendcmdpoll(priv, SDIO_CMD5, 0x300000); + if (ret == OK) + { + cxd56_sdio_recvshort(&priv->dev, SDIO_CMD5, &response); + } + usleep(4000); + } + while ((response == 0xffffffff) || + ((response & 0x80000000) == 0)); + mcinfo("response = 0x%x, card is ready(MSB=1)\n", response); + priv->sc.func_num = SDIO_OCR_NUM_FUNCTIONS(response) + 1; + } + mcinfo("send CMD3 to enter standby state\n"); + cxd56_sdio_sendcmdpoll(priv, SD_CMD3, 0); + ret = cxd56_sdio_recvshortcrc(&priv->dev, SD_CMD3, &response); + if (ret != OK) + { + return ret; + } + + mcinfo("RCA: 0x%x\n", (response >> 16)); + if (response & 0xffff) + { + mcerr("ERROR: CMD3 resp error: 0x%x\n", (response & 0xffff)); + if (response & 0x8000) + mcerr("ERROR: CRC error on previous command\n"); + } + + cxd56_sdio_sendcmdpoll(priv, MMCSD_CMD7S, response & 0xffff0000); + mcinfo("send cmd7(RCA:%x, %x) OK\n", (response >> 16), response & 0xffff0000); + ret = cxd56_sdio_recvshortcrc(&priv->dev, MMCSD_CMD7S, &response); + if (ret != OK) + { + mcerr("ERROR: mmcsd_recvR1 for CMD7 failed: %d\n", ret); + return ret; + } + + cxd56_sdio_changeclock(priv); + + ret = cxd56_sdio_sendcmdpoll(priv, SDIO_ACMD52, 0x7<<9); + if (ret == OK) + { + ret = cxd56_sdio_recvshort(&priv->dev, SDIO_ACMD52, &response); + if (ret != OK) + { + mcerr("ERROR: Addr:0x7, recv R5 error\n"); + return ret; + } + mcinfo("Bus interface ctrl (@0x7):0x%x\n", response); + // 0x80: CD disable = 1, we should set it be true before issue CMD53 + cxd56_sdio_sendcmdpoll(priv, SDIO_ACMD52, 0x7<<9 | (response & 0xFF) | 0x80); + mcinfo("set CD disable = 1\n"); + } + else + { + mcerr("ERROR: Send cmd52 addr:0x7 error\n"); + return ret; + } + + ret = cxd56_sdio_sendcmdpoll(priv, SDIO_ACMD52, 0x8<<9); + if (ret == OK) + { + cxd56_sdio_recvshort(&priv->dev, SDIO_ACMD52, &response); + if (ret != OK) + { + mcerr("ERROR: Addr:0x8, recv R5 error\n"); + return ret; + } + mcinfo("Card capability(@0x8):0x%x\n", response); + + mcinfo("It's a %s card\n", (response & 0x40)? "low speed": "full speed"); + if ((response & 0x40) == 0) + { + priv->sc.full_speed = true; + } + } + else + { + mcerr("ERROR: Send cmd52 addr:0x8 error\n"); + return ret; + } + + mcinfo("func_num = %d\n", priv->sc.func_num); + for (i = 0; i < priv->sc.func_num; i++) + { + fn = cxd56_sdio_function_alloc(&priv->sc); + if (!fn) + { + goto SDIO_INIT_ERR; + } + fn->number = i; + + priv->sc.fn[i] = fn; + } + + for (i = 1; i < priv->sc.func_num; i++) + { + fn = priv->sc.fn[i]; + if (cxd56_sdio_read_cis(fn, &fn->cis) != 0) + { + mcerr("ERROR: Can't read CIS\n"); + goto SDIO_INIT_CIS_ERR; + } + } + + if (priv->sc.full_speed) + { + uint8_t bus_ctrl; + + /* enable 4-bits bus */ + cxd56_sdio_readb_internal(priv->sc.fn[0], SDIO_CCCR_BUS_IF, &bus_ctrl); + bus_ctrl = (bus_ctrl & ~0x3) | 0x2; + cxd56_sdio_writeb_internal(priv->sc.fn[0], SDIO_CCCR_BUS_IF, bus_ctrl, &bus_ctrl); + + if ((bus_ctrl & 0x3) == 2) + { + mcinfo("Set card to 4-bits mode\n"); + cxd56_sdio_widebus(&priv->dev, true); + mcinfo("Set controller to 4-bits mode\n"); + } + else + { + mcinfo("Failed to enter 4-bits mode\n"); + } + } + + return OK; + +SDIO_INIT_ERR: + return -ENOMEM; + +SDIO_INIT_CIS_ERR: + return -EIO; +} +#endif /* CONFIG_CXD56_SDIO_ENABLE_MULTIFUNCTION */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: cxd56_sdhci_initialize + * + * Description: + * Initialize SDIO for operation. + * + * Input Parameters: + * slotno - Not used. + * + * Returned Values: + * A reference to an SDIO interface structure. NULL is returned on failures. + * + ****************************************************************************/ + +FAR struct sdio_dev_s *cxd56_sdhci_initialize(int slotno) +{ + uint32_t regval; +#ifdef CONFIG_SDIO_DMA + uint32_t i; +#endif + + /* There is only one slot */ + + struct cxd56_sdiodev_s *priv = &g_sdhcdev; + DEBUGASSERT(slotno == 0); + + /* Initalize the pins */ + + board_sdcard_pin_initialize(); + + /* Enable clocking to the SDHC module. Clocking is still disabled in + * the SYSCTRL register. + */ + + cxd56_sdio_clock_enable(); + + //putreg32(getreg32(CXD56_SDHCI_BASE+0x230) >> 3 ,CXD56_SDHCI_BASE+0x230); + putreg32(getreg32(CXD56_SDHCI_SYSCTL) | SDHCI_SYSCTL_ICLKEN, CXD56_SDHCI_SYSCTL); + + /* Command Line Pre Drive Enable */ + regval = getreg32(CXD56_SDHCI_VENDSPEC); + putreg32(regval | 0x00000040, CXD56_SDHCI_VENDSPEC); + + /* Configure the pins */ + + board_sdcard_pin_configuraton(); + + /* Software reset */ + regval = getreg32(CXD56_SDHCI_SYSCTL); + putreg32(regval | SDHCI_SYSCTL_RSTA, CXD56_SDHCI_SYSCTL); + while ((getreg32(CXD56_SDHCI_SYSCTL) & SDHCI_SYSCTL_RSTA) != 0); + + putreg32(0xffffffff, CXD56_SDHCI_IRQSTATEN); + + cxd56_sdio_sdhci_reset(&(priv->dev)); + +#ifdef CONFIG_CXD56_SDIO_ENABLE_MULTIFUNCTION + /* Power ON for SDIO */ + + regval = getreg32(CXD56_SDHCI_PROCTL); + regval |= 0xf << 8; + putreg32(regval, CXD56_SDHCI_PROCTL); + + up_mdelay(25); + + /* SD clock enable */ + + cxd56_sdio_clock(&(priv->dev), CLOCK_IDMODE); +#endif /* CONFIG_CXD56_SDIO_ENABLE_MULTIFUNCTION */ + +#ifdef CONFIG_SDIO_DMA + for(i=0;iusedma = false; + priv->dmasend_prepare = false; + priv->dmasend_cmd = 0; + priv->dmasend_regcmd = 0; + +#endif + +#ifdef CONFIG_CXD56_SDIO_ENABLE_MULTIFUNCTION + cxd56_sdio_initialize(priv); +#endif /* CONFIG_CXD56_SDIO_ENABLE_MULTIFUNCTION */ + + /* In addition to the system clock, the SDHC module needs a clock for the + * base for the external card clock. There are four possible sources for + * this clock, selected by the SIM's SOPT2 register: + * + * - Core/system clock + * - MCGPLLCLK/MCGFLLCLK clock + * - OSCERCLK EXTAL clock + * - External bypass clock from off-chip (SCHC0_CLKINB) + */ + + return &g_sdhcdev.dev; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: cxd56_sdhci_finalize + * + * Description: + * Finalize SDIO for operation. + * + * Input Parameters: + * slotno - Not used. + * + * Returned Values: + * A reference to an SDIO interface structure. NULL is returned on failures. + * + ****************************************************************************/ + +FAR struct sdio_dev_s *cxd56_sdhci_finalize(int slotno) +{ + uint32_t regval; + + /* There is only one slot */ + + struct cxd56_sdiodev_s *priv = &g_sdhcdev; + DEBUGASSERT(slotno == 0); + + /* Enable clocking to the SDHC module. Clocking is still disabled in + * the SYSCTRL register. + */ + + /* SD clock disable */ + + cxd56_sdio_clock(&(priv->dev), CLOCK_SDIO_DISABLED); + + /* Power OFF for SDIO */ + + regval = getreg32(CXD56_SDHCI_PROCTL); + regval &= ~(0xf << 8); + putreg32(regval, CXD56_SDHCI_PROCTL); + + /* Disable Internal Clock */ + + putreg32(getreg32(CXD56_SDHCI_SYSCTL) & ~SDHCI_SYSCTL_ICLKEN, CXD56_SDHCI_SYSCTL); + + /* Command Line Pre Drive Disable */ + + regval = getreg32(CXD56_SDHCI_VENDSPEC); + putreg32(regval & ~0x00000040, CXD56_SDHCI_VENDSPEC); + + /* SDIO Clock Disable */ + + cxd56_sdio_clock_disable(); + + return &g_sdhcdev.dev; +} + +/**************************************************************************** + * Name: cxd56_sdhci_mediachange + * + * Description: + * Called by board-specific logic -- possible from an interrupt handler -- + * in order to signal to the driver that a card has been inserted or + * removed from the slot + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * + * Returned Values: + * None + * + ****************************************************************************/ + +void cxd56_sdhci_mediachange(FAR struct sdio_dev_s *dev) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + sdio_statset_t cdstatus; + irqstate_t flags; + uint8_t mediachange = 0; + int32_t timeout = SDHCI_CARDSTATETIMEOUT; + + /* Update card status */ + if (getreg32(CXD56_SDHCI_PRSSTAT) & SDHCI_PRSSTAT_SDCD) + { + while ((getreg32(CXD56_SDHCI_PRSSTAT) & SDHCI_PRSSTAT_CSTS) == 0) + { + if (timeout < 1) + { + break; + } + usleep(100000); + timeout -= 100000; + } + } + + flags = enter_critical_section(); + cdstatus = priv->cdstatus; + + if (getreg32(CXD56_SDHCI_PRSSTAT) & SDHCI_PRSSTAT_CINS) + { + priv->cdstatus |= SDIO_STATUS_PRESENT; + } + else + { + priv->cdstatus &= ~SDIO_STATUS_PRESENT; + } + + mcinfo("cdstatus OLD: %02x NEW: %02x\n", cdstatus, priv->cdstatus); + + /* Perform any requested callback if the status has changed */ + + if (cdstatus != priv->cdstatus) + { + if (priv->cdstatus & SDIO_STATUS_PRESENT) + { + priv->cbevents &= SDIOMEDIA_INSERTED; + } + mediachange = 1;//cxd56_sdio_callback(priv); + } + leave_critical_section(flags); + if (mediachange) + { + cxd56_sdio_callback(priv); + } +} + +/**************************************************************************** + * Name: cxd56_sdhci_wrprotect + * + * Description: + * Called by board-specific logic to report if the card in the slot is + * mechanically write protected. + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * wrprotect - true is a card is writeprotected. + * + * Returned Values: + * None + * + ****************************************************************************/ + +void cxd56_sdhci_wrprotect(FAR struct sdio_dev_s *dev, bool wrprotect) +{ + struct cxd56_sdiodev_s *priv = (struct cxd56_sdiodev_s *)dev; + irqstate_t flags; + + /* Update card status */ + + flags = enter_critical_section(); + if (wrprotect) + { + priv->cdstatus |= SDIO_STATUS_WRPROTECTED; + } + else + { + priv->cdstatus &= ~SDIO_STATUS_WRPROTECTED; + } + + mcinfo("cdstatus: %02x\n", priv->cdstatus); + leave_critical_section(flags); +} +#endif /* CONFIG_CXD56_SDIO */ diff --git a/arch/arm/src/cxd56xx/cxd56_sdhci.h b/arch/arm/src/cxd56xx/cxd56_sdhci.h new file mode 100644 index 0000000000..e53807d08e --- /dev/null +++ b/arch/arm/src/cxd56xx/cxd56_sdhci.h @@ -0,0 +1,463 @@ +/**************************************************************************** + * arch/arm/src/cxd56xx/cxd56_sdhci.h + * + * Copyright (C) 2008-2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Copyright 2018 Sony Semiconductor Solutions Corporation + * + * 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 __ARCH_ARM_SRC_CXD56XX_CXD56_SDHCI_H +#define __ARCH_ARM_SRC_CXD56XX_CXD56_SDHCI_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include "chip.h" + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Register Offsets *********************************************************/ + +#define CXD56_SDHCI_DSADDR_OFFSET (0x0000) /* DMA System Address Register */ +#define CXD56_SDHCI_BLKATTR_OFFSET (0x0004) /* Block Attributes Register */ +#define CXD56_SDHCI_CMDARG_OFFSET (0x0008) /* Command Argument Register */ +#define CXD56_SDHCI_XFERTYP_OFFSET (0x000c) /* Transfer Type Register */ +#define CXD56_SDHCI_CMDRSP0_OFFSET (0x0010) /* Command Response 0 */ +#define CXD56_SDHCI_CMDRSP1_OFFSET (0x0014) /* Command Response 1 */ +#define CXD56_SDHCI_CMDRSP2_OFFSET (0x0018) /* Command Response 2 */ +#define CXD56_SDHCI_CMDRSP3_OFFSET (0x001c) /* Command Response 3 */ +#define CXD56_SDHCI_DATPORT_OFFSET (0x0020) /* Buffer Data Port Register */ +#define CXD56_SDHCI_PRSSTAT_OFFSET (0x0024) /* Present State Register */ +#define CXD56_SDHCI_PROCTL_OFFSET (0x0028) /* Protocol Control Register */ +#define CXD56_SDHCI_SYSCTL_OFFSET (0x002c) /* System Control Register */ +#define CXD56_SDHCI_IRQSTAT_OFFSET (0x0030) /* Interrupt Status Register */ +#define CXD56_SDHCI_IRQSTATEN_OFFSET (0x0034) /* Interrupt Status Enable Register */ +#define CXD56_SDHCI_IRQSIGEN_OFFSET (0x0038) /* Interrupt Signal Enable Register */ +#define CXD56_SDHCI_AC12ERR_OFFSET (0x003c) /* Auto CMD12 Error Status Register */ +#define CXD56_SDHCI_HTCAPBLT_OFFSET (0x0040) /* Host Controller Capabilities */ +#define CXD56_SDHCI_FEVT_OFFSET (0x0050) /* Force Event Register */ +#define CXD56_SDHCI_ADMAES_OFFSET (0x0054) /* ADMA Error Status Register */ +#define CXD56_SDHCI_ADSADDR_OFFSET (0x0058) /* ADMA System Address Register */ +#define CXD56_SDHCI_HOSTVER_OFFSET (0x00fc) /* Host Controller Version */ +#define CXD56_SDHCI_VENDSPEC_OFFSET (0x0110) /* Vender Specific Control */ +#define CXD56_SDHCI_OTHERIOLL_OFFSET (0x021C) /* IO Pin Control */ +#define CXD56_SDHCI_USERDEF1CTL_OFFSET (0x0270) /* User Define1 Control Register */ +#define CXD56_SDHCI_USERDEF2CTL_OFFSET (0x0274) /* User Define2 Control Register */ + +/* Register Addresses *******************************************************/ +#define CXD56_SDHCI_BASE CXD56_SDIO_BASE + +#define CXD56_SDHCI_DSADDR (CXD56_SDHCI_BASE+CXD56_SDHCI_DSADDR_OFFSET) +#define CXD56_SDHCI_BLKATTR (CXD56_SDHCI_BASE+CXD56_SDHCI_BLKATTR_OFFSET) +#define CXD56_SDHCI_CMDARG (CXD56_SDHCI_BASE+CXD56_SDHCI_CMDARG_OFFSET) +#define CXD56_SDHCI_XFERTYP (CXD56_SDHCI_BASE+CXD56_SDHCI_XFERTYP_OFFSET) +#define CXD56_SDHCI_CMDRSP0 (CXD56_SDHCI_BASE+CXD56_SDHCI_CMDRSP0_OFFSET) +#define CXD56_SDHCI_CMDRSP1 (CXD56_SDHCI_BASE+CXD56_SDHCI_CMDRSP1_OFFSET) +#define CXD56_SDHCI_CMDRSP2 (CXD56_SDHCI_BASE+CXD56_SDHCI_CMDRSP2_OFFSET) +#define CXD56_SDHCI_CMDRSP3 (CXD56_SDHCI_BASE+CXD56_SDHCI_CMDRSP3_OFFSET) +#define CXD56_SDHCI_DATPORT (CXD56_SDHCI_BASE+CXD56_SDHCI_DATPORT_OFFSET) +#define CXD56_SDHCI_PRSSTAT (CXD56_SDHCI_BASE+CXD56_SDHCI_PRSSTAT_OFFSET) +#define CXD56_SDHCI_PROCTL (CXD56_SDHCI_BASE+CXD56_SDHCI_PROCTL_OFFSET) +#define CXD56_SDHCI_SYSCTL (CXD56_SDHCI_BASE+CXD56_SDHCI_SYSCTL_OFFSET) +#define CXD56_SDHCI_IRQSTAT (CXD56_SDHCI_BASE+CXD56_SDHCI_IRQSTAT_OFFSET) +#define CXD56_SDHCI_IRQSTATEN (CXD56_SDHCI_BASE+CXD56_SDHCI_IRQSTATEN_OFFSET) +#define CXD56_SDHCI_IRQSIGEN (CXD56_SDHCI_BASE+CXD56_SDHCI_IRQSIGEN_OFFSET) +#define CXD56_SDHCI_AC12ERR (CXD56_SDHCI_BASE+CXD56_SDHCI_AC12ERR_OFFSET) +#define CXD56_SDHCI_HTCAPBLT (CXD56_SDHCI_BASE+CXD56_SDHCI_HTCAPBLT_OFFSET) +#define CXD56_SDHCI_FEVT (CXD56_SDHCI_BASE+CXD56_SDHCI_FEVT_OFFSET) +#define CXD56_SDHCI_ADMAES (CXD56_SDHCI_BASE+CXD56_SDHCI_ADMAES_OFFSET) +#define CXD56_SDHCI_ADSADDR (CXD56_SDHCI_BASE+CXD56_SDHCI_ADSADDR_OFFSET) +#define CXD56_SDHCI_HOSTVER (CXD56_SDHCI_BASE+CXD56_SDHCI_HOSTVER_OFFSET) +#define CXD56_SDHCI_VENDSPEC (CXD56_SDHCI_BASE+CXD56_SDHCI_VENDSPEC_OFFSET) +#define CXD56_SDHCI_OTHERIOLL (CXD56_SDHCI_BASE+CXD56_SDHCI_OTHERIOLL_OFFSET) +#define CXD56_SDHCI_USERDEF1CTL (CXD56_SDHCI_BASE+CXD56_SDHCI_USERDEF1CTL_OFFSET) +#define CXD56_SDHCI_USERDEF2CTL (CXD56_SDHCI_BASE+CXD56_SDHCI_USERDEF2CTL_OFFSET) + +/* Register Bit Definitions *************************************************/ + +/* DMA System Address Register */ + +#define SDHCI_DSADDR_SHIFT (1) /* Bits 1-31: DMA System Address */ +#define SDHCI_DSADDR_MASK (0xfffffffe) + /* Bits 0-1: Reserved */ +/* Block Attributes Register */ + +#define SDHCI_BLKATTR_SIZE_SHIFT (0) /* Bits 0-12: Transfer Block Size */ +#define SDHCI_BLKATTR_SIZE_MASK (0x1fff << SDHCI_BLKATTR_SIZE_SHIFT) + /* Bits 13-15: Reserved */ +#define SDHCI_BLKATTR_CNT_SHIFT (16) /* Bits 16-31: Blocks Count For Current Transfer */ +#define SDHCI_BLKATTR_CNT_MASK (0xffff << SDHCI_BLKATTR_CNT_SHIFT) + +/* Command Argument Register (32-bit cmd/arg data) */ + +/* Transfer Type Register */ + +#define SDHCI_XFERTYP_DMAEN (1 << 0) /* Bit 0: DMA Enable */ +#define SDHCI_XFERTYP_BCEN (1 << 1) /* Bit 1: Block Count Enable */ +#define SDHCI_XFERTYP_AC12EN (1 << 2) /* Bit 2: Auto CMD12 Enable */ + /* Bit 3: Reserved */ +#define SDHCI_XFERTYP_DTDSEL (1 << 4) /* Bit 4: Data Transfer Direction Select */ +#define SDHCI_XFERTYP_MSBSEL (1 << 5) /* Bit 5: Multi/Single Block Select */ + /* Bits 6-15: Reserved */ +#define SDHCI_XFERTYP_RSPTYP_SHIFT (16) /* Bits 16-17: Response Type Select */ +#define SDHCI_XFERTYP_RSPTYP_MASK (3 << SDHCI_XFERTYP_RSPTYP_SHIFT) +# define SDHCI_XFERTYP_RSPTYP_NONE (0 << SDHCI_XFERTYP_RSPTYP_SHIFT) /* No response */ +# define SDHCI_XFERTYP_RSPTYP_LEN136 (1 << SDHCI_XFERTYP_RSPTYP_SHIFT) /* Response length 136 */ +# define SDHCI_XFERTYP_RSPTYP_LEN48 (2 << SDHCI_XFERTYP_RSPTYP_SHIFT) /* Response length 48 */ +# define SDHCI_XFERTYP_RSPTYP_LEN48BSY (3 << SDHCI_XFERTYP_RSPTYP_SHIFT) /* Response length 48, check busy */ + /* Bit 18: Reserved */ +#define SDHCI_XFERTYP_CCCEN (1 << 19) /* Bit 19: Command CRC Check Enable */ +#define SDHCI_XFERTYP_CICEN (1 << 20) /* Bit 20: Command Index Check Enable */ +#define SDHCI_XFERTYP_DPSEL (1 << 21) /* Bit 21: Data Present Select */ +#define SDHCI_XFERTYP_CMDTYP_SHIFT (22) /* Bits 22-23: Command Type */ +#define SDHCI_XFERTYP_CMDTYP_MASK (3 << SDHCI_XFERTYP_CMDTYP_SHIFT) +# define SDHCI_XFERTYP_CMDTYP_NORMAL (0 << SDHCI_XFERTYP_CMDTYP_SHIFT) /* Normal other commands */ +# define SDHCI_XFERTYP_CMDTYP_SUSPEND (1 << SDHCI_XFERTYP_CMDTYP_SHIFT) /* Suspend CMD52 for writing bus suspend in CCCR */ +# define SDHCI_XFERTYP_CMDTYP_RESUME (2 << SDHCI_XFERTYP_CMDTYP_SHIFT) /* Resume CMD52 for writing function select in CCCR */ +# define SDHCI_XFERTYP_CMDTYP_ABORT (3 << SDHCI_XFERTYP_CMDTYP_SHIFT) /* Abort CMD12, CMD52 for writing I/O abort in CCCR */ +#define SDHCI_XFERTYP_CMDINX_SHIFT (24) /* Bits 24-29: Command Index */ +#define SDHCI_XFERTYP_CMDINX_MASK (63 << SDHCI_XFERTYP_CMDINX_SHIFT) + /* Bits 30-31: Reserved */ +/* Command Response 0-3 (32-bit response data) */ + +/* Buffer Data Port Register (32-bit data content) */ + +/* Present State Register */ + +#define SDHCI_PRSSTAT_CIHB (1 << 0) /* Bit 0: Command Inhibit (CMD) */ +#define SDHCI_PRSSTAT_CDIHB (1 << 1) /* Bit 1: Command Inhibit (DAT) */ +#define SDHCI_PRSSTAT_DLA (1 << 2) /* Bit 2: Data Line Active */ +#define SDHCI_PRSSTAT_SDSTB (1 << 3) /* Bit 3: SD Clock Stable */ +#define SDHCI_PRSSTAT_IPGOFF (1 << 4) /* Bit 4: Bus Clock */ +#define SDHCI_PRSSTAT_HCKOFF (1 << 5) /* Bit 5: System Clock */ +#define SDHCI_PRSSTAT_PEROFF (1 << 6) /* Bit 6: SDHC clock */ +#define SDHCI_PRSSTAT_SDOFF (1 << 7) /* Bit 7: SD Clock Gated Off Internally */ +#define SDHCI_PRSSTAT_WTA (1 << 8) /* Bit 8: Write Transfer Active */ +#define SDHCI_PRSSTAT_RTA (1 << 9) /* Bit 9: Read Transfer Active */ +#define SDHCI_PRSSTAT_BWEN (1 << 10) /* Bit 10: Buffer Write Enable */ +#define SDHCI_PRSSTAT_BREN (1 << 11) /* Bit 11: Buffer Read Enable */ + /* Bits 12-15: Reserved */ +#define SDHCI_PRSSTAT_CINS (1 << 16) /* Bit 16: Card Inserted */ +#define SDHCI_PRSSTAT_CSTS (1 << 17) /* Bit 17: Card State Stable */ +#define SDHCI_PRSSTAT_SDCD (1 << 18) /* Bit 18: Card Detect Pin Level */ +#define SDHCI_PRSSTAT_SDWPN (1 << 19) /* Bit 19: Write Protect Switch Pin Level*/ +#define SDHCI_PRSSTAT_DLSL_SHIFT (20) /* Bits 20-23: DAT Line Signal Level */ +#define SDHCI_PRSSTAT_DLSL_MASK (0xf << SDHCI_PRSSTAT_DLSL_SHIFT) +# define SDHCI_PRSSTAT_DLSL_DAT0 (0x1 << SDHCI_PRSSTAT_DLSL_SHIFT) +# define SDHCI_PRSSTAT_DLSL_DAT1 (0x2 << SDHCI_PRSSTAT_DLSL_SHIFT) +# define SDHCI_PRSSTAT_DLSL_DAT2 (0x4 << SDHCI_PRSSTAT_DLSL_SHIFT) +# define SDHCI_PRSSTAT_DLSL_DAT3 (0x8 << SDHCI_PRSSTAT_DLSL_SHIFT) +#define SDHCI_PRSSTAT_CLSL (1 << 24) /* Bit 23: CMD Line Signal Level */ + +/* Protocol Control Register */ + +#define SDHCI_PROCTL_LCTL (1 << 0) /* Bit 0: LED Control */ +#define SDHCI_PROCTL_DTW_SHIFT (1) /* Bits 1-2: Data Transfer Width */ +#define SDHCI_PROCTL_DTW_MASK (1 << SDHCI_PROCTL_DTW_SHIFT) +# define SDHCI_PROCTL_DTW_1BIT (0 << SDHCI_PROCTL_DTW_SHIFT) /* 1-bit mode */ +# define SDHCI_PROCTL_DTW_4BIT (1 << SDHCI_PROCTL_DTW_SHIFT) /* 4-bit mode */ +#define SDHCI_PROCTL_DMAS_SHIFT (3) /* Bits 8-9: DMA Select */ +#define SDHCI_PROCTL_DMAS_MASK (3 << SDHCI_PROCTL_DMAS_SHIFT) +# define SDHCI_PROCTL_DMAS_NODMA (0 << SDHCI_PROCTL_DMAS_SHIFT) /* No DMA or simple DMA is selected */ +# define SDHCI_PROCTL_DMAS_ADMA2 (2 << SDHCI_PROCTL_DMAS_SHIFT) /* ADMA2 is selected */ +#define SDHCI_PROCTL_CDTL (1 << 6) /* Bit 6: Card Detect Test Level */ +#define SDHCI_PROCTL_CDSS (1 << 7) /* Bit 7: Card Detect Signal Selection */ + /* Bits 10-15: Reserved */ +#define SDHCI_PROCTL_SABGREQ (1 << 16) /* Bit 16: Stop At Block Gap Request */ +#define SDHCI_PROCTL_CREQ (1 << 17) /* Bit 17: Continue Request */ +#define SDHCI_PROCTL_RWCTL (1 << 18) /* Bit 18: Read Wait Control */ +#define SDHCI_PROCTL_IABG (1 << 19) /* Bit 19: Interrupt At Block Gap */ + /* Bits 20-23: Reserved */ +#define SDHCI_PROCTL_WECINT (1 << 24) /* Bit 24: Wakeup Event Enable On Card Interrupt */ +#define SDHCI_PROCTL_WECINS (1 << 25) /* Bit 25: Wakeup Event Enable On SD Card Insertion */ +#define SDHCI_PROCTL_WECRM (1 << 26) /* Bit 26: Wakeup Event Enable On SD Card Removal */ + /* Bits 27-31: Reserved */ +/* System Control Register */ + +#define SDHCI_SYSCTL_ICLKEN (1 << 0) /* Bit 0: Internal Clock Enable */ +#define SDHCI_SYSCTL_ICLKSTA (1 << 1) /* Bit 1: Internal Clock Stable */ +#define SDHCI_SYSCTL_SDCLKEN (1 << 2) /* Bit 2: SD Clock Enable */ +#define SDHCI_SYSCTL_GENSEL (1 << 5) /* Bit 5: Clock Generetor Select */ +#define SDHCI_SYSCTL_SDCLKFSUP_SHIFT (6) /* Bits 6-7: Divisor */ +#define SDHCI_SYSCTL_SDCLKFSUP_MASK (3 << SDHCI_SYSCTL_SDCLKFSUP_SHIFT) +#define SDHCI_SYSCTL_SDCLKFS_SHIFT (8) /* Bits 8-15: SDCLK Frequency Select */ +#define SDHCI_SYSCTL_SDCLKFS_MASK (0xff << SDHCI_SYSCTL_SDCLKFS_SHIFT) +#define SDHCI_SYSCTL_DTOCV_SHIFT (16) /* Bits 16-19: Data Timeout Counter Value */ +#define SDHCI_SYSCTL_DTOCV_MASK (0xf << SDHCI_SYSCTL_DTOCV_SHIFT) +# define SDHCI_SYSCTL_DTOCV_MUL(n) (((n)-213) << SDHCI_SYSCTL_DTOCV_SHIFT) /* SDCLK x n, n=213..227 */ + /* Bits 20-23: Reserved */ +#define SDHCI_SYSCTL_RSTA (1 << 24) /* Bit 24: Software Reset For ALL */ +#define SDHCI_SYSCTL_RSTC (1 << 25) /* Bit 25: Software Reset For CMD Line */ +#define SDHCI_SYSCTL_RSTD (1 << 26) /* Bit 26: Software Reset For DAT Line */ +#define SDHCI_SYSCTL_INITA (1 << 27) /* Bit 27: Initialization Active */ + /* Bits 28-31: Reserved */ +/* Interrupt Status Register, Interrupt Status Enable Register, and Interrupt Signal Enable Register + * Common interrupt bit definitions + */ + +#define SDHCI_INT_CC (1 << 0) /* Bit 0: Command Complete */ +#define SDHCI_INT_TC (1 << 1) /* Bit 1: Transfer Complete */ +#define SDHCI_INT_BGE (1 << 2) /* Bit 2: Block Gap Event */ +#define SDHCI_INT_DINT (1 << 3) /* Bit 3: DMA Interrupt */ +#define SDHCI_INT_BWR (1 << 4) /* Bit 4: Buffer Write Ready */ +#define SDHCI_INT_BRR (1 << 5) /* Bit 5: Buffer Read Ready */ +#define SDHCI_INT_CINS (1 << 6) /* Bit 6: Card Insertion */ +#define SDHCI_INT_CRM (1 << 7) /* Bit 7: Card Removal */ +#define SDHCI_INT_CINT (1 << 8) /* Bit 8: Card Interrupt */ + /* Bits 9-15: Reserved */ +#define SDHCI_INT_CTOE (1 << 16) /* Bit 16: Command Timeout Error */ +#define SDHCI_INT_CCE (1 << 17) /* Bit 17: Command CRC Error */ +#define SDHCI_INT_CEBE (1 << 18) /* Bit 18: Command End Bit Error */ +#define SDHCI_INT_CIE (1 << 19) /* Bit 19: Command Index Error */ +#define SDHCI_INT_DTOE (1 << 20) /* Bit 20: Data Timeout Error */ +#define SDHCI_INT_DCE (1 << 21) /* Bit 21: Data CRC Error */ +#define SDHCI_INT_DEBE (1 << 22) /* Bit 22: Data End Bit Error */ + /* Bit 23: Reserved */ +#define SDHCI_INT_AC12E (1 << 24) /* Bit 24: Auto CMD12 Error */ + /* Bits 25-27: Reserved */ +#define SDHCI_INT_DMAE (1 << 28) /* Bit 28: DMA Error */ + /* Bits 29-31: Reserved */ +#define SDHCI_INT_ALL 0x117f01ff + +/* Auto CMD12 Error Status Register */ + +#define SDHCI_AC12ERR_NE (1 << 0) /* Bit 0: Auto CMD12 Not Executed */ +#define SDHCI_AC12ERR_TOE (1 << 1) /* Bit 1: Auto CMD12 Timeout Error */ +#define SDHCI_AC12ERR_EBE (1 << 2) /* Bit 2: Auto CMD12 End Bit Error */ +#define SDHCI_AC12ERR_CE (1 << 3) /* Bit 3: Auto CMD12 CRC Error */ +#define SDHCI_AC12ERR_IE (1 << 4) /* Bit 4: Auto CMD12 Index Error */ + /* Bits 5-6: Reserved */ +#define SDHCI_AC12ERR_CNI (1 << 7) /* Bit 7: Command Not Issued By Auto CMD12 Error */ + /* Bits 8-31: Reserved */ +/* Host Controller Capabilities */ + /* Bits 0-15: Reserved */ +#define SDHCI_HTCAPBLT_MBL_SHIFT (16) /* Bits 16-18: Max Block Length */ +#define SDHCI_HTCAPBLT_MBL_MASK (7 << SDHCI_HTCAPBLT_MBL_SHIFT) +# define SDHCI_HTCAPBLT_MBL_512BYTES (0 << SDHCI_HTCAPBLT_MBL_SHIFT) +# define SDHCI_HTCAPBLT_MBL_1KB (1 << SDHCI_HTCAPBLT_MBL_SHIFT) +# define SDHCI_HTCAPBLT_MBL_2KB (2 << SDHCI_HTCAPBLT_MBL_SHIFT) +# define SDHCI_HTCAPBLT_MBL_4KB (3 << SDHCI_HTCAPBLT_MBL_SHIFT) + /* Bit 19: Reserved */ +#define SDHCI_HTCAPBLT_ADMAS (1 << 20) /* Bit 20: ADMA Support */ +#define SDHCI_HTCAPBLT_HSS (1 << 21) /* Bit 21: High Speed Support */ +#define SDHCI_HTCAPBLT_DMAS (1 << 22) /* Bit 22: DMA Support */ +#define SDHCI_HTCAPBLT_SRS (1 << 23) /* Bit 23: Suspend/Resume Support */ +#define SDHCI_HTCAPBLT_VS33 (1 << 24) /* Bit 24: Voltage Support 3.3 V */ +#define SDHCI_HTCAPBLT_VS30 (1 << 25) /* Bit 25: Voltage Support 3.0 V */ +#define SDHCI_HTCAPBLT_VS18 (1 << 26) /* Bit 26: Voltage Support 1.8 */ + /* Bits 27-31: Reserved */ +/* Force Event Register */ + +#define SDHCI_FEVT_AC12NE (1 << 0) /* Bit 0: Force Event Auto Command 12 Not Executed */ +#define SDHCI_FEVT_AC12TOE (1 << 1) /* Bit 1: Force Event Auto Command 12 Time Out Error */ +#define SDHCI_FEVT_AC12CE (1 << 2) /* Bit 2: Force Event Auto Command 12 CRC Error */ +#define SDHCI_FEVT_AC12EBE (1 << 3) /* Bit 3: Force Event Auto Command 12 End Bit Error */ +#define SDHCI_FEVT_AC12IE (1 << 4) /* Bit 4: Force Event Auto Command 12 Index Error */ + /* Bits 5-6: Reserved */ +#define SDHCI_FEVT_CNIBAC12E (1 << 7) /* Bit 7: Force Event Command Not Executed By Auto Command 12 Error */ + /* Bits 8-15: Reserved */ +#define SDHCI_FEVT_CTOE (1 << 16) /* Bit 16: Force Event Command Time Out Error */ +#define SDHCI_FEVT_CCE (1 << 17) /* Bit 17: Force Event Command CRC Error */ +#define SDHCI_FEVT_CEBE (1 << 18) /* Bit 18: Force Event Command End Bit Error */ +#define SDHCI_FEVT_CIE (1 << 19) /* Bit 19: Force Event Command Index Error */ +#define SDHCI_FEVT_DTOE (1 << 20) /* Bit 20: Force Event Data Time Out Error */ +#define SDHCI_FEVT_DCE (1 << 21) /* Bit 21: Force Event Data CRC Error */ +#define SDHCI_FEVT_DEBE (1 << 22) /* Bit 22: Force Event Data End Bit Error */ + /* Bit 23: Reserved */ +#define SDHCI_FEVT_AC12E (1 << 24) /* Bit 24: Force Event Auto Command 12 Error */ + /* Bits 25-27: Reserved */ +#define SDHCI_FEVT_DMAE (1 << 28) /* Bit 28: Force Event DMA Error */ + /* Bits 29-30: Reserved */ +#define SDHCI_FEVT_CINT (1 << 31) /* Bit 31: Force Event Card Interrupt */ + +/* ADMA Error Status Register */ + +#define SDHCI_ADMAES_SHIFT (0) /* Bits 0-1: ADMA Error State (when ADMA Error is occurred) */ +#define SDHCI_ADMAES_MASK (3 << SDHCI_ADMAES_ADMAES_SHIFT) +# define SDHCI_ADMAES_STOP (0 << SDHCI_ADMAES_ADMAES_SHIFT) /* Stop DMA */ +# define SDHCI_ADMAES_FDS (1 << SDHCI_ADMAES_ADMAES_SHIFT) /* Fetch descriptor */ +# define SDHCI_ADMAES_CADR (2 << SDHCI_ADMAES_ADMAES_SHIFT) /* Change address */ +# define SDHCI_ADMAES_TFR (3 << SDHCI_ADMAES_ADMAES_SHIFT) /* Transfer data */ +#define SDHCI_ADMAES_LME (1 << 2) /* Bit 2: ADMA Length Mismatch Error */ +#define SDHCI_ADMAES_DCE (1 << 3) /* Bit 3: ADMA Descriptor Error */ + /* Bits 4-31: Reserved */ +/* ADMA System Address Register */ + +#define SDHCI_ADSADDR_SHIFT (1) /* Bits 1-31: ADMA System Address */ +#define SDHCI_ADSADDR_MASK (0xfffffffe) + /* Bits 0-1: Reserved */ + +/* Vendor Specific Register */ + +#define SDHCI_VENDOR_EXTDMAEN (1 << 0) /* Bit 0: External DMA Request Enable */ +#define SDHCI_VENDOR_EXBLKNU (1 << 1) /* Bit 1: Exact block number block read enable for SDIO CMD53 */ + /* Bits 2-15: Reserved */ +#define SDHCI_VENDOR_INTSTVAL_SHIFT (16) /* Bits 16-23: Internal State Value */ +#define SDHCI_VENDOR_INTSTVAL_MASK (0xff << SDHCI_VENDOR_INTSTVAL_SHIFT) + /* Bits 24-31: Reserved */ + +/* User Define1 Control Register */ + +#define SDHCI_UDEF1_SDCLKI_SEL (1 << 0) +#define SDHCI_UDEF1_SDCLKI_SEL_EXT (1 << 0) +#define SDHCI_UDEF1_SDCLKI_SEL_INT (0 << 0) +#define SDHCI_UDEF1_SDCLK_SEL (1 << 1) +#define SDHCI_UDEF1_SDCLK_SEL_EXT (1 << 1) +#define SDHCI_UDEF1_SDCLK_SEL_INT (0 << 1) +#define SDHCI_UDEF1_TAP_SEL_SHIFT (4) +#define SDHCI_UDEF1_TAP_SEL_MASK (0x1f << SDHCI_UDEF1_TAP_SEL_SHIFT) +#define SDHCI_UDEF1_TAP_SEL (1 << 12) +#define SDHCI_UDEF1_TAP_SEL_SW (1 << 12) +#define SDHCI_UDEF1_TAP_SEL_HW (0 << 12) +#define SDHCI_UDEF1_DAT_DLY_BUF (1 << 24) +#define SDHCI_UDEF1_DAT_DLY_BUF_ON (1 << 24) +#define SDHCI_UDEF1_DAT_DLY_BUF_OFF (0 << 24) + +/* User Define2 Control Register */ + +#define SDHCI_UDEF2_CLK_DLY_SHIFT (0) +#define SDHCI_UDEF2_CLK_DLY_MASK (0x7 << SDHCI_UDEF2_CLK_DLY_SHIFT) +#define SDHCI_UDEF2_CMD_EDGE_DET_ON (1 << 4) +#define SDHCI_UDEF2_CMD_EDGE_DET_OFF (0 << 4) +#define SDHCI_UDEF2_DAT_DIR_ACT_HI (0x0 << 8) +#define SDHCI_UDEF2_DAT_DIR_ACT_LOW (0x7 << 8) +#define SDHCI_UDEF2_TTCLK_DIV1 (1 << 16) +#define SDHCI_UDEF2_TTCLK_DIV2 (0 << 16) +#define SDHCI_UDEF2_CLKI_SEL (1 << 20) +#define SDHCI_UDEF2_CLKI_SEL_EXT (1 << 20) +#define SDHCI_UDEF2_CLKI_SEL_INT (0 << 20) +#define SDHCI_UDEF2_CMD_SEL (1 << 24) +#define SDHCI_UDEF2_CMD_SEL_CLKI (1 << 24) +#define SDHCI_UDEF2_CMD_SEL_INT (0 << 24) +#define SDHCI_UDEF2_FORCE_1p8V_EN (1 << 31) + +/**************************************************************************** + * Public Types + ****************************************************************************/ +struct sdio_dev_s; +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + + +/**************************************************************************** + * Name: cxd56_sdhci_initialize + * + * Description: + * Initialize SDIO for operation. + * + * Input Parameters: + * slotno - Not used. + * + * Returned Values: + * A reference to an SDIO interface structure. NULL is returned on failures. + * + ****************************************************************************/ + +FAR struct sdio_dev_s *cxd56_sdhci_initialize(int slotno); + +/**************************************************************************** + * Name: cxd56_sdhci_finalize + * + * Description: + * Finalize SDIO for operation. + * + * Input Parameters: + * slotno - Not used. + * + * Returned Values: + * A reference to an SDIO interface structure. NULL is returned on failures. + * + ****************************************************************************/ + +FAR struct sdio_dev_s *cxd56_sdhci_finalize(int slotno); + +/**************************************************************************** + * Name: cxd56_sdhci_mediachange + * + * Description: + * Called by board-specific logic -- posssible from an interrupt handler -- + * in order to signal to the driver that a card has been inserted or + * removed from the slot + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * + * Returned Values: + * None + * + ****************************************************************************/ +void cxd56_sdhci_mediachange(FAR struct sdio_dev_s *dev); + +/**************************************************************************** + * Name: sdio_wrprotect + * + * Description: + * Called by board-specific logic to report if the card in the slot is + * mechanically write protected. + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * wrprotect - true is a card is writeprotected. + * + * Returned Values: + * None + * + ****************************************************************************/ +void cxd56_sdhci_wrprotect(FAR struct sdio_dev_s *dev, bool wrprotect); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_ARM_SRC_CXD56XX_CXD56_SDHCI_H */ diff --git a/arch/arm/src/cxd56xx/cxd56_usbdev.c b/arch/arm/src/cxd56xx/cxd56_usbdev.c new file mode 100644 index 0000000000..4620a5ae09 --- /dev/null +++ b/arch/arm/src/cxd56xx/cxd56_usbdev.c @@ -0,0 +1,3497 @@ +/**************************************************************************** + * arch/arm/src/cxd56xx/cxd56_usbdev.c + * + * Copyright (C) 2008-2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Copyright 2018 Sony Semiconductor Solutions Corporation + * + * 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 +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "up_internal.h" +#include "cxd56_clock.h" +#include "cxd56_usbdev.h" +#include "hardware/cxd5602_topreg.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* TOPREG VBUS regsiter */ + +#define CLR_EDGE (1 << 9) +#define CLR_EN (1 << 8) +#define VBUS_DET (1 << 0) + +/* Configuration ************************************************************/ + +#ifndef CONFIG_USBDEV_MAXPOWER +# define CONFIG_USBDEV_MAXPOWER 100 /* mA */ +#endif + +/* Vendor ID & Product ID of the USB device */ + +#ifndef CONFIG_CXD56_VENDORID +# define CONFIG_CXD56_VENDORID 0x054c +#endif + +#ifndef CONFIG_CXD56_PRODUCTID +# define CONFIG_CXD56_PRODUCTID 0x0bc2 +#endif + +#ifndef CONFIG_USBDEV_EP0_MAXSIZE +# define CONFIG_USBDEV_EP0_MAXSIZE 64 +#endif + +#ifndef CONFIG_USBDEV_SETUP_MAXDATASIZE +# define CONFIG_USBDEV_SETUP_MAXDATASIZE CONFIG_USBDEV_EP0_MAXSIZE +#endif + +#define CONFIG_DEFAULT_PHY_CFG0 \ + (PHY_STAGSELECT | PHY_HSFALLCNTRL | PHY_IHSTX(0xc) | PHY_INHSRFRED | \ + PHY_INHSIPLUS | PHY_INHSDRVSLEW| PHY_INLFSFBCAP) + +#ifndef __aligned +# define __aligned(x) __attribute__((aligned(x))) +#endif + +/* Debug **********************************************************************/ + +/* Trace error codes */ + +#define CXD56_TRACEERR_ALLOCFAIL 0x0001 +#define CXD56_TRACEERR_ATTACHIRQREG 0x0002 +#define CXD56_TRACEERR_BINDFAILED 0x0003 +#define CXD56_TRACEERR_COREIRQREG 0x0004 +#define CXD56_TRACEERR_DRIVER 0x0005 +#define CXD56_TRACEERR_DRIVERREGISTERED 0x0006 +#define CXD56_TRACEERR_EPREAD 0x0007 +#define CXD56_TRACEERR_EWRITE 0x0008 +#define CXD56_TRACEERR_INVALIDPARMS 0x0009 +#define CXD56_TRACEERR_NOEP 0x000a +#define CXD56_TRACEERR_NOTCONFIGURED 0x000b +#define CXD56_TRACEERR_NULLPACKET 0x000c +#define CXD56_TRACEERR_NULLREQUEST 0x000d +#define CXD56_TRACEERR_REQABORTED 0x000e +#define CXD56_TRACEERR_STALLEDCLRFEATURE 0x000f +#define CXD56_TRACEERR_STALLEDISPATCH 0x0010 +#define CXD56_TRACEERR_STALLEDGETST 0x0011 +#define CXD56_TRACEERR_STALLEDGETSTEP 0x0012 +#define CXD56_TRACEERR_STALLEDGETSTRECIP 0x0013 +#define CXD56_TRACEERR_STALLEDREQUEST 0x0014 +#define CXD56_TRACEERR_STALLEDSETFEATURE 0x0015 +#define CXD56_TRACEERR_TXREQLOST 0x0016 +#define CXD56_TRACEERR_RXREQLOST 0x0017 +#define CXD56_TRACEERR_VBUSIRQREG 0x0018 +#define CXD56_TRACEERR_VBUSNIRQREG 0x0019 + +/* Trace interrupt codes */ + +#define CXD56_TRACEINTID_USB 0x0001 +#define CXD56_TRACEINTID_SYS 0x0002 +#define CXD56_TRACEINTID_VBUS 0x0004 +#define CXD56_TRACEINTID_VBUSN 0x0008 + +#define CXD56_TRACEINTID_RMTWKP 1 +#define CXD56_TRACEINTID_ENUM 2 +#define CXD56_TRACEINTID_SOF 3 +#define CXD56_TRACEINTID_US 4 +#define CXD56_TRACEINTID_UR 5 +#define CXD56_TRACEINTID_ES 6 +#define CXD56_TRACEINTID_SI 7 +#define CXD56_TRACEINTID_SC 8 +#define CXD56_TRACEINTID_GETSTATUS 9 +#define CXD56_TRACEINTID_GETIFDEV 10 +#define CXD56_TRACEINTID_CLEARFEATURE 11 +#define CXD56_TRACEINTID_SETFEATURE 12 +#define CXD56_TRACEINTID_TESTMODE 13 +#define CXD56_TRACEINTID_SETADDRESS 14 +#define CXD56_TRACEINTID_GETSETDESC 15 +#define CXD56_TRACEINTID_GETSETIFCONFIG 16 +#define CXD56_TRACEINTID_SYNCHFRAME 17 +#define CXD56_TRACEINTID_DISPATCH 18 +#define CXD56_TRACEINTID_GETENDPOINT 19 +#define CXD56_TRACEINTID_RESUME 20 +#define CXD56_TRACEINTID_CDCCLEAR 21 +#define CXD56_TRACEINTID_TXDMAERROR 22 +#define CXD56_TRACEINTID_RXDMAERROR 23 +#define CXD56_TRACEINTID_TXBNA 24 +#define CXD56_TRACEINTID_RXBNA 25 +#define CXD56_TRACEINTID_XFERDONE 26 +#define CXD56_TRACEINTID_TXEMPTY 27 +#define CXD56_TRACEINTID_TDC 28 +#define CXD56_TRACEINTID_IN 29 +#define CXD56_TRACEINTID_EPOUTQEMPTY 31 +#define CXD56_TRACEINTID_OUTSETUP 32 +#define CXD56_TRACEINTID_OUTDATA 33 + +#ifdef CONFIG_USBDEV_TRACE_STRINGS +const struct trace_msg_t g_usb_trace_strings_intdecode[] = +{ + TRACE_STR(CXD56_TRACEINTID_RMTWKP), + TRACE_STR(CXD56_TRACEINTID_ENUM), + TRACE_STR(CXD56_TRACEINTID_SOF), + TRACE_STR(CXD56_TRACEINTID_US), + TRACE_STR(CXD56_TRACEINTID_UR), + TRACE_STR(CXD56_TRACEINTID_ES), + TRACE_STR(CXD56_TRACEINTID_SI), + TRACE_STR(CXD56_TRACEINTID_SC), + TRACE_STR(CXD56_TRACEINTID_GETSTATUS), + TRACE_STR(CXD56_TRACEINTID_GETIFDEV), + TRACE_STR(CXD56_TRACEINTID_CLEARFEATURE), + TRACE_STR(CXD56_TRACEINTID_SETFEATURE), + TRACE_STR(CXD56_TRACEINTID_TESTMODE), + TRACE_STR(CXD56_TRACEINTID_SETADDRESS), + TRACE_STR(CXD56_TRACEINTID_GETSETDESC), + TRACE_STR(CXD56_TRACEINTID_GETSETIFCONFIG), + TRACE_STR(CXD56_TRACEINTID_SYNCHFRAME), + TRACE_STR(CXD56_TRACEINTID_DISPATCH), + TRACE_STR(CXD56_TRACEINTID_GETENDPOINT), + TRACE_STR(CXD56_TRACEINTID_RESUME), + TRACE_STR(CXD56_TRACEINTID_CDCCLEAR), + TRACE_STR(CXD56_TRACEINTID_TXDMAERROR), + TRACE_STR(CXD56_TRACEINTID_RXDMAERROR), + TRACE_STR(CXD56_TRACEINTID_TXBNA), + TRACE_STR(CXD56_TRACEINTID_RXBNA), + TRACE_STR(CXD56_TRACEINTID_XFERDONE), + TRACE_STR(CXD56_TRACEINTID_TXEMPTY), + TRACE_STR(CXD56_TRACEINTID_TDC), + TRACE_STR(CXD56_TRACEINTID_IN), + TRACE_STR(CXD56_TRACEINTID_EPOUTQEMPTY), + TRACE_STR(CXD56_TRACEINTID_OUTSETUP), + TRACE_STR(CXD56_TRACEINTID_OUTDATA), + TRACE_STR_END +}; + +const struct trace_msg_t g_usb_trace_strings_deverror[] = +{ + TRACE_STR(CXD56_TRACEERR_ALLOCFAIL), + TRACE_STR(CXD56_TRACEERR_ATTACHIRQREG), + TRACE_STR(CXD56_TRACEERR_BINDFAILED), + TRACE_STR(CXD56_TRACEERR_COREIRQREG), + TRACE_STR(CXD56_TRACEERR_DRIVER), + TRACE_STR(CXD56_TRACEERR_DRIVERREGISTERED), + TRACE_STR(CXD56_TRACEERR_EPREAD), + TRACE_STR(CXD56_TRACEERR_EWRITE), + TRACE_STR(CXD56_TRACEERR_INVALIDPARMS), + TRACE_STR(CXD56_TRACEERR_NOEP), + TRACE_STR(CXD56_TRACEERR_NOTCONFIGURED), + TRACE_STR(CXD56_TRACEERR_NULLPACKET), + TRACE_STR(CXD56_TRACEERR_NULLREQUEST), + TRACE_STR(CXD56_TRACEERR_REQABORTED), + TRACE_STR(CXD56_TRACEERR_STALLEDCLRFEATURE), + TRACE_STR(CXD56_TRACEERR_STALLEDISPATCH), + TRACE_STR(CXD56_TRACEERR_STALLEDGETST), + TRACE_STR(CXD56_TRACEERR_STALLEDGETSTEP), + TRACE_STR(CXD56_TRACEERR_STALLEDGETSTRECIP), + TRACE_STR(CXD56_TRACEERR_STALLEDREQUEST), + TRACE_STR(CXD56_TRACEERR_STALLEDSETFEATURE), + TRACE_STR(CXD56_TRACEERR_TXREQLOST), + TRACE_STR(CXD56_TRACEERR_RXREQLOST), + TRACE_STR(CXD56_TRACEERR_VBUSIRQREG), + TRACE_STR(CXD56_TRACEERR_VBUSNIRQREG), + TRACE_STR_END +}; +#endif + +/* Hardware interface **********************************************************/ + +/* The CXD56 hardware supports 8 configurable endpoints EP1-4, IN and OUT + * (in addition to EP0 IN and OUT). This driver, however, does not exploit + * the full configuratability of the hardware at this time but, instead, + * supports the one interrupt IN, one bulk IN and one bulk OUT endpoint. + */ + +/* Hardware dependent sizes and numbers */ + +#define CXD56_EP0MAXPACKET 64 /* EP0 max packet size */ +#define CXD56_BULKMAXPACKET 512 /* Bulk endpoint max packet */ +#define CXD56_INTRMAXPACKET 64 /* Interrupt endpoint max packet */ +#define CXD56_EP0BUFSIZE 64 /* EP0 max packet size */ +#define CXD56_BULKBUFSIZE 1024 /* Bulk endpoint max packet */ +#define CXD56_INTRBUFSIZE 64 /* Interrupt endpoint max packet */ +#define CXD56_NENDPOINTS 7 /* Includes EP0 */ + +/* Endpoint numbers */ + +#define CXD56_EP0 0 /* Control endpoint */ +#define CXD56_EPBULKIN0 1 /* Bulk EP for send to host */ +#define CXD56_EPBULKOUT0 2 /* Bulk EP for recv to host */ +#define CXD56_EPINTRIN0 3 /* Intr EP for host poll */ +#define CXD56_EPBULKIN1 4 /* Bulk EP for send to host */ +#define CXD56_EPBULKOUT1 5 /* Bulk EP for recv to host */ +#define CXD56_EPINTRIN1 6 /* Intr EP for host poll */ + +/* Request queue operations ****************************************************/ + +#define cxd56_rqempty(ep) ((ep)->head == NULL) +#define cxd56_rqpeek(ep) ((ep)->head) + +#define CXD56_USBDEV_LINELEN 32 +#define CXD56_USBDEV_TIMEOUT 1000 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct cxd56_setup_desc_s +{ + volatile uint32_t status; + volatile uint32_t reserved; + volatile uint32_t setup_1; + volatile uint32_t setup_2; +}; + +struct cxd56_data_desc_s +{ + volatile uint32_t status; + volatile uint32_t reserved; + volatile uint32_t buf; + volatile uint32_t next; +}; + +/* A container for a request so that the request make be retained in a list */ + +struct cxd56_req_s +{ + struct usbdev_req_s req; /* Standard USB request */ + struct cxd56_req_s *flink; /* Supports a singly linked list */ +}; + +/* This is the internal representation of an endpoint */ + +struct cxd56_ep_s +{ + /* Common endpoint fields. This must be the first thing defined in the + * structure so that it is possible to simply cast from struct usbdev_ep_s + * to struct cxd56_ep_s. + */ + + struct usbdev_ep_s ep; /* Standard endpoint structure */ + + /* CXD56-specific fields */ + + struct cxd56_usbdev_s *dev; /* Reference to private driver data */ + struct cxd56_req_s *head; /* Request list for this endpoint */ + struct cxd56_req_s *tail; + struct cxd56_data_desc_s *desc; /* DMA descriptor */ + void *buffer; /* OUT only, receiving data buffer */ + uint8_t epphy; /* Physical EP address/index */ + uint8_t stalled : 1; /* Endpoint is halted */ + uint8_t in : 1; /* Endpoint is IN only */ + uint8_t halted : 1; /* Endpoint feature halted */ + uint8_t txnullpkt : 1; /* Null packet needed at end of transfer */ + uint8_t txwait : 1; /* IN transaction already requested from host */ +}; + +/* This structure encapsulates the overall driver state */ + +struct cxd56_usbdev_s +{ + /* Common device fields. This must be the first thing defined in the + * structure so that it is possible to simply cast from struct usbdev_s + * to struct cxd56_usbdev_s. + */ + + struct usbdev_s usbdev; + + /* The bound device class driver */ + + struct usbdevclass_driver_s *driver; + + /* CXD56-specific fields */ + + uint8_t stalled : 1; /* 1: Protocol stalled */ + uint8_t selfpowered : 1; /* 1: Device is self powered */ + uint8_t paddrset : 1; /* 1: Peripheral addr has been set */ + uint8_t attached : 1; /* 1: Host attached */ + uint8_t paddr; /* Peripheral address */ + uint8_t avail; + + /* E0 SETUP data buffering. + * + * ctrl + * The 8-byte SETUP request is received on the EP0 OUT endpoint and is + * saved. + * + * ep0data + * For OUT SETUP requests, the SETUP data phase must also complete before + * the SETUP command can be processed. + * + * ep0datlen + * Lenght of OUT DATA received in ep0data[] + */ + + struct usb_ctrlreq_s ctrl; /* Last EP0 request */ + + uint8_t ep0data[CONFIG_USBDEV_SETUP_MAXDATASIZE]; + uint16_t ep0datlen; + + /* The endpoint list */ + + struct cxd56_ep_s eplist[CXD56_NENDPOINTS]; + + /* attach status */ + + int state; + int power; + + /* signal */ + + int signo; + int pid; +}; + +/* For maintaining tables of endpoint info */ + +struct cxd56_epinfo_s +{ + uint8_t addr; /* Logical endpoint address */ + uint8_t attr; /* Endpoint attributes */ + uint16_t maxpacket; /* Max packet size */ + uint16_t bufsize; /* Buffer size */ +}; + +/* This structure describes one open "file" */ + +struct cxd56_usbdev_file_s +{ + struct procfs_file_s base; /* Base open file structure */ + unsigned int linesize; /* Number of valid characters in line[] */ + + /* Pre-allocated buffer for formatted lines */ + + char line[CXD56_USBDEV_LINELEN]; +}; + +static struct pm_cpu_freqlock_s g_hv_lock = + PM_CPUFREQLOCK_INIT(PM_CPUFREQLOCK_TAG('U', 'S', 0), PM_CPUFREQLOCK_FLAG_HV); +static struct pm_cpu_wakelock_s g_wake_lock = +{ + .count = 0, + .info = PM_CPUWAKELOCK_TAG('U', 'S', 0), +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Request queue operations *************************************************/ + +static FAR struct cxd56_req_s *cxd56_rqdequeue(FAR struct cxd56_ep_s *privep); +static void cxd56_rqenqueue(FAR struct cxd56_ep_s *privep, + FAR struct cxd56_req_s *req); + +/* Low level data transfers and request operations */ + +static int cxd56_epwrite(FAR struct cxd56_ep_s *privep, FAR uint8_t *buf, + uint16_t nbytes); +static inline void cxd56_abortrequest(FAR struct cxd56_ep_s *privep, + FAR struct cxd56_req_s *privreq, + int16_t result); +static void cxd56_reqcomplete(FAR struct cxd56_ep_s *privep, int16_t result); +static int cxd56_wrrequest(FAR struct cxd56_ep_s *privep); +static int cxd56_rdrequest(FAR struct cxd56_ep_s *privep); +static void cxd56_cancelrequests(FAR struct cxd56_ep_s *privep); +static void cxd56_usbdevreset(FAR struct cxd56_usbdev_s *priv); +static void cxd56_usbreset(FAR struct cxd56_usbdev_s *priv); + +/* Interrupt handling */ + +static FAR struct cxd56_ep_s * + cxd56_epfindbyaddr(FAR struct cxd56_usbdev_s *priv, uint16_t eplog); +static void cxd56_dispatchrequest(FAR struct cxd56_usbdev_s *priv); +static inline void cxd56_ep0setup(FAR struct cxd56_usbdev_s *priv); +static int cxd56_usbinterrupt(int irq, FAR void *context, FAR void *arg); +static int cxd56_sysinterrupt(int irq, FAR void *context, FAR void *arg); +static int cxd56_vbusinterrupt(int irq, FAR void *context, FAR void *arg); +static int cxd56_vbusninterrupt(int irq, FAR void *context, FAR void *arg); + +/* Initialization operations */ + +static inline void cxd56_ep0hwinitialize(FAR struct cxd56_usbdev_s *priv); +static void cxd56_ctrlinitialize(FAR struct cxd56_usbdev_s *priv); +static void cxd56_epinitialize(FAR struct cxd56_usbdev_s *priv); + +/* Un-initialization operations */ + +static void cxd56_usbhwuninit(void); + +/* Endpoint methods */ + +static int cxd56_epconfigure(FAR struct usbdev_ep_s *ep, + FAR const struct usb_epdesc_s *desc, bool last); +static int cxd56_epdisable(FAR struct usbdev_ep_s *ep); +static FAR struct usbdev_req_s *cxd56_epallocreq(FAR struct usbdev_ep_s *ep); +static void cxd56_epfreereq(FAR struct usbdev_ep_s *ep, + FAR struct usbdev_req_s *req); +#ifdef CONFIG_USBDEV_DMA +static FAR void *cxd56_epallocbuffer(FAR struct usbdev_ep_s *ep, + uint16_t nbytes); +static void cxd56_epfreebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf); +#endif +static int cxd56_epsubmit(FAR struct usbdev_ep_s *ep, + FAR struct usbdev_req_s *privreq); +static int cxd56_epcancel(FAR struct usbdev_ep_s *ep, + FAR struct usbdev_req_s *privreq); +static int cxd56_epstall(FAR struct usbdev_ep_s *ep, bool resume); + +/* USB device controller methods */ + +static FAR struct usbdev_ep_s *cxd56_allocep(FAR struct usbdev_s *dev, + uint8_t epno, bool in, + uint8_t eptype); +static void cxd56_freeep(FAR struct usbdev_s *dev, FAR struct usbdev_ep_s *ep); +static int cxd56_getframe(FAR struct usbdev_s *dev); +static int cxd56_wakeup(FAR struct usbdev_s *dev); +static int cxd56_selfpowered(FAR struct usbdev_s *dev, bool selfpowered); +static int cxd56_pullup(FAR struct usbdev_s *dev, bool enable); + +/* Notify USB device attach/detach signal */ + +static void cxd56_notify_signal(uint16_t state, uint16_t power); + +#ifdef CONFIG_FS_PROCFS + +/* procfs methods */ + +static int cxd56_usbdev_open(FAR struct file *filep, FAR const char *relpath, + int oflags, mode_t mode); +static int cxd56_usbdev_close(FAR struct file *filep); +static ssize_t cxd56_usbdev_read(FAR struct file *filep, FAR char *buffer, + size_t buflen); +static int cxd56_usbdev_dup(FAR const struct file *oldp, FAR struct file *newp); +static int cxd56_usbdev_stat(FAR const char *relpath, FAR struct stat *buf); + +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* Endpoint methods */ + +static const struct usbdev_epops_s g_epops = +{ + .configure = cxd56_epconfigure, + .disable = cxd56_epdisable, + .allocreq = cxd56_epallocreq, + .freereq = cxd56_epfreereq, +#ifdef CONFIG_USBDEV_DMA + .allocbuffer = cxd56_epallocbuffer, + .freebuffer = cxd56_epfreebuffer, +#endif + .submit = cxd56_epsubmit, + .cancel = cxd56_epcancel, + .stall = cxd56_epstall, +}; + +/* USB controller device methods */ + +static const struct usbdev_ops_s g_devops = +{ + .allocep = cxd56_allocep, + .freeep = cxd56_freeep, + .getframe = cxd56_getframe, + .wakeup = cxd56_wakeup, + .selfpowered = cxd56_selfpowered, + .pullup = cxd56_pullup, +}; + +/* There is only one, single, pre-allocated instance of the driver structure */ + +static struct cxd56_usbdev_s g_usbdev; + +/* DMA Descriptors for each endpoints */ + +static struct cxd56_setup_desc_s __aligned(4) g_ep0setup; +static struct cxd56_data_desc_s __aligned(4) g_ep0in; +static struct cxd56_data_desc_s __aligned(4) g_ep0out; + +/* Summarizes information about all CXD56 endpoints */ + +static const struct cxd56_epinfo_s g_epinfo[CXD56_NENDPOINTS] = +{ + { + CXD56_EP0, /* EP0 */ + USB_EP_ATTR_XFER_CONTROL, /* Type: Control IN/OUT */ + CXD56_EP0MAXPACKET, /* Max packet size */ + CXD56_EP0BUFSIZE, /* Buffer size */ + }, + { + CXD56_EPBULKIN0 | USB_DIR_IN, /* Logical endpoint number: 1 IN */ + USB_EP_ATTR_XFER_BULK, /* Type: Bulk */ + CXD56_BULKMAXPACKET, /* Max packet size */ + CXD56_BULKBUFSIZE, /* Buffer size */ + }, + { + CXD56_EPBULKOUT0 | USB_DIR_OUT, /* Logical endpoint number: 2 OUT */ + USB_EP_ATTR_XFER_BULK, /* Type: Bulk */ + CXD56_BULKMAXPACKET, /* Max packet size */ + CXD56_BULKBUFSIZE, /* Buffer size */ + }, + { + CXD56_EPINTRIN0 | USB_DIR_IN, /* Logical endpoint number: 3 IN */ + USB_EP_ATTR_XFER_INT, /* Type: Interrupt */ + CXD56_INTRMAXPACKET, /* Max packet size */ + CXD56_INTRBUFSIZE, /* Buffer size */ + }, + { + CXD56_EPBULKIN1 | USB_DIR_IN, /* Logical endpoint number: 4 IN */ + USB_EP_ATTR_XFER_BULK, /* Type: Bulk */ + CXD56_BULKMAXPACKET, /* Max packet size */ + CXD56_BULKBUFSIZE, /* Buffer size */ + }, + { + CXD56_EPBULKOUT1 | USB_DIR_OUT, /* Logical endpoint number: 5 OUT */ + USB_EP_ATTR_XFER_BULK, /* Type: Bulk */ + CXD56_BULKMAXPACKET, /* Max packet size */ + CXD56_BULKBUFSIZE, /* Buffer size */ + }, + { + CXD56_EPINTRIN1 | USB_DIR_IN, /* Logical endpoint number: 6 IN */ + USB_EP_ATTR_XFER_INT, /* Type: Interrupt */ + CXD56_INTRMAXPACKET, /* Max packet size */ + CXD56_INTRBUFSIZE, /* Buffer size */ + }}; + +static uint8_t g_ep0outbuffer[CXD56_EP0MAXPACKET]; + +#ifdef CONFIG_FS_PROCFS + +/* See include/nutts/fs/procfs.h + * We use the old-fashioned kind of initializers so that this will compile + * with any compiler. + */ + +const struct procfs_operations cxd56_usbdev_operations = +{ + cxd56_usbdev_open, /* open */ + cxd56_usbdev_close, /* close */ + cxd56_usbdev_read, /* read */ + NULL, /* write */ + cxd56_usbdev_dup, /* dup */ + + NULL, /* opendir */ + NULL, /* closedir */ + NULL, /* readdir */ + NULL, /* rewinddir */ + + cxd56_usbdev_stat /* stat */ +}; + +# ifdef CONFIG_FS_PROCFS_REGISTER +static const struct procfs_entry_s g_procfs_usbdev = +{ + "usbdev", + &cxd56_usbdev_operations +}; +# endif +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: cxd56_cablestatus + * + * Description: + * Set VBUS connected status to system register + * + ****************************************************************************/ + +static inline void cxd56_cableconnected(bool connected) +{ + uint32_t val; + + val = getreg32(CXD56_TOPREG_USB_VBUS); + if (connected) + { + putreg32(val | VBUS_DET, CXD56_TOPREG_USB_VBUS); + } + else + { + putreg32(val & ~VBUS_DET, CXD56_TOPREG_USB_VBUS); + } +} + +/**************************************************************************** + * Name: cxd56_iscableconnected + * + * Description: + * Return the cable status. (true is connected) + * + ****************************************************************************/ + +static inline bool cxd56_iscableconnected(void) +{ + return getreg32(CXD56_TOPREG_USB_VBUS) & VBUS_DET; +} + +/**************************************************************************** + * Name: cxd56_rqdequeue + * + * Description: + * Remove a request from an endpoint request queue + * + ****************************************************************************/ + +static FAR struct cxd56_req_s *cxd56_rqdequeue(FAR struct cxd56_ep_s *privep) +{ + FAR struct cxd56_req_s *ret = privep->head; + + if (ret) + { + privep->head = ret->flink; + if (!privep->head) + { + privep->tail = NULL; + } + + ret->flink = NULL; + } + + return ret; +} + +/**************************************************************************** + * Name: cxd56_rqenqueue + * + * Description: + * Add a request from an endpoint request queue + * + ****************************************************************************/ + +static void cxd56_rqenqueue(FAR struct cxd56_ep_s *privep, + FAR struct cxd56_req_s *req) +{ + req->flink = NULL; + if (!privep->head) + { + privep->head = req; + privep->tail = req; + } + else + { + privep->tail->flink = req; + privep->tail = req; + } +} + +/**************************************************************************** + * Name: cxd56_epwrite + * + * Description: + * Endpoint write (IN) + * + ****************************************************************************/ + +static int cxd56_epwrite(FAR struct cxd56_ep_s *privep, FAR uint8_t *buf, + uint16_t nbytes) +{ + FAR struct cxd56_data_desc_s *desc; + uint32_t ctrl; + uint8_t epphy = privep->epphy; + + /* Setup IN descriptor */ + + desc = epphy == 0 ? &g_ep0in : privep->desc; + + if (IS_BS_DMA_BUSY(desc)) + { + return 0; + } + + desc->buf = (uint32_t)(uintptr_t)buf; + desc->status = nbytes | DESC_LAST; /* always last descriptor */ + + /* Set Poll bit to ready to send */ + + ctrl = getreg32(CXD56_USB_IN_EP_CONTROL(epphy)); + + /* Send NULL packet request */ + + if (privep->txnullpkt) + { + ctrl |= USB_SENDNULL; + } + + putreg32(ctrl | USB_P | USB_CNAK, CXD56_USB_IN_EP_CONTROL(epphy)); + + return nbytes; +} + +/**************************************************************************** + * Name: cxd56_abortrequest + * + * Description: + * Discard a request + * + ****************************************************************************/ + +static inline void cxd56_abortrequest(FAR struct cxd56_ep_s *privep, + FAR struct cxd56_req_s *privreq, + int16_t result) +{ + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_REQABORTED), (uint16_t)privep->epphy); + + /* Save the result in the request structure */ + + privreq->req.result = result; + + /* Callback to the request completion handler */ + + privreq->req.callback(&privep->ep, &privreq->req); +} + +/**************************************************************************** + * Name: cxd56_reqcomplete + * + * Description: + * Handle termination of a request. + * + ****************************************************************************/ + +static void cxd56_reqcomplete(FAR struct cxd56_ep_s *privep, int16_t result) +{ + FAR struct cxd56_req_s *privreq; + int stalled = privep->stalled; + irqstate_t flags; + + /* Remove the completed request at the head of the endpoint request list */ + + flags = enter_critical_section(); + privreq = cxd56_rqdequeue(privep); + leave_critical_section(flags); + + if (privreq) + { + /* If endpoint 0, temporarily reflect the state of protocol stalled + * in the callback. + */ + + if (privep->epphy == CXD56_EP0) + { + privep->stalled = privep->dev->stalled; + } + + /* Save the result in the request structure */ + + privreq->req.result = result; + + /* Callback to the request completion handler */ + + privreq->flink = NULL; + privreq->req.callback(&privep->ep, &privreq->req); + + /* Restore the stalled indication */ + + privep->stalled = stalled; + } +} + +/**************************************************************************** + * Name: cxd56_txdmacomplete + * + * Description: + * DMA transfer to TxFIFO is completed. + * if exist queued request, do the next transfer request. + * + ****************************************************************************/ + +static void cxd56_txdmacomplete(FAR struct cxd56_ep_s *privep) +{ + FAR struct cxd56_data_desc_s *desc; + FAR struct cxd56_req_s *privreq; + + desc = privep->epphy == CXD56_EP0 ? &g_ep0in : privep->desc; + + /* Avoid invalid transfer by USB Core */ + + DEBUGASSERT(IS_BS_DMA_DONE(desc)); + + desc->status |= DESC_BS_HOST_BUSY; + + privreq = cxd56_rqpeek(privep); + if (!privreq) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_TXREQLOST), privep->epphy); + } + else + { + privreq->req.xfrd += desc->status & DESC_SIZE_MASK; + + if (privreq->req.xfrd >= privreq->req.len && !privep->txnullpkt) + { + usbtrace(TRACE_COMPLETE(privep->epphy), privreq->req.xfrd); + privep->txnullpkt = 0; + cxd56_reqcomplete(privep, OK); + } + } +} + +/**************************************************************************** + * Name: cxd56_wrrequest + * + * Description: + * Send from the next queued write request + * + * Returned Value: + * 0:not finished; 1:completed; <0:error + * + ****************************************************************************/ + +static int cxd56_wrrequest(FAR struct cxd56_ep_s *privep) +{ + FAR struct cxd56_req_s *privreq; + FAR uint8_t *buf; + int nbytes; + int bytesleft; + + /* Check the request from the head of the endpoint request queue */ + + privreq = cxd56_rqpeek(privep); + if (!privreq) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_NULLREQUEST), 0); + return OK; + } + + /* Ignore any attempt to send a zero length packet on anything but EP0IN */ + + if (privreq->req.len == 0) + { + if (privep->epphy == CXD56_EP0) + { + cxd56_epwrite(privep, NULL, 0); + } + else + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_NULLPACKET), 0); + } + return OK; + } + + /* Get the number of bytes left to be sent in the packet */ + + bytesleft = privreq->req.len - privreq->req.xfrd; + + /* Send the next packet if (1) there are more bytes to be sent, or + * (2) the last packet sent was exactly maxpacketsize (bytesleft == 0) + */ + + usbtrace(TRACE_WRITE(privep->epphy), (uint16_t)bytesleft); + if (bytesleft > 0 || privep->txnullpkt) + { + /* Try to send maxpacketsize -- unless we don't have that many + * bytes to send. + */ + + privep->txnullpkt = 0; + if (bytesleft > privep->ep.maxpacket) + { + nbytes = privep->ep.maxpacket; + } + else + { + nbytes = bytesleft; + if ((privreq->req.flags & USBDEV_REQFLAGS_NULLPKT) != 0) + { + privep->txnullpkt = (bytesleft == privep->ep.maxpacket); + } + } + + /* Send the largest number of bytes that we can in this packet */ + + buf = privreq->req.buf + privreq->req.xfrd; + cxd56_epwrite(privep, buf, nbytes); + } + + return OK; +} + +/**************************************************************************** + * Name: cxd56_rxdmacomplete + * + * Description: + * Notify the upper layer and continue to next receive request. + * + ****************************************************************************/ + +static void cxd56_rxdmacomplete(FAR struct cxd56_ep_s *privep) +{ + FAR struct cxd56_data_desc_s *desc = privep->desc; + FAR struct cxd56_req_s *privreq; + uint32_t status = desc->status; + uint16_t nrxbytes; + + nrxbytes = status & DESC_SIZE_MASK; + + privreq = cxd56_rqpeek(privep); + if (!privreq) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_RXREQLOST), privep->epphy); + return; + } + + desc->status = DESC_BS_HOST_BUSY; + + if ((status & DESC_BS_MASK) == DESC_BS_DMA_DONE) + { + privreq->req.xfrd += nrxbytes; + + if (privreq->req.xfrd >= privreq->req.len || + nrxbytes < privep->ep.maxpacket) + { + usbtrace(TRACE_COMPLETE(privep->epphy), privreq->req.xfrd); + cxd56_reqcomplete(privep, OK); + } + } + else + { + uerr("Descriptor status error %08x\n", status); + } + + cxd56_rdrequest(privep); +} + +/**************************************************************************** + * Name: cxd56_rdrequest + * + * Description: + * Receive to the next queued read request + * + ****************************************************************************/ + +static int cxd56_rdrequest(FAR struct cxd56_ep_s *privep) +{ + FAR struct cxd56_data_desc_s *desc = privep->desc; + FAR struct cxd56_req_s *privreq; + uint32_t ctrl; + + /* Check the request from the head of the endpoint request queue */ + + privreq = cxd56_rqpeek(privep); + if (!privreq) + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_EPOUTQEMPTY), 0); + return OK; + } + + /* Receive the next packet */ + + if (!IS_BS_HOST_BUSY(desc)) + { + return OK; + } + + usbtrace(TRACE_READ(privep->epphy), privep->ep.maxpacket); + + desc->buf = (uint32_t)(uintptr_t)privreq->req.buf; + desc->status = privep->ep.maxpacket | DESC_LAST; + + /* Ready to receive next packet */ + + ctrl = getreg32(CXD56_USB_OUT_EP_CONTROL(privep->epphy)); + putreg32(ctrl | USB_RRDY | USB_CNAK, CXD56_USB_OUT_EP_CONTROL(privep->epphy)); + + return OK; +} + +/**************************************************************************** + * Name: cxd56_stopinep + * + * Description: + * Stop IN endpoint forcibly + * + ****************************************************************************/ + +static void cxd56_stopinep(FAR struct cxd56_ep_s *privep) +{ + uint32_t ctrl; + + /* Stop TX */ + + ctrl = getreg32(CXD56_USB_IN_EP_CONTROL(privep->epphy)); + ctrl |= USB_F; + putreg32(ctrl, CXD56_USB_IN_EP_CONTROL(privep->epphy)); +} + +/**************************************************************************** + * Name: cxd56_stopoutep + * + * Description: + * Stop OUT endpoint forcibly + * + ****************************************************************************/ + +static void cxd56_stopoutep(FAR struct cxd56_ep_s *privep) +{ + uint32_t ctrl; + uint32_t stat; + + /* Stop RX if FIFO not empty */ + + stat = getreg32(CXD56_USB_OUT_EP_STATUS(privep->epphy)); + if (stat & USB_INT_MRXFIFOEMPTY) + { + return; + } + + ctrl = getreg32(CXD56_USB_OUT_EP_CONTROL(privep->epphy)); + ctrl |= USB_CLOSEDESC | USB_MRXFLUSH; + putreg32(ctrl, CXD56_USB_OUT_EP_CONTROL(privep->epphy)); +} + +/**************************************************************************** + * Name: cxd56_cancelrequests + * + * Description: + * Cancel all pending requests for an endpoint + * + ****************************************************************************/ + +static void cxd56_cancelrequests(FAR struct cxd56_ep_s *privep) +{ + if (privep->epphy > 0) + { + if (privep->in) + { + cxd56_stopinep(privep); + } + else + { + cxd56_stopoutep(privep); + } + } + + while (!cxd56_rqempty(privep)) + { + usbtrace(TRACE_COMPLETE(privep->epphy), (cxd56_rqpeek(privep))->req.xfrd); + cxd56_reqcomplete(privep, -ESHUTDOWN); + } + + if (privep->epphy > 0) + { + if (privep->in) + { + putreg32(0, CXD56_USB_IN_EP_DATADESC(privep->epphy)); + } + else + { + putreg32(0, CXD56_USB_OUT_EP_DATADESC(privep->epphy)); + } + } +} + +/**************************************************************************** + * Name: cxd56_epfindbyaddr + * + * Description: + * Find the physical endpoint structure corresponding to a logic endpoint + * address + * + ****************************************************************************/ + +static FAR struct cxd56_ep_s * +cxd56_epfindbyaddr(FAR struct cxd56_usbdev_s *priv, uint16_t eplog) +{ + FAR struct cxd56_ep_s *privep; + int i; + + /* Endpoint zero is a special case */ + + if (USB_EPNO(eplog) == 0) + { + return &priv->eplist[0]; + } + + /* Handle the remaining */ + + for (i = 1; i < CXD56_NENDPOINTS; i++) + { + privep = &priv->eplist[i]; + + /* Same logical endpoint number? (includes direction bit) */ + + if (eplog == privep->ep.eplog) + { + /* Return endpoint found */ + + return privep; + } + } + + /* Return endpoint not found */ + + return NULL; +} + +/**************************************************************************** + * Name: cxd56_dispatchrequest + * + * Description: + * Provide unhandled setup actions to the class driver + * + ****************************************************************************/ + +static void cxd56_dispatchrequest(FAR struct cxd56_usbdev_s *priv) +{ + int ret; + + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_DISPATCH), 0); + if (priv && priv->driver) + { + ret = CLASS_SETUP(priv->driver, &priv->usbdev, &priv->ctrl, priv->ep0data, + priv->ep0datlen); + if (ret < 0) + { + /* Stall on failure */ + + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_STALLEDISPATCH), + priv->ctrl.req); + priv->stalled = 1; + } + } +} + +/**************************************************************************** + * Name: cxd56_ep0setup + * + * Description: + * USB Ctrl EP Setup Event + * + ****************************************************************************/ + +static inline void cxd56_ep0setup(FAR struct cxd56_usbdev_s *priv) +{ + FAR struct cxd56_ep_s *ep0 = &priv->eplist[0]; + FAR struct cxd56_req_s *privreq = cxd56_rqpeek(ep0); + FAR struct cxd56_ep_s *privep; + uint16_t index; + uint16_t value; + uint16_t len; + uint32_t reg; + + /* Terminate any pending requests */ + + while (!cxd56_rqempty(ep0)) + { + int16_t result = OK; + if (privreq->req.xfrd != privreq->req.len) + { + result = -EPROTO; + } + + usbtrace(TRACE_COMPLETE(ep0->epphy), privreq->req.xfrd); + cxd56_reqcomplete(ep0, result); + } + + /* Assume NOT stalled */ + + ep0->stalled = 0; + priv->stalled = 0; + + /* Read EP0 SETUP data */ + + memcpy(&priv->ctrl, (void *)&g_ep0setup.setup_1, USB_SIZEOF_CTRLREQ); + memset(&g_ep0setup, 0, USB_SIZEOF_CTRLREQ); + + index = GETUINT16(priv->ctrl.index); + value = GETUINT16(priv->ctrl.value); + len = GETUINT16(priv->ctrl.len); + + uinfo("type=%02x req=%02x value=%04x index=%04x len=%04x\n", + priv->ctrl.type, priv->ctrl.req, value, index, len); + + ep0->in = (priv->ctrl.type & USB_DIR_IN) != 0; + + /* Is this an setup with OUT and data of length > 0 */ + + if (USB_REQ_ISOUT(priv->ctrl.type) && len != priv->ep0datlen) + { + /* At this point priv->ctrl is the setup packet. */ + + return; + } + + /* Dispatch any non-standard requests */ + + if ((priv->ctrl.type & USB_REQ_TYPE_MASK) != USB_REQ_TYPE_STANDARD) + { + cxd56_dispatchrequest(priv); + } + else + { + /* Handle standard request. Pick off the things of interest to the + * USB device controller driver; pass what is left to the class driver + */ + + switch (priv->ctrl.req) + { + case USB_REQ_GETSTATUS: + { + /* type: device-to-host; recipient = device, interface, endpoint + * value: 0 + * index: zero interface endpoint + * len: 2; data = status + */ + + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_GETSTATUS), 0); + + if (len != 2 || (priv->ctrl.type & USB_REQ_DIR_IN) == 0 || value != 0) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_STALLEDGETST), + priv->ctrl.req); + priv->stalled = 1; + } + else + { + switch (priv->ctrl.type & USB_REQ_RECIPIENT_MASK) + { + case USB_REQ_RECIPIENT_ENDPOINT: + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_GETENDPOINT), + 0); + privep = cxd56_epfindbyaddr(priv, index); + if (!privep) + { + usbtrace( + TRACE_DEVERROR(CXD56_TRACEERR_STALLEDGETSTEP), + priv->ctrl.type); + priv->stalled = 1; + } + } + break; + + case USB_REQ_RECIPIENT_DEVICE: + case USB_REQ_RECIPIENT_INTERFACE: + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_GETIFDEV), 0); + break; + + default: + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_STALLEDGETSTRECIP), + priv->ctrl.type); + priv->stalled = 1; + } + break; + } + } + } + break; + + case USB_REQ_CLEARFEATURE: + { + /* type: host-to device; recipient = device, interface or endpoint + * value: feature selector + * index: zero interface endpoint; + * len: zero, data = none + */ + + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_CLEARFEATURE), + (uint16_t)priv->ctrl.req); + if ((priv->ctrl.type & USB_REQ_RECIPIENT_MASK) != + USB_REQ_RECIPIENT_ENDPOINT) + { + cxd56_dispatchrequest(priv); + } + else if (priv->paddrset != 0 && value == USB_FEATURE_ENDPOINTHALT && + len == 0 && + (privep = cxd56_epfindbyaddr(priv, index)) != NULL) + { + privep->halted = 0; + cxd56_epstall(&privep->ep, true); + cxd56_epwrite(ep0, NULL, 0); + } + else + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_STALLEDCLRFEATURE), + priv->ctrl.type); + priv->stalled = 1; + } + } + break; + + case USB_REQ_SETFEATURE: + { + /* type: host-to-device; recipient = device, interface, endpoint + * value: feature selector + * index: zero interface endpoint; + * len: 0; data = none + */ + + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_SETFEATURE), 0); + if (priv->ctrl.type == USB_REQ_RECIPIENT_DEVICE && + value == USB_FEATURE_TESTMODE) + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_TESTMODE), index); + } + else if (priv->ctrl.type != USB_REQ_RECIPIENT_ENDPOINT) + { + cxd56_dispatchrequest(priv); + } + else if (value == USB_FEATURE_ENDPOINTHALT && len == 0 && + (privep = cxd56_epfindbyaddr(priv, index)) != NULL) + { + privep->halted = 1; + } + else + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_STALLEDSETFEATURE), + priv->ctrl.type); + priv->stalled = 1; + } + } + break; + + case USB_REQ_SETADDRESS: + { + /* type: host-to-device; recipient = device + * value: device address + * index: 0 + * len: 0; data = none + */ + + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_SETADDRESS), 0); + priv->paddr = value & 0xff; + } + break; + + case USB_REQ_GETDESCRIPTOR: + /* type: device-to-host; recipient = device + * value: descriptor type and index + * index: 0 or language ID; + * len: descriptor len; data = descriptor + */ + case USB_REQ_SETDESCRIPTOR: + /* type: host-to-device; recipient = device + * value: descriptor type and index + * index: 0 or language ID; + * len: descriptor len; data = descriptor + */ + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_GETSETDESC), 0); + cxd56_dispatchrequest(priv); + } + break; + + case USB_REQ_GETCONFIGURATION: + /* type: device-to-host; recipient = device + * value: 0; + * index: 0; + * len: 1; data = configuration value + */ + case USB_REQ_SETCONFIGURATION: + /* type: host-to-device; recipient = device + * value: configuration value + * index: 0; + * len: 0; data = none + */ + case USB_REQ_GETINTERFACE: + /* type: device-to-host; recipient = interface + * value: 0 + * index: interface; + * len: 1; data = alt interface + */ + case USB_REQ_SETINTERFACE: + /* type: host-to-device; recipient = interface + * value: alternate setting + * index: interface; + * len: 0; data = none + */ + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_GETSETIFCONFIG), 0); + cxd56_dispatchrequest(priv); + } + break; + + case USB_REQ_SYNCHFRAME: + { + /* type: device-to-host; recipient = endpoint + * value: 0 + * index: endpoint; + * len: 2; data = frame number + */ + + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_SYNCHFRAME), 0); + } + break; + + default: + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_STALLEDREQUEST), + priv->ctrl.req); + priv->stalled = 1; + } + break; + } + } + + /* Check if the setup processing resulted in a STALL */ + + if (priv->stalled) + { + reg = getreg32(CXD56_USB_IN_EP_CONTROL(0)); + putreg32(reg | USB_STALL, CXD56_USB_IN_EP_CONTROL(0)); + reg = getreg32(CXD56_USB_OUT_EP_CONTROL(0)); + putreg32(reg | USB_STALL, CXD56_USB_OUT_EP_CONTROL(0)); + } +} + +/**************************************************************************** + * Name: cxd56_epinterrupt + * + * Description: + * Handle USB endpoint interrupts + * + ****************************************************************************/ + +static int cxd56_epinterrupt(int irq, FAR void *context) +{ + FAR struct cxd56_usbdev_s *priv = &g_usbdev; + FAR struct cxd56_ep_s *privep; + uint32_t eps; + uint32_t stat; + uint32_t ctrl; + int n; + + eps = getreg32(CXD56_USB_DEV_EP_INTR); + { + for (n = 0; n < CXD56_NENDPOINTS; n++) + { + /* Determine IN endpoint interrupts */ + + privep = &priv->eplist[n]; + + if (eps & (1 << n)) + { + stat = getreg32(CXD56_USB_IN_EP_STATUS(n)); + + if (stat & USB_INT_RCS) + { + /* Handle Clear_Feature */ + + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_CLEARFEATURE), n); + ctrl = getreg32(CXD56_USB_IN_EP_CONTROL(n)); + putreg32(ctrl | USB_F, CXD56_USB_IN_EP_CONTROL(n)); + putreg32(ctrl | USB_CNAK, CXD56_USB_IN_EP_CONTROL(n)); + ctrl = getreg32(CXD56_USB_IN_EP_CONTROL(n)); + putreg32(USB_INT_RCS, CXD56_USB_IN_EP_STATUS(n)); + + privep->stalled = 0; + privep->halted = 0; + } + + if (stat & USB_INT_RSS) + { + /* Handle Set_Feature */ + + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_SETFEATURE), n); + putreg32(USB_INT_RSS, CXD56_USB_IN_EP_STATUS(n)); + privep->halted = 1; + } + + if (stat & USB_INT_TXEMPTY) + { + /* Transmit FIFO Empty detected */ + + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_TXEMPTY), n); + putreg32(USB_INT_TXEMPTY, CXD56_USB_IN_EP_STATUS(n)); + } + + if (stat & USB_INT_TDC) + { + /* DMA Transmit complete for TxFIFO */ + + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_TDC), n); + putreg32(USB_INT_TDC, CXD56_USB_IN_EP_STATUS(n)); + } + + if (stat & USB_INT_XFERDONE) + { + /* Transfer Done/Transmit FIFO Empty */ + + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_XFERDONE), n); + + /* Set NAK during processing IN request completion */ + + ctrl = getreg32(CXD56_USB_IN_EP_CONTROL(n)); + putreg32(ctrl | USB_SNAK, CXD56_USB_IN_EP_CONTROL(n)); + + putreg32(USB_INT_XFERDONE, CXD56_USB_IN_EP_STATUS(n)); + + cxd56_txdmacomplete(privep); + + /* Clear NAK to raise IN interrupt for send next IN + * packets. + */ + + putreg32(ctrl | USB_CNAK, CXD56_USB_IN_EP_CONTROL(n)); + } + + if (stat & USB_INT_IN) + { + /* Reply NAK for IN token when TxFIFO empty */ + + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_IN), n); + + ctrl = getreg32(CXD56_USB_IN_EP_CONTROL(n)); + putreg32(ctrl | USB_SNAK, CXD56_USB_IN_EP_CONTROL(n)); + + /* If IN request is ready, then send it. */ + + if (!cxd56_rqempty(privep)) + { + cxd56_wrrequest(privep); + } + else + { + privep->txwait = 1; + } + + putreg32(USB_INT_IN, CXD56_USB_IN_EP_STATUS(n)); + } + + if (stat & USB_INT_HE) + { + /* Detect AHB Bus error */ + + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_TXDMAERROR), n); + putreg32(USB_INT_HE, CXD56_USB_IN_EP_STATUS(n)); + } + + if (stat & USB_INT_BNA) + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_TXBNA), n); + putreg32(USB_INT_BNA, CXD56_USB_IN_EP_STATUS(n)); + } + putreg32(1 << n, CXD56_USB_DEV_EP_INTR); + } + + /* Determine OUT endpoint interrupts */ + + if (eps & (1 << (n + 16))) + { + stat = getreg32(CXD56_USB_OUT_EP_STATUS(n)); + + if (USB_INT_OUT(stat) == USB_INT_OUT_SETUP) + { + putreg32(USB_INT_OUT_SETUP, CXD56_USB_OUT_EP_STATUS(n)); + if (n == 0) + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_OUTSETUP), 0); + + ctrl = getreg32(CXD56_USB_OUT_EP_CONTROL(0)); + putreg32(ctrl | USB_SNAK, CXD56_USB_OUT_EP_CONTROL(0)); + + cxd56_ep0setup(priv); + + putreg32(ctrl | USB_CNAK | USB_RRDY, + CXD56_USB_OUT_EP_CONTROL(0)); + + ctrl = getreg32(CXD56_USB_IN_EP_CONTROL(0)); + putreg32(ctrl | USB_CNAK, CXD56_USB_IN_EP_CONTROL(0)); + } + } + + if (USB_INT_OUT(stat) == USB_INT_OUT_DATA) + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_OUTDATA), n); + putreg32(USB_INT_OUT_DATA, CXD56_USB_OUT_EP_STATUS(n)); + if (n == 0) + { + priv->ep0datlen = g_ep0out.status & DESC_SIZE_MASK; + + /* Reset DMA descriptor for next packet */ + + g_ep0out.status = privep->ep.maxpacket | DESC_LAST; + + /* Ready to receive the next SETUP packet */ + + ctrl = getreg32(CXD56_USB_OUT_EP_CONTROL(0)); + putreg32(ctrl | USB_SNAK | USB_RRDY, + CXD56_USB_OUT_EP_CONTROL(0)); + + /* Dispatch setup packet and out transaction */ + + if (priv->ep0datlen > 0) + { + memcpy(priv->ep0data, (const void *)g_ep0out.buf, + priv->ep0datlen); + + if (((priv->ctrl.type & USB_REQ_TYPE_MASK) != + USB_REQ_TYPE_STANDARD) && + USB_REQ_ISOUT(priv->ctrl.type)) + { + cxd56_ep0setup(priv); + priv->ep0datlen = 0; + } + } + } + else + { + cxd56_rxdmacomplete(privep); + } + } + + if (stat & USB_INT_CDC_CLEAR) + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_CDCCLEAR), n); + putreg32(USB_INT_CDC_CLEAR, CXD56_USB_OUT_EP_STATUS(n)); + } + + if (stat & USB_INT_RSS) + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_SETFEATURE), n); + ctrl = getreg32(CXD56_USB_OUT_EP_CONTROL(0)); + putreg32(USB_INT_RSS, CXD56_USB_OUT_EP_STATUS(n)); + privep->halted = 1; + } + + if (stat & USB_INT_RCS) + { + uint32_t status; + + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_CLEARFEATURE), n); + + ctrl = getreg32(CXD56_USB_OUT_EP_CONTROL(n)); + + /* Make sure want to be DMA transfer stopped. + * + * XXX: S bit needs to be clear by hand, it is not found in + * the specification documents. + */ + + ctrl &= ~USB_STALL; + + putreg32(ctrl | USB_CLOSEDESC, CXD56_USB_OUT_EP_CONTROL(n)); + do + { + status = getreg32(CXD56_USB_OUT_EP_STATUS(n)); + } + while (!(status & USB_INT_CDC_CLEAR)); + putreg32(USB_INT_CDC_CLEAR, CXD56_USB_OUT_EP_STATUS(n)); + + if (!(stat & USB_INT_MRXFIFOEMPTY)) + { + /* Flush Recieve FIFO and clear NAK to finish status stage */ + + putreg32(ctrl | USB_MRXFLUSH, CXD56_USB_OUT_EP_CONTROL(n)); + } + putreg32(ctrl | USB_CNAK, CXD56_USB_OUT_EP_CONTROL(n)); + putreg32(USB_INT_RCS, CXD56_USB_OUT_EP_STATUS(n)); + privep->stalled = 0; + privep->halted = 0; + } + + if (stat & USB_INT_HE) + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_RXDMAERROR), n); + putreg32(USB_INT_HE, CXD56_USB_OUT_EP_STATUS(n)); + } + + if (stat & USB_INT_BNA) + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_RXBNA), n); + cxd56_rdrequest(privep); + putreg32(USB_INT_BNA, CXD56_USB_OUT_EP_STATUS(n)); + } + + putreg32(1 << (n + 16), CXD56_USB_DEV_EP_INTR); + } + } + } + + return OK; +} + +/**************************************************************************** + * Name: cxd56_usbinterrupt + * + * Description: + * Handle USB controller core interrupts + * + ****************************************************************************/ + +static int cxd56_usbinterrupt(int irq, FAR void *context, FAR void *arg) +{ + struct usb_ctrlreq_s ctrl; + uint32_t intr; + uint32_t status; + int ret; + + intr = getreg32(CXD56_USB_DEV_INTR); + putreg32(intr, CXD56_USB_DEV_INTR); + + usbtrace(TRACE_INTENTRY(CXD56_TRACEINTID_USB), intr & 0xff); + + /* Set/Clear Remove Wakeup is received by the core */ + + if (intr & USB_INT_RMTWKP_STATE) + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_RMTWKP), 0); + } + + /* Speed enumeration is complete */ + + if (intr & USB_INT_ENUM) + { + FAR struct cxd56_usbdev_s *priv = &g_usbdev; + uint32_t speed; + uint32_t config; + + /* Read established speed type (high or full) */ + + speed = USB_STATUS_SPD(getreg32(CXD56_USB_DEV_STATUS)); + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_ENUM), speed); + + /* Set established speed type to device configuration and device + * instance. + */ + + config = getreg32(CXD56_USB_DEV_CONFIG) & ~USB_CONFIG_SPD_MASK; + if (speed == USB_CONFIG_HS) + { + priv->usbdev.speed = USB_SPEED_HIGH; + config |= USB_CONFIG_HS; + } + else if (speed == USB_CONFIG_FS) + { + priv->usbdev.speed = USB_SPEED_FULL; + config |= USB_CONFIG_FS; + } + putreg32(config, CXD56_USB_DEV_CONFIG); + } + + /* An SOF token is detected */ + + if (intr & USB_INT_SOF) + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_SOF), 0); + } + + /* A suspend state is detected */ + + if (intr & USB_INT_US) + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_US), 0); + } + + /* A USB Reset is detected */ + + if (intr & USB_INT_UR) + { + int i; + + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_UR), 0); + + for (i = 1; i < CXD56_NENDPOINTS; i++) + { + FAR struct cxd56_ep_s *privep = + (FAR struct cxd56_ep_s *)&g_usbdev.eplist[i]; + + cxd56_cancelrequests(privep); + } + + cxd56_pullup(&g_usbdev.usbdev, false); + if (g_usbdev.driver) + { + CLASS_DISCONNECT(g_usbdev.driver, &g_usbdev.usbdev); + } + } + + /* An idle state is detected */ + + if (intr & USB_INT_ES) + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_ES), 0); + } + + /* The device has received a Set_Interface command */ + + if (intr & USB_INT_SI) + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_SI), 0); + status = getreg32(CXD56_USB_DEV_STATUS); + memset(&ctrl, 0, USB_SIZEOF_CTRLREQ); + ctrl.type = USB_REQ_RECIPIENT_INTERFACE; + ctrl.req = USB_REQ_SETINTERFACE; + ctrl.value[0] = USB_STATUS_ALT(status); + ctrl.index[0] = USB_STATUS_INTF(status); + g_usbdev.ctrl = ctrl; + ret = CLASS_SETUP(g_usbdev.driver, &g_usbdev.usbdev, &ctrl, NULL, 0); + if (ret < 0) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_STALLEDISPATCH), + USB_REQ_SETINTERFACE); + g_usbdev.stalled = 1; + } + putreg32(getreg32(CXD56_USB_DEV_CONTROL) | USB_CTRL_CSR_DONE, + CXD56_USB_DEV_CONTROL); + } + + /* The device has received a Set_Configuration command */ + + if (intr & USB_INT_SC) + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_SC), 0); + status = getreg32(CXD56_USB_DEV_STATUS); + memset(&ctrl, 0, USB_SIZEOF_CTRLREQ); + ctrl.req = USB_REQ_SETCONFIGURATION; + ctrl.value[0] = USB_STATUS_CFG(status); + g_usbdev.ctrl = ctrl; + ret = CLASS_SETUP(g_usbdev.driver, &g_usbdev.usbdev, &ctrl, NULL, 0); + if (ret < 0) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_STALLEDISPATCH), + USB_REQ_SETCONFIGURATION); + g_usbdev.stalled = 1; + } + putreg32(getreg32(CXD56_USB_DEV_CONTROL) | USB_CTRL_CSR_DONE, + CXD56_USB_DEV_CONTROL); + } + + /* Handle each EP interrupts */ + + cxd56_epinterrupt(irq, context); + + usbtrace(TRACE_INTEXIT(CXD56_TRACEINTID_USB), 0); + + return OK; +} + +/**************************************************************************** + * Name: cxd56_sysinterrupt + * + * Description: + * + ****************************************************************************/ + +static int cxd56_sysinterrupt(int irq, FAR void *context, FAR void *arg) +{ + FAR struct cxd56_usbdev_s *priv = (FAR struct cxd56_usbdev_s *)arg; + uint32_t status; + + UNUSED(priv); + + usbtrace(TRACE_INTENTRY(CXD56_TRACEINTID_SYS), 0); + + status = getreg32(CXD56_USB_SYS_INTR); + putreg32(status, CXD56_USB_SYS_INTR); + + if (status & USB_INT_RESUME) + { + usbtrace(TRACE_INTDECODE(CXD56_TRACEINTID_RESUME), 0); + } + + usbtrace(TRACE_INTEXIT(CXD56_TRACEINTID_SYS), 0); + + return OK; +} + +/**************************************************************************** + * Name: cxd56_ep0hwinitialize + * + * Description: + * Initialize endpoints. This is logically a part of cxd56_ctrlinitialize + * + ****************************************************************************/ + +static void cxd56_ep0hwinitialize(FAR struct cxd56_usbdev_s *priv) +{ + uint32_t maxp = g_epinfo[0].maxpacket; + uint32_t bufsz = g_epinfo[0].bufsize / 4; + uint32_t status; + + /* Initialize DMA descriptors */ + + memset(&g_ep0setup, 0, sizeof(g_ep0setup)); + memset(&g_ep0in, 0, sizeof(g_ep0in)); + memset(&g_ep0out, 0, sizeof(g_ep0out)); + + g_ep0out.buf = (uint32_t)(uintptr_t)g_ep0outbuffer; + g_ep0out.status = CXD56_EP0MAXPACKET | DESC_LAST; + + putreg32((uint32_t)(uintptr_t)&g_ep0setup, CXD56_USB_OUT_EP_SETUP(0)); + putreg32((uint32_t)(uintptr_t)&g_ep0in, CXD56_USB_IN_EP_DATADESC(0)); + putreg32((uint32_t)(uintptr_t)&g_ep0out, CXD56_USB_OUT_EP_DATADESC(0)); + + /* Clear all interrupts */ + + status = getreg32(CXD56_USB_IN_EP_STATUS(0)); + putreg32(status, CXD56_USB_IN_EP_STATUS(0)); + status = getreg32(CXD56_USB_OUT_EP_STATUS(0)); + putreg32(status, CXD56_USB_OUT_EP_STATUS(0)); + + /* EP0 setup for control */ + + putreg32(maxp, CXD56_USB_IN_EP_MAXPKTSIZE(0)); + putreg32(bufsz, CXD56_USB_IN_EP_BUFSIZE(0)); + putreg32(maxp | (bufsz << 16), CXD56_USB_OUT_EP_BUFSIZE(0)); + putreg32(USB_ET(USB_EP_CONTROL) | USB_F, CXD56_USB_IN_EP_CONTROL(0)); + putreg32(USB_ET(USB_EP_CONTROL) | USB_SNAK, CXD56_USB_OUT_EP_CONTROL(0)); + putreg32(maxp << 19, CXD56_USB_DEV_UDC_EP(0)); +} + +/**************************************************************************** + * Name: cxd56_ctrlinitialize + * + * Description: + * Initialize the CXD56 USB controller for peripheral mode operation . + * + ****************************************************************************/ + +static void cxd56_ctrlinitialize(FAR struct cxd56_usbdev_s *priv) +{ + uint32_t ctrl; + uint32_t config; + + config = USB_CONFIG_CSR_PRG | USB_CONFIG_PI | USB_CONFIG_RWKP; +#ifdef CONFIG_USBDEV_SELFPOWERED + config |= USB_CONFIG_SP; +#endif + putreg32(config, CXD56_USB_DEV_CONFIG); + ctrl = USB_CTRL_SD | USB_CTRL_RES; + putreg32(ctrl, CXD56_USB_DEV_CONTROL); + + /* Polling wait for resumed */ + + while (getreg32(CXD56_USB_DEV_STATUS) & USB_STATUS_SUSP); + + ctrl |= USB_CTRL_MODE | USB_CTRL_RDE | USB_CTRL_TDE; + putreg32(ctrl, CXD56_USB_DEV_CONTROL); +} + +/**************************************************************************** + * Name: cxd56_usbdevreset + * + * Description: + * Reset USB engine + * + ****************************************************************************/ + +static void cxd56_usbdevreset(FAR struct cxd56_usbdev_s *priv) +{ + uint32_t mask; + int i; + int timeout = 0; + + /* Initialize USB Device controller */ + + putreg32(0, CXD56_USB_RESET); + putreg32(1, CXD56_USB_RESET); + putreg32(getreg32(CXD56_USB_PHY_CONFIG1) | PHY_PLLENABLE, + CXD56_USB_PHY_CONFIG1); + + while (!(getreg32(CXD56_USB_SYS_INTR) & USB_INT_READY)) + { + timeout++; + if (timeout > CXD56_USBDEV_TIMEOUT) + { + uinfo("usb reset timeout.\n"); + break; + } + up_mdelay(1); + } + + /* Workaround for recovery from reset to slow issue. + * Wait to recover from usb reset condition, + * until any register value can read correctly. + */ + + while (getreg32(CXD56_USB_DEV_INTR_MASK) == 0) + { + timeout++; + if (timeout > CXD56_USBDEV_TIMEOUT) + { + uinfo("intr mask register timeout.\n"); + break; + } + up_mdelay(1); + } + + putreg32(USB_INT_READY, CXD56_USB_SYS_INTR); + putreg32(1 << 24, CXD56_USB_PJ_DEMAND); /* XXX */ + + cxd56_pullup(&priv->usbdev, false); + + /* Initialize the CXD56 USB controller for DMA mode operation. */ + + cxd56_ctrlinitialize(priv); + + cxd56_ep0hwinitialize(priv); + + for (i = 1; i < CXD56_NENDPOINTS; i++) + { + const struct cxd56_epinfo_s *info = &g_epinfo[i]; + uint32_t stat; + + if (USB_ISEPIN(info->addr)) + { + stat = getreg32(CXD56_USB_IN_EP_STATUS(i)); + putreg32(stat, CXD56_USB_IN_EP_STATUS(i)); + putreg32(info->maxpacket, CXD56_USB_IN_EP_MAXPKTSIZE(i)); + putreg32(info->bufsize / 4, CXD56_USB_IN_EP_BUFSIZE(i)); + putreg32(USB_ET(info->attr) | USB_F, CXD56_USB_IN_EP_CONTROL(i)); + } + else + { + stat = getreg32(CXD56_USB_OUT_EP_STATUS(i)); + putreg32(stat, CXD56_USB_OUT_EP_STATUS(i)); + putreg32(info->maxpacket | ((info->bufsize / 4) << 16), + CXD56_USB_OUT_EP_BUFSIZE(i)); + putreg32(USB_ET(info->attr) | USB_SNAK, CXD56_USB_OUT_EP_CONTROL(i)); + } + } + + /* Enable device interrupts */ + + mask = getreg32(CXD56_USB_DEV_INTR_MASK); + mask &= ~(USB_INT_RMTWKP_STATE | USB_INT_ENUM | USB_INT_UR | USB_INT_SI | + USB_INT_SC); + putreg32(mask, CXD56_USB_DEV_INTR_MASK); + + /* Enable EP0 IN/OUT */ + + mask = getreg32(CXD56_USB_DEV_EP_INTR_MASK); + mask &= ~(1 << 16 | 1); + putreg32(mask, CXD56_USB_DEV_EP_INTR_MASK); +} + +/**************************************************************************** + * Endpoint Methods + ****************************************************************************/ + +/**************************************************************************** + * Name: cxd56_epconfigure + * + * Description: + * Configure endpoint, making it usable + * + * Input Parameters: + * ep - the struct usbdev_ep_s instance obtained from allocep() + * desc - A struct usb_epdesc_s instance describing the endpoint + * last - true if this this last endpoint to be configured. Some hardware + * needs to take special action when all of the endpoints have been + * configured. + * + ****************************************************************************/ + +static int cxd56_epconfigure(FAR struct usbdev_ep_s *ep, + FAR const struct usb_epdesc_s *desc, bool last) +{ + FAR struct cxd56_ep_s *privep = (FAR struct cxd56_ep_s *)ep; + int n; + int eptype; + uint16_t maxpacket; + uint32_t status; + uint32_t udc; + uint32_t addr; + uint32_t ctrl; + + usbtrace(TRACE_EPCONFIGURE, privep->epphy); + DEBUGASSERT(desc->addr == ep->eplog); + + n = privep->epphy; + eptype = desc->attr & USB_EP_ATTR_XFERTYPE_MASK; + maxpacket = GETUINT16(desc->mxpacketsize); + ep->maxpacket = maxpacket; + + status = getreg32(CXD56_USB_DEV_STATUS); + + uinfo("config: EP%d %s %d maxpacket=%d (status: %08x)\n", n, + privep->in ? "IN" : "OUT", eptype, maxpacket, status); + + udc = n; + udc |= privep->in ? (1 << 4) : 0; + udc |= eptype << 5; + udc |= USB_STATUS_CFG(status) << 7; + udc |= USB_STATUS_INTF(status) << 11; + udc |= USB_STATUS_ALT(status) << 15; + udc |= maxpacket << 19; + uinfo("UDC: %08x\n", udc); + + /* This register is write-only (why?) */ + + putreg32(udc, CXD56_USB_DEV_UDC_EP(n)); + + /* Write to UDC EP register takes time, so wait for the USBBusy bit */ + + while (getreg32(CXD56_USB_BUSY)); + + /* Off STALL bit and enable receive */ + + addr = USB_ISEPIN(ep->eplog) ? CXD56_USB_IN_EP_CONTROL(privep->epphy) + : CXD56_USB_OUT_EP_CONTROL(privep->epphy); + ctrl = getreg32(addr); + + putreg32((ctrl & ~USB_STALL), addr); + + privep->stalled = 0; + + /* Clear and setup DMA descriptor */ + + privep->desc->status = DESC_BS_HOST_BUSY; + privep->desc->buf = 0; + + if (privep->in) + { + putreg32((uint32_t)(uintptr_t)privep->desc, + CXD56_USB_IN_EP_DATADESC(privep->epphy)); + } + else + { + putreg32((uint32_t)(uintptr_t)privep->desc, + CXD56_USB_OUT_EP_DATADESC(privep->epphy)); + } + + return OK; +} + +/**************************************************************************** + * Name: cxd56_epdisable + * + * Description: + * The endpoint will no longer be used + * + ****************************************************************************/ + +static int cxd56_epdisable(FAR struct usbdev_ep_s *ep) +{ + FAR struct cxd56_ep_s *privep = (FAR struct cxd56_ep_s *)ep; + irqstate_t flags; + +#ifdef CONFIG_DEBUG_FEATURES + if (!ep) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_INVALIDPARMS), 0); + return -EINVAL; + } +#endif + usbtrace(TRACE_EPDISABLE, privep->epphy); + uinfo("EP%d\n", ((FAR struct cxd56_ep_s *)ep)->epphy); + + /* Cancel any ongoing activity and reset the endpoint */ + + flags = enter_critical_section(); + cxd56_epstall(&privep->ep, false); + cxd56_cancelrequests(privep); + leave_critical_section(flags); + return OK; +} + +/**************************************************************************** + * Name: cxd56_epallocreq + * + * Description: + * Allocate an I/O request + * + ****************************************************************************/ + +static FAR struct usbdev_req_s *cxd56_epallocreq(FAR struct usbdev_ep_s *ep) +{ + FAR struct cxd56_req_s *privreq; + +#ifdef CONFIG_DEBUG_FEATURES + if (!ep) + { + return NULL; + } +#endif + usbtrace(TRACE_EPALLOCREQ, ((FAR struct cxd56_ep_s *)ep)->epphy); + + privreq = (FAR struct cxd56_req_s *)kmm_malloc(sizeof(struct cxd56_req_s)); + if (!privreq) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_ALLOCFAIL), 0); + return NULL; + } + + memset(privreq, 0, sizeof(struct cxd56_req_s)); + return &privreq->req; +} + +/**************************************************************************** + * Name: cxd56_epfreereq + * + * Description: + * Free an I/O request + * + ****************************************************************************/ + +static void cxd56_epfreereq(FAR struct usbdev_ep_s *ep, + FAR struct usbdev_req_s *req) +{ + FAR struct cxd56_req_s *privreq = (FAR struct cxd56_req_s *)req; + +#ifdef CONFIG_DEBUG_FEATURES + if (!ep || !req) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_INVALIDPARMS), 0); + return; + } +#endif + + usbtrace(TRACE_EPFREEREQ, ((FAR struct cxd56_ep_s *)ep)->epphy); + kmm_free(privreq); +} + +/**************************************************************************** + * Name: cxd56_epallocbuffer + * + * Description: + * Allocate an I/O buffer + * + ****************************************************************************/ + +#ifdef CONFIG_USBDEV_DMA +static FAR void *cxd56_epallocbuffer(FAR struct usbdev_ep_s *ep, uint16_t bytes) +{ + FAR struct cxd56_ep_s *privep = (FAR struct cxd56_ep_s *)ep; + + UNUSED(privep); + usbtrace(TRACE_EPALLOCBUFFER, privep->epphy); + + return kmm_malloc(bytes); +} +#endif + +/**************************************************************************** + * Name: cxd56_epfreebuffer + * + * Description: + * Free an I/O buffer + * + ****************************************************************************/ + +#ifdef CONFIG_USBDEV_DMA +static void cxd56_epfreebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf) +{ + FAR struct cxd56_ep_s *privep = (FAR struct cxd56_ep_s *)ep; + + UNUSED(privep); + usbtrace(TRACE_EPFREEBUFFER, privep->epphy); + + kmm_free(buf); +} +#endif + +/**************************************************************************** + * Name: cxd56_epsubmit + * + * Description: + * Submit an I/O request to the endpoint + * + ****************************************************************************/ + +static int cxd56_epsubmit(FAR struct usbdev_ep_s *ep, + FAR struct usbdev_req_s *req) +{ + FAR struct cxd56_req_s *privreq = (FAR struct cxd56_req_s *)req; + FAR struct cxd56_ep_s *privep = (FAR struct cxd56_ep_s *)ep; + FAR struct cxd56_usbdev_s *priv; + uint32_t ctrl; + irqstate_t flags; + int ret = OK; + +#ifdef CONFIG_DEBUG_FEATURES + if (!req || !req->callback || !req->buf || !ep) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_INVALIDPARMS), 0); + return -EINVAL; + } +#endif + usbtrace(TRACE_EPSUBMIT, privep->epphy); + priv = privep->dev; + + if (!priv->driver || priv->usbdev.speed == USB_SPEED_UNKNOWN) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_NOTCONFIGURED), 0); + return -ESHUTDOWN; + } + + req->result = -EINPROGRESS; + req->xfrd = 0; + flags = enter_critical_section(); + + /* If we are stalled, then drop all requests on the floor, except OUT */ + + if (privep->stalled && privep->in) + { + cxd56_abortrequest(privep, privreq, -EBUSY); + ret = -EBUSY; + } + + /* Handle control requests. + * Submit on endpoint 0 is always IN request + */ + + else if (privep->epphy == 0) + { + cxd56_rqenqueue(privep, privreq); + + /* SetConfiguration and SetInterface are handled by hardware, USB device IP + * a utomatically returns NULL packet to host, so I drop this request and + * indicate complete to upper driver. + */ + + if (priv->ctrl.req == USB_REQ_SETCONFIGURATION || + priv->ctrl.req == USB_REQ_SETINTERFACE) + { + /* Nothing to transfer -- exit success, with zero bytes transferred */ + + usbtrace(TRACE_COMPLETE(privep->epphy), privreq->req.xfrd); + cxd56_reqcomplete(privep, OK); + } + + if (priv->ctrl.req == USB_REQ_SETCONFIGURATION) + { + /* Notify attach signal. + * max supply current is returned in response to GET_CONFIGURATION + * from the device. host receives the response and determines the + * supply current value. + */ + + cxd56_notify_signal(USBDEV_STATE_ATTACH, priv->power); + } + + /* Get max supply current value from GET_CONFIGURATION response. + * max supply current value is stored in units of 2 mA. + */ + + if (priv->ctrl.req == USB_REQ_GETDESCRIPTOR && + priv->ctrl.value[1] == USB_DESC_TYPE_CONFIG) + { + FAR struct usb_cfgdesc_s *cfgdesc; + + cfgdesc = (FAR struct usb_cfgdesc_s *)req->buf; + priv->power = cfgdesc->mxpower * 2; + } + + /* If IN transaction has been requested, clear NAK bit to be able + * to raise IN interrupt to start IN packets. + */ + + if (privep->txwait) + { + ctrl = getreg32(CXD56_USB_IN_EP_CONTROL(privep->epphy)); + putreg32(ctrl | USB_CNAK, CXD56_USB_IN_EP_CONTROL(privep->epphy)); + } + } + + /* Handle IN (device-to-host) requests */ + + else if (privep->in) + { + /* Add the new request to the request queue for the IN endpoint */ + + cxd56_rqenqueue(privep, privreq); + usbtrace(TRACE_INREQQUEUED(privep->epphy), privreq->req.len); + + /* If IN transaction has been requested, clear NAK bit to be able + * to raise IN interrupt to start IN packets. + */ + + if (privep->txwait) + { + ctrl = getreg32(CXD56_USB_IN_EP_CONTROL(privep->epphy)); + putreg32(ctrl | USB_CNAK, CXD56_USB_IN_EP_CONTROL(privep->epphy)); + } + } + + /* Handle OUT (host-to-device) requests */ + + else + { + /* Add the new request to the request queue for the OUT endpoint */ + + privep->txnullpkt = 0; + cxd56_rqenqueue(privep, privreq); + usbtrace(TRACE_OUTREQQUEUED(privep->epphy), privreq->req.len); + + /* This there a incoming data pending the availability of a request? */ + + ret = cxd56_rdrequest(privep); + } + + leave_critical_section(flags); + return ret; +} + +/**************************************************************************** + * Name: cxd56_epcancel + * + * Description: + * Cancel an I/O request previously sent to an endpoint + * + ****************************************************************************/ + +static int cxd56_epcancel(FAR struct usbdev_ep_s *ep, + FAR struct usbdev_req_s *req) +{ + FAR struct cxd56_ep_s *privep = (FAR struct cxd56_ep_s *)ep; + irqstate_t flags; + +#ifdef CONFIG_DEBUG_FEATURES + if (!ep || !req) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_INVALIDPARMS), 0); + return -EINVAL; + } +#endif + + usbtrace(TRACE_EPCANCEL, privep->epphy); + + flags = enter_critical_section(); + cxd56_cancelrequests(privep); + leave_critical_section(flags); + return OK; +} + +/**************************************************************************** + * Name: cxd56_epstall + * + * Description: + * Stall or resume and endpoint + * + ****************************************************************************/ + +static int cxd56_epstall(FAR struct usbdev_ep_s *ep, bool resume) +{ + FAR struct cxd56_ep_s *privep = (FAR struct cxd56_ep_s *)ep; + uint32_t ctrl; + uint32_t addr; + + addr = USB_ISEPIN(ep->eplog) ? CXD56_USB_IN_EP_CONTROL(privep->epphy) + : CXD56_USB_OUT_EP_CONTROL(privep->epphy); + + if (resume) + { + usbtrace(TRACE_EPRESUME, privep->epphy); + ctrl = getreg32(addr); + putreg32(ctrl & ~USB_STALL, addr); + privep->stalled = 0; + } + else + { + usbtrace(TRACE_EPSTALL, privep->epphy); + ctrl = getreg32(addr); + putreg32(ctrl | USB_STALL, addr); + privep->stalled = 1; + } + + return OK; +} + +/**************************************************************************** + * Device Methods + ****************************************************************************/ + +static int cxd56_allocepbuffer(FAR struct cxd56_ep_s *privep) +{ + DEBUGASSERT(!privep->desc && !privep->buffer); + DEBUGASSERT(privep->epphy); /* Do not use for EP0 */ + + privep->desc = + (struct cxd56_data_desc_s *)kmm_malloc(sizeof(struct cxd56_data_desc_s)); + if (!privep->desc) + { + return -1; + } + + privep->buffer = NULL; + privep->desc->status = DESC_BS_HOST_BUSY; + privep->desc->buf = 0; + privep->desc->next = 0; + + if (privep->in) + { + putreg32((uint32_t)(uintptr_t)privep->desc, + CXD56_USB_IN_EP_DATADESC(privep->epphy)); + } + else + { + putreg32((uint32_t)(uintptr_t)privep->desc, + CXD56_USB_OUT_EP_DATADESC(privep->epphy)); + } + return 0; +} + +static void cxd56_freeepbuffer(FAR struct cxd56_ep_s *privep) +{ + DEBUGASSERT(privep->epphy); /* Do not use for EP0 */ + + if (privep->in) + { + putreg32(0, CXD56_USB_IN_EP_DATADESC(privep->epphy)); + } + else + { + putreg32(0, CXD56_USB_OUT_EP_DATADESC(privep->epphy)); + } + + if (privep->desc) + { + kmm_free(privep->desc); + privep->desc = NULL; + } + + if (privep->buffer) + { + kmm_free(privep->buffer); + privep->buffer = NULL; + } +} + +/**************************************************************************** + * Name: cxd56_allocep + * + * Description: + * Allocate an endpoint matching the parameters + * + * Input Parameters: + * eplog - 7-bit logical endpoint number (direction bit ignored). Zero means + * that any endpoint matching the other requirements will suffice. The + * assigned endpoint can be found in the eplog field. + * in - true: IN (device-to-host) endpoint requested + * eptype - Endpoint type. One of {USB_EP_ATTR_XFER_ISOC, USB_EP_ATTR_XFER_BULK, + * USB_EP_ATTR_XFER_INT} + * + ****************************************************************************/ + +static FAR struct usbdev_ep_s *cxd56_allocep(FAR struct usbdev_s *dev, + uint8_t eplog, bool in, + uint8_t eptype) +{ + FAR struct cxd56_usbdev_s *priv = (FAR struct cxd56_usbdev_s *)dev; + int ndx; + + usbtrace(TRACE_DEVALLOCEP, eplog); + + /* Ignore any direction bits in the logical address */ + + eplog = USB_EPNO(eplog); + + /* Check all endpoints (except EP0) */ + + for (ndx = 1; ndx < CXD56_NENDPOINTS; ndx++) + { + /* if not used? */ + + if (!(priv->avail & (1 << ndx))) + { + continue; + } + + /* Does this match the endpoint number (if one was provided?) */ + + if (eplog != 0 && eplog != USB_EPNO(priv->eplist[ndx].ep.eplog)) + { + continue; + } + + /* Does the direction match */ + + if (in) + { + if (!USB_ISEPIN(g_epinfo[ndx].addr)) + { + continue; + } + } + else + { + if (!USB_ISEPOUT(g_epinfo[ndx].addr)) + { + continue; + } + } + + /* Does the type match? */ + + if (g_epinfo[ndx].attr == eptype) + { + /* Success! */ + + irqstate_t flags; + uint32_t mask; + + if (cxd56_allocepbuffer(&priv->eplist[ndx]) < 0) + { + continue; + } + + flags = enter_critical_section(); + priv->avail &= ~(1 << ndx); + mask = getreg32(CXD56_USB_DEV_EP_INTR_MASK); + mask &= ~(1 << ndx << (in ? 0 : 16)); + putreg32(mask, CXD56_USB_DEV_EP_INTR_MASK); + leave_critical_section(flags); + return &priv->eplist[ndx].ep; + } + } + + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_NOEP), 0); + return NULL; +} + +/**************************************************************************** + * Name: cxd56_freeep + * + * Description: + * Free the previously allocated endpoint + * + ****************************************************************************/ + +static void cxd56_freeep(FAR struct usbdev_s *dev, FAR struct usbdev_ep_s *ep) +{ + FAR struct cxd56_ep_s *privep = (FAR struct cxd56_ep_s *)ep; + FAR struct cxd56_usbdev_s *pdev = privep->dev; + irqstate_t flags; + + usbtrace(TRACE_DEVFREEEP, (uint16_t)privep->epphy); + + cxd56_freeepbuffer(privep); + + flags = enter_critical_section(); + pdev->avail |= 1 << privep->epphy; + leave_critical_section(flags); +} + +/**************************************************************************** + * Name: cxd56_getframe + * + * Description: + * Returns the current frame number + * + ****************************************************************************/ + +static int cxd56_getframe(FAR struct usbdev_s *dev) +{ + irqstate_t flags; + int ret = 0; + + usbtrace(TRACE_DEVGETFRAME, 0); + +#ifdef CONFIG_DEBUG_FEATURES + if (!dev) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_INVALIDPARMS), 0); + return -ENODEV; + } +#endif + + /* Return the contents of the frame register. Interrupts must be disabled + * because the operation is not atomic. + */ + + flags = enter_critical_section(); + ret = getreg32(CXD56_USB_DEV_STATUS) >> 18; + leave_critical_section(flags); + return ret; +} + +/**************************************************************************** + * Name: cxd56_wakeup + * + * Description: + * Tries to wake up the host connected to this device + * + ****************************************************************************/ + +static int cxd56_wakeup(FAR struct usbdev_s *dev) +{ + irqstate_t flags; + + usbtrace(TRACE_DEVWAKEUP, 0); + + flags = enter_critical_section(); + putreg32(getreg32(CXD56_USB_DEV_CONTROL) | 1, CXD56_USB_DEV_CONTROL); + leave_critical_section(flags); + return OK; +} + +/**************************************************************************** + * Name: cxd56_selfpowered + * + * Description: + * Sets/clears the device selfpowered feature + * + ****************************************************************************/ + +static int cxd56_selfpowered(FAR struct usbdev_s *dev, bool selfpowered) +{ + FAR struct cxd56_usbdev_s *priv = &g_usbdev; + + usbtrace(TRACE_DEVSELFPOWERED, (uint16_t)selfpowered); + +#ifdef CONFIG_DEBUG_FEATURES + if (!dev) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_INVALIDPARMS), 0); + return -ENODEV; + } +#endif + + priv->selfpowered = selfpowered; + return OK; +} + +/**************************************************************************** + * Name: cxd56_pullup + * + * Description: + * Software-controlled connect to/disconnect from USB host + * + ****************************************************************************/ + +static int cxd56_pullup(FAR struct usbdev_s *dev, bool enable) +{ + uint32_t ctrl; + uint32_t ep; + + usbtrace(TRACE_DEVPULLUP, (uint16_t)enable); + + ctrl = getreg32(CXD56_USB_DEV_CONTROL); + ep = getreg32(CXD56_USB_OUT_EP_CONTROL(0)); + + if (enable) + { + ctrl &= ~(USB_CTRL_SD | USB_CTRL_RES); + ep |= USB_RRDY; + } + else + { + ctrl |= USB_CTRL_SD | USB_CTRL_RES; + ep &= USB_RRDY; + } + + putreg32(ctrl, CXD56_USB_DEV_CONTROL); + putreg32(ep, CXD56_USB_OUT_EP_CONTROL(0)); + + return OK; +} + +/**************************************************************************** + * Name: cxd56_epinitialize + * + * Description: + * Initialize all of the endpoint data + * + ****************************************************************************/ + +static void cxd56_epinitialize(FAR struct cxd56_usbdev_s *priv) +{ + int i; + + /* Initialize the device state structure */ + + priv->usbdev.ops = &g_devops; + + /* Set up the standard stuff */ + + memset(&priv->eplist[0], 0, sizeof(struct cxd56_ep_s)); + priv->eplist[0].ep.ops = &g_epops; + priv->eplist[0].dev = priv; + + /* The index, i, is the physical endpoint address; Map this + * to a logical endpoint address usable by the class driver. + */ + + priv->eplist[0].epphy = 0; + priv->eplist[0].ep.eplog = g_epinfo[0].addr; + + /* Setup the endpoint-specific stuff */ + + priv->eplist[0].ep.maxpacket = g_epinfo[0].maxpacket; + + /* Expose only the standard EP0 */ + + priv->usbdev.ep0 = &priv->eplist[0].ep; + + /* Initilialize USB hardware */ + + for (i = 1; i < CXD56_NENDPOINTS; i++) + { + FAR const struct cxd56_epinfo_s *info = &g_epinfo[i]; + FAR struct cxd56_ep_s *privep; + + /* Set up the standard stuff */ + + privep = &priv->eplist[i]; + memset(privep, 0, sizeof(struct cxd56_ep_s)); + privep->ep.ops = &g_epops; + privep->dev = priv; + privep->desc = NULL; + privep->buffer = NULL; + + /* The index, i, is the physical endpoint address; Map this + * to a logical endpoint address usable by the class driver. + */ + + privep->epphy = i; + privep->ep.eplog = info->addr; + + /* Setup the endpoint-specific stuff */ + + privep->ep.maxpacket = g_epinfo[i].maxpacket; + + if (USB_ISEPIN(info->addr)) + { + privep->in = 1; + } + } +} + +/**************************************************************************** + * Name: cxd56_usbhwuninit + ****************************************************************************/ + +static void cxd56_usbhwuninit(void) +{ + /* Un-initilialize USB hardware */ + + putreg32(getreg32(CXD56_USB_PHY_CONFIG1) & ~PHY_PLLENABLE, + CXD56_USB_PHY_CONFIG1); + putreg32(getreg32(CXD56_USB_PJ_DEMAND) & ~(1 << 24), CXD56_USB_PJ_DEMAND); + + /* USB Device Reset */ + + putreg32(0, CXD56_USB_RESET); +} + +/**************************************************************************** + * Name: cxd56_vbusinterrupt + ****************************************************************************/ + +static int cxd56_vbusinterrupt(int irq, FAR void *context, FAR void *arg) +{ + FAR struct cxd56_usbdev_s *priv = (FAR struct cxd56_usbdev_s *)arg; + + cxd56_cableconnected(true); + + usbtrace(TRACE_INTENTRY(CXD56_TRACEINTID_VBUS), 0); + uinfo("irq=%d context=%08x\n", irq, context); + + /* Toggle vbus interrupts */ + + up_disable_irq(CXD56_IRQ_USB_VBUS); + up_enable_irq(CXD56_IRQ_USB_VBUSN); + + /* Enable interrupts */ + + up_enable_irq(CXD56_IRQ_USB_SYS); + up_enable_irq(CXD56_IRQ_USB_INT); + + /* reconstruct Endpoints and restart Configuration */ + + if (priv->driver) + { + cxd56_usbreset(priv); + } + + /* Notify attach signal. + * if class driver not binded, can't get supply curret value. + */ + + if (!priv->driver) + { + cxd56_notify_signal(USBDEV_STATE_ATTACH, 0); + } + + return OK; +} + +/**************************************************************************** + * Name: cxd56_vbusninterrupt + ****************************************************************************/ + +static int cxd56_vbusninterrupt(int irq, FAR void *context, FAR void *arg) +{ + FAR struct cxd56_usbdev_s *priv = (FAR struct cxd56_usbdev_s *)arg; + FAR struct cxd56_ep_s *privep; + int i; + + cxd56_cableconnected(false); + + usbtrace(TRACE_INTENTRY(CXD56_TRACEINTID_VBUSN), 0); + + uinfo("irq=%d context=%08x\n", irq, context); + + /* Toggle vbus interrupts */ + + up_disable_irq(CXD56_IRQ_USB_VBUSN); + up_enable_irq(CXD56_IRQ_USB_VBUS); + + /* Disconnect device */ + + for (i = 1; i < CXD56_NENDPOINTS; i++) + { + privep = (FAR struct cxd56_ep_s *)&priv->eplist[i]; + + cxd56_epstall(&privep->ep, false); + cxd56_cancelrequests(privep); + } + + if (g_usbdev.driver) + { + CLASS_DISCONNECT(priv->driver, &priv->usbdev); + } + + /* Disable USB_INT interrupt */ + + up_disable_irq(CXD56_IRQ_USB_INT); + up_disable_irq(CXD56_IRQ_USB_SYS); + + /* Notify dettach signal */ + + priv->power = 0; + cxd56_notify_signal(USBDEV_STATE_DETACH, priv->power); + + return OK; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_usbinitialize + * + * Description: + * Initialize USB hardware + * + ****************************************************************************/ + +void up_usbinitialize(void) +{ + usbtrace(TRACE_DEVINIT, 0); + + /* Enable USB clock */ + + cxd56_usb_clock_enable(); + + if (irq_attach(CXD56_IRQ_USB_SYS, cxd56_sysinterrupt, &g_usbdev) != 0) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_ATTACHIRQREG), 0); + goto errout; + } + + if (irq_attach(CXD56_IRQ_USB_INT, cxd56_usbinterrupt, &g_usbdev) != 0) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_COREIRQREG), 0); + goto errout; + } + + if (irq_attach(CXD56_IRQ_USB_VBUS, cxd56_vbusinterrupt, &g_usbdev) != 0) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_VBUSIRQREG), 0); + goto errout; + } + + if (irq_attach(CXD56_IRQ_USB_VBUSN, cxd56_vbusninterrupt, &g_usbdev) != 0) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_VBUSNIRQREG), 0); + goto errout; + } + + /* Initialize driver instance */ + + memset(&g_usbdev, 0, sizeof(struct cxd56_usbdev_s)); + g_usbdev.avail = 0xff; + + /* Initialize endpoint data */ + + cxd56_epinitialize(&g_usbdev); + + /* Enable interrupts */ + + up_enable_irq(CXD56_IRQ_USB_VBUS); + + return; + +errout: + up_usbuninitialize(); +} + +/**************************************************************************** + * Name: up_usbuninitialize + ****************************************************************************/ + +void up_usbuninitialize(void) +{ + FAR struct cxd56_usbdev_s *priv = &g_usbdev; + irqstate_t flags; + + usbtrace(TRACE_DEVUNINIT, 0); + if (priv->driver) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_DRIVERREGISTERED), 0); + usbdev_unregister(priv->driver); + } + + flags = enter_critical_section(); + cxd56_pullup(&priv->usbdev, false); + priv->usbdev.speed = USB_SPEED_UNKNOWN; + + /* Disable and detach IRQs */ + + up_disable_irq(CXD56_IRQ_USB_INT); + up_disable_irq(CXD56_IRQ_USB_SYS); + up_disable_irq(CXD56_IRQ_USB_VBUS); + up_disable_irq(CXD56_IRQ_USB_VBUSN); + + irq_detach(CXD56_IRQ_USB_INT); + irq_detach(CXD56_IRQ_USB_SYS); + irq_detach(CXD56_IRQ_USB_VBUS); + irq_detach(CXD56_IRQ_USB_VBUSN); + + cxd56_usb_clock_disable(); + leave_critical_section(flags); + + /* Clear signal */ + + priv->signo = 0; + priv->pid = 0; +} + +/************************************************************************************ + * Name: usbdevclass_register + * + * Description: + * Register a USB device class driver. The class driver's bind() method will be + * called to bind it to a USB device driver. + * + ************************************************************************************/ + +int usbdev_register(FAR struct usbdevclass_driver_s *driver) +{ + int ret; + + usbtrace(TRACE_DEVREGISTER, 0); + +#ifdef CONFIG_DEBUG_FEATURES + if (!driver || !driver->ops->bind || !driver->ops->unbind || + !driver->ops->setup) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_INVALIDPARMS), 0); + return -EINVAL; + } + + if (g_usbdev.driver) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_DRIVER), 0); + return -EBUSY; + } +#endif + + /* Take freqlock to keep clock faster */ + + up_pm_acquire_freqlock(&g_hv_lock); + up_pm_acquire_wakelock(&g_wake_lock); + + /* Hook up the driver */ + + g_usbdev.driver = driver; + + /* Then bind the class driver */ + + ret = CLASS_BIND(driver, &g_usbdev.usbdev); + if (ret) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_BINDFAILED), (uint16_t)-ret); + g_usbdev.driver = NULL; + return ret; + } + + /* Enable interrupts */ + + up_enable_irq(CXD56_IRQ_USB_VBUS); + + return OK; +} + +/************************************************************************************ + * Name: usbdev_unregister + * + * Description: + * Un-register usbdev class driver.If the USB device is connected to a USB + * host, it will first disconnect(). The driver is also requested to unbind() + * and clean up any device state, before this procedure finally returns. + * + ************************************************************************************/ + +int usbdev_unregister(FAR struct usbdevclass_driver_s *driver) +{ + FAR struct cxd56_usbdev_s *priv = &g_usbdev; + irqstate_t flags; + + usbtrace(TRACE_DEVUNREGISTER, 0); + +#ifdef CONFIG_DEBUG_FEATURES + if (driver != g_usbdev.driver) + { + usbtrace(TRACE_DEVERROR(CXD56_TRACEERR_INVALIDPARMS), 0); + return -EINVAL; + } +#endif + + /* Unbind the class driver */ + + CLASS_UNBIND(driver, &g_usbdev.usbdev); + + flags = enter_critical_section(); + + /* Disable IRQs */ + + up_disable_irq(CXD56_IRQ_USB_INT); + up_disable_irq(CXD56_IRQ_USB_SYS); + + /* Disconnect device */ + + cxd56_pullup(&priv->usbdev, false); + priv->usbdev.speed = USB_SPEED_UNKNOWN; + + /* Unhook the driver */ + + g_usbdev.driver = NULL; + + /* Un-initialize USB hardware */ + + cxd56_usbhwuninit(); + + leave_critical_section(flags); + + up_pm_release_freqlock(&g_hv_lock); + up_pm_release_wakelock(&g_wake_lock); + + return OK; +} + +/************************************************************************************ + * Name: cxd56_usbreset + * + * Description: + * Reinitialize the endpoint and restore the EP configuration + * before disconnecting the host. Then start the Configuration again. + * + ************************************************************************************/ + +static void cxd56_usbreset(FAR struct cxd56_usbdev_s *priv) +{ + uint32_t mask; + int i; + + /* USB reset assert */ + + cxd56_usbdevreset(priv); + + /* Check all endpoints (except EP0) */ + + for (i = 1; i < CXD56_NENDPOINTS; i++) + { + /* skip unused EP */ + + if (priv->avail & (1 << i)) + { + continue; + } + + mask = getreg32(CXD56_USB_DEV_EP_INTR_MASK); + mask &= ~(1 << i << (priv->eplist[i].in ? 0 : 16)); + putreg32(mask, CXD56_USB_DEV_EP_INTR_MASK); + + /* DMA descripter setting */ + + priv->eplist[i].buffer = NULL; + priv->eplist[i].desc->status = DESC_BS_HOST_BUSY; + priv->eplist[i].desc->buf = 0; + priv->eplist[i].desc->next = 0; + + if (priv->eplist[i].in) + { + putreg32((uint32_t)(uintptr_t)priv->eplist[i].desc, + CXD56_USB_IN_EP_DATADESC(priv->eplist[i].epphy)); + } + else + { + putreg32((uint32_t)(uintptr_t)priv->eplist[i].desc, + CXD56_USB_OUT_EP_DATADESC(priv->eplist[i].epphy)); + } + + /* resume EP stall */ + + cxd56_epstall(&priv->eplist[i].ep, true); + } + + cxd56_pullup(&priv->usbdev, true); +} + +/**************************************************************************** + * Name: cxd56_usbdev_setsigno + ****************************************************************************/ + +int cxd56_usbdev_setsigno(int signo) +{ + FAR struct cxd56_usbdev_s *priv = &g_usbdev; + + uinfo("signo = %d\n", signo); + + priv->signo = signo; + priv->pid = getpid(); + + return OK; +} + +/**************************************************************************** + * Name: cxd56_notify_signal + * + * Description: + * Notify the application of USB attach/detach event + * + ****************************************************************************/ + +static void cxd56_notify_signal(uint16_t state, uint16_t power) +{ + FAR struct cxd56_usbdev_s *priv = &g_usbdev; + + if (priv->signo > 0) + { +#ifdef CONFIG_CAN_PASS_STRUCTS + union sigval value; + value.sival_int = state << 16 | power; + (void)sigqueue(priv->pid, priv->signo, value); +#else + (void)sigqueue(priv->pid, priv->signo, state << 16 | power); +#endif + } +} + +#ifdef CONFIG_FS_PROCFS + +/**************************************************************************** + * Name: cxd56_usbdev_open + ****************************************************************************/ + +static int cxd56_usbdev_open(FAR struct file *filep, FAR const char *relpath, + int oflags, mode_t mode) +{ + FAR struct cxd56_usbdev_file_s *priv; + + uinfo("Open '%s'\n", relpath); + + /* PROCFS is read-only. Any attempt to open with any kind of write + * access is not permitted. + * + * REVISIT: Write-able proc files could be quite useful. + */ + + if (((oflags & O_WRONLY) != 0 || (oflags & O_RDONLY) == 0)) + { + uerr("ERROR: Only O_RDONLY supported\n"); + return -EACCES; + } + + /* Allocate the open file structure */ + + priv = (FAR struct cxd56_usbdev_file_s *)kmm_zalloc( + sizeof(struct cxd56_usbdev_file_s)); + if (!priv) + { + uerr("ERROR: Failed to allocate file attributes\n"); + return -ENOMEM; + } + + /* Save the open file structure as the open-specific state in + * filep->f_priv. + */ + + filep->f_priv = (FAR void *)priv; + return OK; +} + +/**************************************************************************** + * Name: modprocfs_close + ****************************************************************************/ + +static int cxd56_usbdev_close(FAR struct file *filep) +{ + FAR struct cxd56_usbdev_file_s *priv; + + /* Recover our private data from the struct file instance */ + + priv = (FAR struct cxd56_usbdev_file_s *)filep->f_priv; + DEBUGASSERT(priv); + + /* Release the file attributes structure */ + + kmm_free(priv); + filep->f_priv = NULL; + return OK; +} + +/**************************************************************************** + * Name: cxd56_usbdev_read + ****************************************************************************/ + +static ssize_t cxd56_usbdev_read(FAR struct file *filep, FAR char *buffer, + size_t buflen) +{ + FAR struct cxd56_usbdev_file_s *attr; + FAR struct cxd56_usbdev_s *priv = &g_usbdev; + off_t offset; + int ret; + + uinfo("buffer=%p buflen=%lu\n", buffer, (unsigned long)buflen); + + /* Recover our private data from the struct file instance */ + + attr = (FAR struct cxd56_usbdev_file_s *)filep->f_priv; + DEBUGASSERT(attr); + + /* Traverse all installed modules */ + + attr->linesize = snprintf(attr->line, CXD56_USBDEV_LINELEN, "%-12s%d mA\n", + "Power:", priv->power); + + /* Transfer the system up time to user receive buffer */ + + offset = filep->f_pos; + ret = procfs_memcpy(attr->line, attr->linesize, buffer, buflen, &offset); + + /* Update the file offset */ + + if (ret > 0) + { + filep->f_pos += ret; + } + + return ret; +} + +/**************************************************************************** + * Name: cxd56_usbdev_dup + ****************************************************************************/ + +static int cxd56_usbdev_dup(FAR const struct file *oldp, FAR struct file *newp) +{ + FAR struct cxd56_usbdev_file_s *oldattr; + FAR struct cxd56_usbdev_file_s *newattr; + + uinfo("Dup %p->%p\n", oldp, newp); + + /* Recover our private data from the old struct file instance */ + + oldattr = (FAR struct cxd56_usbdev_file_s *)oldp->f_priv; + DEBUGASSERT(oldattr); + + /* Allocate a new container to hold the task and attribute selection */ + + newattr = (FAR struct cxd56_usbdev_file_s *)kmm_malloc( + sizeof(struct cxd56_usbdev_file_s)); + if (!newattr) + { + uerr("ERROR: Failed to allocate file attributes\n"); + return -ENOMEM; + } + + /* The copy the file attributes from the old attributes to the new */ + + memcpy(newattr, oldattr, sizeof(struct cxd56_usbdev_file_s)); + + /* Save the new attributes in the new file structure */ + + newp->f_priv = (FAR void *)newattr; + return OK; +} + +/**************************************************************************** + * Name: cxd56_usbdev_stat + ****************************************************************************/ + +static int cxd56_usbdev_stat(FAR const char *relpath, FAR struct stat *buf) +{ + buf->st_mode = S_IFREG | S_IROTH | S_IRGRP | S_IRUSR; + buf->st_size = 0; + buf->st_blksize = 0; + buf->st_blocks = 0; + return OK; +} + +/**************************************************************************** + * Name: cxd56_usbdev_procfs_register + * + * Description: + * Register the usbdev procfs file system entry + * + ****************************************************************************/ + +#ifdef CONFIG_FS_PROCFS_REGISTER +int cxd56_usbdev_procfs_register(void) +{ + return procfs_register(&g_procfs_usbdev); +} +#endif + +#endif diff --git a/arch/arm/src/cxd56xx/cxd56_usbdev.h b/arch/arm/src/cxd56xx/cxd56_usbdev.h new file mode 100644 index 0000000000..14330071a9 --- /dev/null +++ b/arch/arm/src/cxd56xx/cxd56_usbdev.h @@ -0,0 +1,292 @@ +/**************************************************************************** + * arch/arm/src/cxd56xx/cxd56_usbdev.h + * + * Copyright (C) 2008-2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Copyright 2018 Sony Semiconductor Solutions Corporation + * + * 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 of Sony Semiconductor Solutions Corporation 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 __ARCH_ARM_SRC_CXD56XX_CXD56_USB_H +#define __ARCH_ARM_SRC_CXD56XX_CXD56_USB_H + +/******************************************************************************************** + * Included Files + ********************************************************************************************/ + +#include + +/******************************************************************************************** + * Pre-processor Definitions + ********************************************************************************************/ + +/* Register offsets *************************************************************************/ +/* Common Register Offsets */ + +#define CXD56_USB_IN_EP_CONTROL(x) (CXD56_USBDEV_BASE + 0x0000 + ((x) * 0x20)) +#define CXD56_USB_IN_EP_STATUS(x) (CXD56_USBDEV_BASE + 0x0004 + ((x) * 0x20)) +#define CXD56_USB_IN_EP_BUFSIZE(x) (CXD56_USBDEV_BASE + 0x0008 + ((x) * 0x20)) +#define CXD56_USB_IN_EP_MAXPKTSIZE(x) (CXD56_USBDEV_BASE + 0x000c + ((x) * 0x20)) +#define CXD56_USB_IN_EP_DATADESC(x) (CXD56_USBDEV_BASE + 0x0014 + ((x) * 0x20)) + +#define CXD56_USB_OUT_EP_CONTROL(x) (CXD56_USBDEV_BASE + 0x0200 + ((x) * 0x20)) +#define CXD56_USB_OUT_EP_STATUS(x) (CXD56_USBDEV_BASE + 0x0204 + ((x) * 0x20)) +#define CXD56_USB_OUT_EP_BUFSIZE(x) (CXD56_USBDEV_BASE + 0x020c + ((x) * 0x20)) +#define CXD56_USB_OUT_EP_SETUP(x) (CXD56_USBDEV_BASE + 0x0210 + ((x) * 0x20)) +#define CXD56_USB_OUT_EP_DATADESC(x) (CXD56_USBDEV_BASE + 0x0214 + ((x) * 0x20)) + +#define CXD56_USB_DEV_CONFIG (CXD56_USBDEV_BASE + 0x0400) +#define CXD56_USB_DEV_CONTROL (CXD56_USBDEV_BASE + 0x0404) +#define CXD56_USB_DEV_STATUS (CXD56_USBDEV_BASE + 0x0408) +#define CXD56_USB_DEV_INTR (CXD56_USBDEV_BASE + 0x040c) +#define CXD56_USB_DEV_INTR_MASK (CXD56_USBDEV_BASE + 0x0410) +#define CXD56_USB_DEV_EP_INTR (CXD56_USBDEV_BASE + 0x0414) +#define CXD56_USB_DEV_EP_INTR_MASK (CXD56_USBDEV_BASE + 0x0418) + +#define CXD56_USB_DEV_UDC_EP0 (CXD56_USBDEV_BASE + 0x0504) +#define CXD56_USB_DEV_UDC_EP1 (CXD56_USBDEV_BASE + 0x0508) +#define CXD56_USB_DEV_UDC_EP2 (CXD56_USBDEV_BASE + 0x050c) +#define CXD56_USB_DEV_UDC_EP3 (CXD56_USBDEV_BASE + 0x0510) +#define CXD56_USB_DEV_UDC_EP4 (CXD56_USBDEV_BASE + 0x0514) +#define CXD56_USB_DEV_UDC_EP5 (CXD56_USBDEV_BASE + 0x0518) +#define CXD56_USB_DEV_UDC_EP6 (CXD56_USBDEV_BASE + 0x051c) +#define CXD56_USB_DEV_UDC_EP(x) (CXD56_USB_DEV_UDC_EP0 + ((x) * 4)) + +#define CXD56_USB_SYS_INTR (CXD56_USBDEV_BASE + 0x0800) +#define CXD56_USB_SYS_INTR_MASK (CXD56_USBDEV_BASE + 0x0804) +#define CXD56_USB_BUSY (CXD56_USBDEV_BASE + 0x0808) +#define CXD56_USB_VBUS_CTRL (CXD56_USBDEV_BASE + 0x080c) +#define CXD56_USB_RESET (CXD56_USBDEV_BASE + 0x0810) + +#define CXD56_USB_SUSPEND_MASK (CXD56_USBDEV_BASE + 0x081c) + +#define CXD56_USB_PJ_DEMAND (CXD56_USBDEV_BASE + 0x0830) + +#define CXD56_USB_PHY_CONFIG0 (CXD56_USBDEV_BASE + 0x083c) +#define CXD56_USB_PHY_CONFIG1 (CXD56_USBDEV_BASE + 0x0840) +#define CXD56_USB_PHY_CONFIG2 (CXD56_USBDEV_BASE + 0x0844) + +/* EP types */ + +#define USB_EP_CONTROL 0 +#define USB_EP_ISOCHRONOUS 1 +#define USB_EP_BULK 2 +#define USB_EP_INTERRUPT 3 + +/* EP control bits */ + +#define USB_MRXFLUSH (1<<12) +#define USB_CLOSEDESC (1<<11) +#define USB_SENDNULL (1<<10) +#define USB_RRDY (1<<9) +#define USB_CNAK (1<<8) +#define USB_SNAK (1<<7) +#define USB_NAK (1<<6) +#define USB_ET(x) ((x)<<4) +#define USB_P (1<<3) +#define USB_SN (1<<2) +#define USB_F (1<<1) +#define USB_STALL (1<<0) + +/* USB device configuration */ + +#define USB_CONFIG_DDR (1<<19) +#define USB_CONFIG_SET_DESC (1<<18) +#define USB_CONFIG_CSR_PRG (1<<17) +#define USB_CONFIG_HALT_STATUS (1<<16) +#define USB_CONFIG_HS_TIMEOUT_CALIB(x) (((x)&7)<<13) +#define USB_CONFIG_FS_TIMEOUT_CALIB(x) (((x)&7)<<10) +#define USB_CONFIG_PHY_ERROR_DETECT (1<<9) +#define USB_CONFIG_STATUS_1 (1<<8) +#define USB_CONFIG_STATUS (1<<7) +#define USB_CONFIG_DIR (1<<6) +#define USB_CONFIG_PI (1<<5) +#define USB_CONFIG_SS (1<<4) +#define USB_CONFIG_SP (1<<3) +#define USB_CONFIG_RWKP (1<<2) +#define USB_CONFIG_SPD(x) (((x)&3)) +#define USB_CONFIG_HS 0 +#define USB_CONFIG_FS 1 +#define USB_CONFIG_SPD_MASK 3 + +/* USB device control */ + +#define USB_CTRL_THLEN(x) (((x)&0xff)<<24) +#define USB_CTRL_BRLEN(x) (((x)&0xff)<<16) +#define USB_CTRL_SRXFLUSH (1<<14) +#define USB_CTRL_CSR_DONE (1<<13) +#define USB_CTRL_DEVNAK (1<<12) +#define USB_CTRL_SCALE (1<<11) +#define USB_CTRL_SD (1<<10) +#define USB_CTRL_MODE (1<<9) +#define USB_CTRL_BREN (1<<8) +#define USB_CTRL_THE (1<<7) +#define USB_CTRL_BF (1<<6) +#define USB_CTRL_BE (1<<5) +#define USB_CTRL_DU (1<<4) +#define USB_CTRL_TDE (1<<3) +#define USB_CTRL_RDE (1<<2) +#define USB_CTRL_RES (1<<0) + +/* USB device status bits */ + +#define USB_STATUS_RMTWKP_STATE (1<<17) +#define USB_STATUS_PHYERROR (1<<16) +#define USB_STATUS_RXFIFOEMPTY (1<<15) +#define USB_STATUS_SPD_SHIFT 13 +#define USB_STATUS_SPD_MASK (3<> USB_STATUS_SPD_SHIFT) +#define USB_STATUS_SUSP (1<<12) +#define USB_STATUS_ALT(x) (((x)>>8)&0xf) +#define USB_STATUS_INTF(x) (((x)>>4)&0xf) +#define USB_STATUS_CFG(x) (((x)>>0)&0xf) + +/* USB device interrupt bits */ + +#define USB_INT_RMTWKP_STATE (1<<7) +#define USB_INT_ENUM (1<<6) +#define USB_INT_SOF (1<<5) +#define USB_INT_US (1<<4) +#define USB_INT_UR (1<<3) +#define USB_INT_ES (1<<2) +#define USB_INT_SI (1<<1) +#define USB_INT_SC (1<<0) + +/* USB system interrupt bits */ + +#define USB_INT_VBUS_DISC (1<<3) +#define USB_INT_VBUS_CONN (1<<2) +#define USB_INT_RESUME (1<<1) +#define USB_INT_READY (1<<0) + +/* USB endpoint interrupt bits */ + +#define USB_INT_CDC_CLEAR (1<<28) /* */ +#define USB_INT_XFERDONE (1<<27) /* Tfansfer Done/Transmit FIFO Empty */ +#define USB_INT_RSS (1<<26) /* Recieved Set Stall Indication */ +#define USB_INT_RCS (1<<25) /* Received Clear Stall Indication */ +#define USB_INT_TXEMPTY (1<<24) /* Transmit FIFO Empty */ +#define USB_INT_ISO_IN_DONE (1<<23) /* Isochronous IN transaction for the current microframe is complete */ +#define USB_INT_RX_PKT_SIZE(x) (((x)>>11)&0xfff) /* Receive Packet Size */ +#define USB_INT_TDC (1<<10) /* Transmit DMA Completion */ +#define USB_INT_HE (1<<9) /* Error response on the host bus */ +#define USB_INT_MRXFIFOEMPTY (1<<8) /* Receive Address FIFO Empty Status */ +#define USB_INT_BNA (1<<7) /* Buffer Not Available */ +#define USB_INT_IN (1<<6) /* IN token has been received */ +#define USB_INT_OUT(x) ((x) & (3 << 4)) /* OUT packet has been received. */ +#define USB_INT_OUT_DATA (1 << 4) +#define USB_INT_OUT_SETUP (2 << 4) + +/* PHY Configuration 0 bits */ + +#define PHY_STAGSELECT (1u<<31) +#define PHY_SHORTCKT_PROT (1u<<30) +#define PHY_HSFALLCNTRL (1u<<29) +#define PHY_HSRXOFFSET(x) (((x)&3)<<27) +#define PHY_HSRXEQUALIZE (1u<<26) +#define PHY_INSQUETUNE(x) (((x)&3)<<24) +#define PHY_ZHSDRV(x) (((x)&3)<<22) +#define PHY_IHSTX(x) (((x)&0xf)<<18) +#define PHY_INHSRFRED (1u<<17) +#define PHY_INFSRFCNTL (1u<<16) +#define PHY_INHSIPLUSENABLE (1u<<15) +#define PHY_INHSIPLUS (1u<<14) +#define PHY_INHSIMINUS (1u<<13) +#define PHY_INHSDRVSLEW (1u<<12) +#define PHY_INLFSFBCAP (1u<<11) +#define PHY_INTRCC1MA (1u<<10) +#define PHY_INCURRENTENABLE (1u<<9) +#define PHY_INAFETRIM(x) ((x)&0x1ff) + +/* PHY Configuration 1 bits */ + +#define PHY_STRB_BYPASS (1u<<31) +#define PHY_STRB (1u<<30) +#define PHY_DITHER_DISABLE_RECT (1u<<29) +#define PHY_DITHER_DISABLE_TRI (1u<<28) +#define PHY_FRAC_CONTROL (1u<<27) +#define PHY_PLLENABLE (1u<<26) +#define PHY_FRAC_INPUT(x) (((x)&0xffff)<<10) +#define PHY_ODF(x) (((x)&0x7)<<7) +#define PHY_NDIV(x) ((x)&0x3f) + +/* DMA descriptor status bits */ + +#define DESC_BS_SHIFT 30 +#define DESC_BS_MASK (3 << DESC_BS_SHIFT) +#define DESC_BS_HOST_READY (0 << DESC_BS_SHIFT) +#define DESC_BS_DMA_BUSY (1 << DESC_BS_SHIFT) +#define DESC_BS_DMA_DONE (2 << DESC_BS_SHIFT) +#define DESC_BS_HOST_BUSY (3 << DESC_BS_SHIFT) +#define IS_BS_HOST_READY(desc) (((desc)->status & DESC_BS_MASK) == DESC_BS_HOST_READY) +#define IS_BS_DMA_BUSY(desc) (((desc)->status & DESC_BS_MASK) == DESC_BS_DMA_BUSY) +#define IS_BS_DMA_DONE(desc) (((desc)->status & DESC_BS_MASK) == DESC_BS_DMA_DONE) +#define IS_BS_HOST_BUSY(desc) (((desc)->status & DESC_BS_MASK) == DESC_BS_HOST_BUSY) + +/* There is same definitions for TX/RX */ + +#define DESC_STS_SHIFT 28 +#define DESC_STS_MASK (3 << DESC_STS_SHIFT) +#define DESC_STS_SUCCESS (0 << DESC_STS_SHIFT) +#define DESC_STS_DESERR (1 << DESC_STS_SHIFT) +#define DESC_STS_BUFERR (3 << DESC_STS_SHIFT) +#define IS_STS_SUCCESS(desc) (((desc)->status & DESC_STS_MASK) == DESC_STS_SUCCESS) +#define IS_STS_DESERR(desc) (((desc)->status & DESC_STS_MASK) == DESC_STS_DESERR) +#define IS_STS_BUFERR(desc) (((desc)->status & DESC_STS_MASK) == DESC_STS_BUFERR) + +#define DESC_LAST (1 << 27) + +#define DESC_SIZE_MASK (0xffff) + +/**************************************************************************** + * Name: cxd56_usbdev_setsigno + * + * Description: + * cxd56xx usb device driver attach / detach event signal + * + ****************************************************************************/ + +int cxd56_usbdev_setsigno(int signo); + +/**************************************************************************** + * Name: cxd56_usbdev_procfs_register + * + * Description: + * Register the usbdev procfs file system entry + * + ****************************************************************************/ + +#ifdef CONFIG_FS_PROCFS_REGISTER +int cxd56_usbdev_procfs_register(void); +#endif + +#endif /* __ARCH_ARM_SRC_CXD56XX_CXD56_USBDEV_H */