diff --git a/arch/arm/src/cxd56xx/cxd56_emmc.c b/arch/arm/src/cxd56xx/cxd56_emmc.c index 05579f73ad0c..eac83c8c4cdd 100644 --- a/arch/arm/src/cxd56xx/cxd56_emmc.c +++ b/arch/arm/src/cxd56xx/cxd56_emmc.c @@ -33,6 +33,10 @@ * ****************************************************************************/ +/**************************************************************************** + * Included Files + ****************************************************************************/ + #include #include @@ -55,6 +59,10 @@ #include "hardware/cxd56_emmc.h" #include "cxd56_pinconfig.h" +/**************************************************************************** + * Pre-processoro Definitions + ****************************************************************************/ + #define SECTOR_SIZE (512) #define EMMC_DATA_WRITE 0 @@ -67,7 +75,27 @@ #define EMMC_RESP_R2 3 #define EMMC_RESP_R3 4 -struct emmc_dma_desc_s { +#define EMMC_CLKDIV_UNDER_400KHZ (32u) +#define EMMC_CLKDIV_NON_DIV (0u) + +#define EMMC_RCA (2) /* greater than 1 */ + +#define EMMC_DATA_TIMEOUT (0xFFFFFFu) /* max reg value */ +#define EMMC_RESP_TIMEOUT (0xFFu) /* max reg value */ + +#define EMMC_MSIZE (6) /* Burst size is 512B */ +#define EMMC_FIFO_DEPTH (0x100) /* FIFO size is 1KB */ + +#ifndef MIN +#define MIN(a, b) ((a) < (b) ? (a) : (b)) +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct emmc_dma_desc_s +{ uint32_t ctrl; uint32_t size; uint32_t addr; @@ -81,6 +109,10 @@ struct cxd56_emmc_state_s uint32_t total_sectors; }; +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + /* Block driver interfaces **************************************************/ static int cxd56_emmc_open(FAR struct inode *inode); @@ -98,6 +130,10 @@ static int cxd56_emmc_geometry(FAR struct inode *inode, struct geometry *geometry); static int emmc_interrupt(int irq, FAR void *context, FAR void *arg); +/**************************************************************************** + * Private Data + ****************************************************************************/ + static const struct block_operations g_bops = { cxd56_emmc_open, /* open */ @@ -106,29 +142,18 @@ static const struct block_operations g_bops = #if !defined(CONFIG_MMCSD_READONLY) cxd56_emmc_write, /* write */ #else - NULL, /* write */ + NULL, /* write */ #endif cxd56_emmc_geometry, /* geometry */ - NULL /* ioctl */ + NULL /* ioctl */ }; static sem_t g_waitsem; struct cxd56_emmc_state_s g_emmcdev; -#define EMMC_CLKDIV_UNDER_400KHZ (32u) -#define EMMC_CLKDIV_NON_DIV (0u) - -#define EMMC_RCA (2) /* greater than 1 */ - -#define EMMC_DATA_TIMEOUT (0xFFFFFFu) /* max reg value */ -#define EMMC_RESP_TIMEOUT (0xFFu) /* max reg value */ - -#define EMMC_MSIZE (6) /* Burst size is 512B */ -#define EMMC_FIFO_DEPTH (0x100) /* FIFO size is 1KB */ - -#ifndef MIN -#define MIN(a, b) ((a) < (b) ? (a) : (b)) -#endif +/**************************************************************************** + * Private Functions + ****************************************************************************/ static void emmc_takesem(FAR sem_t *sem) { @@ -308,9 +333,9 @@ static struct emmc_dma_desc_s *emmc_setupdma(void *buf, unsigned int nbytes) /* Adjust first and last descriptor members */ - descs[0].ctrl |= EMMC_IDMAC_DES0_FD; - descs[ndescs-1].ctrl |= EMMC_IDMAC_DES0_LD; - descs[ndescs-1].next = 0; + descs[0].ctrl |= EMMC_IDMAC_DES0_FD; + descs[ndescs - 1].ctrl |= EMMC_IDMAC_DES0_LD; + descs[ndescs - 1].next = 0; #ifdef CONFIG_DEBUG_VERBOSE for (i = 0, d = descs; i < ndescs; i++, d++) @@ -341,6 +366,7 @@ static int emmc_checkresponse(void) ferr("Response error %08x\n", resp); return -EIO; } + return OK; } @@ -454,6 +480,7 @@ static int emmc_is_powerup(void) { return 0; } + up_mdelay(5); } while (--retry); @@ -716,7 +743,7 @@ static int cxd56_emmc_readsectors(FAR struct cxd56_emmc_state_s *priv, ret = -EIO; } - finish: +finish: emmc_givesem(&priv->excsem); kmm_free(descs); @@ -787,7 +814,7 @@ static int cxd56_emmc_writesectors(FAR struct cxd56_emmc_state_s *priv, emmc_flushwritefifo(); - finish: +finish: emmc_givesem(&priv->excsem); kmm_free(descs); @@ -826,8 +853,9 @@ static int cxd56_emmc_close(FAR struct inode *inode) return OK; } -static ssize_t cxd56_emmc_read(FAR struct inode *inode, unsigned char *buffer, - size_t start_sector, unsigned int nsectors) +static ssize_t cxd56_emmc_read(FAR struct inode *inode, + unsigned char *buffer, size_t start_sector, + unsigned int nsectors) { FAR struct cxd56_emmc_state_s *priv; int ret; @@ -927,9 +955,11 @@ int cxd56_emmcinitialize(void) kmm_free(buf); return -EIO; } + priv->total_sectors = *(FAR uint32_t *)&buf[EXTCSD_SEC_COUNT]; kmm_free(descs); } + kmm_free(buf); } @@ -943,6 +973,10 @@ int cxd56_emmcinitialize(void) return OK; } +/**************************************************************************** + * Public Functions + ****************************************************************************/ + int emmc_uninitialize(void) { /* Send power off command */ diff --git a/arch/arm/src/lc823450/lc823450_mmcl.c b/arch/arm/src/lc823450/lc823450_mmcl.c index d5f2fcf4c706..4ace75fafe3b 100644 --- a/arch/arm/src/lc823450/lc823450_mmcl.c +++ b/arch/arm/src/lc823450/lc823450_mmcl.c @@ -78,10 +78,13 @@ static int mmcl_open(FAR struct inode *inode); static int mmcl_close(FAR struct inode *inode); static ssize_t mmcl_read(FAR struct inode *inode, unsigned char *buffer, size_t start_sector, unsigned int nsectors); -static ssize_t mmcl_write(FAR struct inode *inode, const unsigned char *buffer, - size_t start_sector, unsigned int nsectors); -static int mmcl_geometry(FAR struct inode *inode, struct geometry *geometry); -static int mmcl_ioctl(FAR struct inode *inode, int cmd, unsigned long arg); +static ssize_t mmcl_write(FAR struct inode *inode, + const unsigned char *buffer, size_t start_sector, + unsigned int nsectors); +static int mmcl_geometry(FAR struct inode *inode, + struct geometry *geometry); +static int mmcl_ioctl(FAR struct inode *inode, int cmd, + unsigned long arg); /**************************************************************************** * Private Data @@ -163,8 +166,9 @@ static ssize_t mmcl_read(FAR struct inode *inode, unsigned char *buffer, * ****************************************************************************/ -static ssize_t mmcl_write(FAR struct inode *inode, const unsigned char *buffer, - size_t start_sector, unsigned int nsectors) +static ssize_t mmcl_write(FAR struct inode *inode, + const unsigned char *buffer, size_t start_sector, + unsigned int nsectors) { ssize_t nwrite; struct mmcl_dev_s *dev; @@ -249,7 +253,8 @@ static int mmcl_ioctl(FAR struct inode *inode, int cmd, unsigned long arg) * Name: mmcl_allocdev ****************************************************************************/ -static FAR struct mmcl_dev_s *mmcl_allocdev(int number, FAR struct mtd_dev_s *mtd) +static FAR struct mmcl_dev_s *mmcl_allocdev(int number, + FAR struct mtd_dev_s *mtd) { struct mmcl_dev_s *dev; int ret; @@ -268,7 +273,8 @@ static FAR struct mmcl_dev_s *mmcl_allocdev(int number, FAR struct mtd_dev_s *mt * from the size of a pointer). */ - ret = MTD_IOCTL(mtd, MTDIOC_GEOMETRY, (unsigned long)((uintptr_t)&dev->geo)); + ret = MTD_IOCTL(mtd, MTDIOC_GEOMETRY, + (unsigned long)((uintptr_t)&dev->geo)); if (ret < 0) { finfo("MTD ioctl(MTDIOC_GEOMETRY) failed: %d\n", ret); @@ -317,6 +323,7 @@ int mmcl_initialize(int minor, FAR struct mtd_dev_s *mtd) CONFIG_MTD_DEVPATH1, #endif }; + int ret = -ENOMEM; /* Sanity check */ diff --git a/boards/arm/stm32l4/stm32l476vg-disco/src/stm32_appinit.c b/boards/arm/stm32l4/stm32l476vg-disco/src/stm32_appinit.c index 8abe7db4db60..d884a8df79ba 100644 --- a/boards/arm/stm32l4/stm32l476vg-disco/src/stm32_appinit.c +++ b/boards/arm/stm32l4/stm32l476vg-disco/src/stm32_appinit.c @@ -65,9 +65,9 @@ #include "stm32l476vg-disco.h" -/* Conditional logic in stm32l476vg-disco.h will determine if certain features - * are supported. Tests for these features need to be made after including - * stm32l476vg-disco.h. +/* Conditional logic in stm32l476vg-disco.h will determine if certain + * features are supported. Tests for these features need to be made after + * including stm32l476vg-disco.h. */ #ifdef HAVE_RTC_DRIVER @@ -129,7 +129,7 @@ int board_app_initialize(uintptr_t arg) FAR struct rtc_lowerhalf_s *rtclower; #endif #if defined(HAVE_N25QXXX) -FAR struct mtd_dev_s *mtd_temp; + FAR struct mtd_dev_s *mtd_temp; #endif #if defined(HAVE_N25QXXX_CHARDEV) char blockdev[18]; @@ -197,34 +197,35 @@ FAR struct mtd_dev_s *mtd_temp; _err("ERROR: n25qxxx_initialize failed\n"); return ret; } + g_mtd_fs = mtd_temp; #ifdef CONFIG_MTD_PARTITION - { - FAR struct mtd_geometry_s geo; - off_t nblocks; - - /* Setup a partition of 256KiB for our file system. */ - - ret = MTD_IOCTL(g_mtd_fs, MTDIOC_GEOMETRY, - (unsigned long)(uintptr_t)&geo); - if (ret < 0) - { - _err("ERROR: MTDIOC_GEOMETRY failed\n"); - return ret; - } - - nblocks = (256*1024) / geo.blocksize; - - mtd_temp = mtd_partition(g_mtd_fs, 0, nblocks); - if (!mtd_temp) - { - _err("ERROR: mtd_partition failed\n"); - return ret; - } - - g_mtd_fs = mtd_temp; - } + { + FAR struct mtd_geometry_s geo; + off_t nblocks; + + /* Setup a partition of 256KiB for our file system. */ + + ret = MTD_IOCTL(g_mtd_fs, MTDIOC_GEOMETRY, + (unsigned long)(uintptr_t)&geo); + if (ret < 0) + { + _err("ERROR: MTDIOC_GEOMETRY failed\n"); + return ret; + } + + nblocks = (256 * 1024) / geo.blocksize; + + mtd_temp = mtd_partition(g_mtd_fs, 0, nblocks); + if (!mtd_temp) + { + _err("ERROR: mtd_partition failed\n"); + return ret; + } + + g_mtd_fs = mtd_temp; + } #endif #ifdef HAVE_N25QXXX_SMARTFS diff --git a/boards/boardctl.c b/boards/boardctl.c index cded6c46ec05..f57366557c3f 100644 --- a/boards/boardctl.c +++ b/boards/boardctl.c @@ -1,35 +1,20 @@ /**************************************************************************** * boards/boardctl.c * - * Copyright (C) 2015-2017, 2018-2019 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: + * http://www.apache.org/licenses/LICENSE-2.0 * - * 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. + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. * ****************************************************************************/ @@ -95,7 +80,8 @@ ****************************************************************************/ #ifdef CONFIG_BOARDCTL_USBDEVCTRL -static inline int boardctl_usbdevctrl(FAR struct boardioc_usbdev_ctrl_s *ctrl) +static inline int + boardctl_usbdevctrl(FAR struct boardioc_usbdev_ctrl_s *ctrl) { int ret = OK; @@ -297,10 +283,10 @@ static inline int boardctl_pmctrl(FAR struct boardioc_pm_ctrl_s *ctrl) * to "correct" but awkward implementations. * * boardctl() is non-standard OS interface to alleviate the problem. It - * basically circumvents the normal device driver ioctl interlace and allows - * the application to perform direction IOCTL-like calls to the board-specific - * logic. In it is especially useful for setting up board operational and - * test configurations. + * basically circumvents the normal device driver ioctl interlace and + * allows the application to perform direction IOCTL-like calls to the + * board-specific logic. In it is especially useful for setting up board + * operational and test configurations. * * Input Parameters: * cmd - Identifies the board command to be executed @@ -322,16 +308,16 @@ int boardctl(unsigned int cmd, uintptr_t arg) /* CMD: BOARDIOC_INIT * DESCRIPTION: Perform one-time application initialization. * ARG: The boardctl() argument is passed to the - * board_app_initialize() implementation without modification. - * The argument has no meaning to NuttX; the meaning of the - * argument is a contract between the board-specific - * initialization logic and the matching application logic. - * The value cold be such things as a mode enumeration value, - * a set of DIP switch switch settings, a pointer to - * configuration data read from a file or serial FLASH, or - * whatever you would like to do with it. Every - * implementation should accept zero/NULL as a default - * configuration. + * board_app_initialize() implementation without + * modification. The argument has no meaning to NuttX; + * the meaning of the argument is a contract between + * the board-specific initialization logic and the + * matching application logic. The value cold be such + * things as a mode enumeration value, a set of DIP + * switch switch settings, a pointer to configuration + * data read from a file or serial FLASH, or whatever + * you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. * CONFIGURATION: CONFIG_LIB_BOARDCTL * DEPENDENCIES: Board logic must provide board_app_initialization */ @@ -411,8 +397,9 @@ int boardctl(unsigned int cmd, uintptr_t arg) /* CMD: BOARDIOC_UNIQUEID * DESCRIPTION: Return a unique ID associated with the board (such * as a serial number or a MAC address). - * ARG: A writable array of size CONFIG_BOARDCTL_UNIQUEID_SIZE - * in which to receive the board unique ID. + * ARG: A writable array of size + * CONFIG_BOARDCTL_UNIQUEID_SIZE in which to receive + * the board unique ID. * DEPENDENCIES: Board logic must provide the board_uniqueid() * interface. */ @@ -427,7 +414,8 @@ int boardctl(unsigned int cmd, uintptr_t arg) #ifdef CONFIG_BOARDCTL_MKRD /* CMD: BOARDIOC_MKRD * DESCRIPTION: Create a RAM disk - * ARG: Pointer to read-only instance of struct boardioc_mkrd_s. + * ARG: Pointer to read-only instance of struct + * boardioc_mkrd_s. * CONFIGURATION: CONFIG_BOARDCTL_MKRD * DEPENDENCIES: None */ @@ -453,7 +441,8 @@ int boardctl(unsigned int cmd, uintptr_t arg) #ifdef CONFIG_BOARDCTL_ROMDISK /* CMD: BOARDIOC_ROMDISK * DESCRIPTION: Register - * ARG: Pointer to read-only instance of struct boardioc_romdisk_s. + * ARG: Pointer to read-only instance of struct + * boardioc_romdisk_s. * CONFIGURATION: CONFIG_BOARDCTL_ROMDISK * DEPENDENCIES: None */ @@ -469,8 +458,8 @@ int boardctl(unsigned int cmd, uintptr_t arg) } else { - ret = romdisk_register((int)desc->minor, desc->image, desc->nsectors, - desc->sectsize); + ret = romdisk_register((int)desc->minor, desc->image, + desc->nsectors, desc->sectsize); } } break; @@ -478,9 +467,9 @@ int boardctl(unsigned int cmd, uintptr_t arg) #ifdef CONFIG_BOARDCTL_APP_SYMTAB /* CMD: BOARDIOC_APP_SYMTAB - * DESCRIPTION: Select the application symbol table. This symbol table - * provides the symbol definitions exported to application - * code from application space. + * DESCRIPTION: Select the application symbol table. This symbol + * table provides the symbol definitions exported to + * application code from application space. * ARG: A pointer to an instance of struct boardioc_symtab_s * CONFIGURATION: CONFIG_BOARDCTL_APP_SYMTAB * DEPENDENCIES: None @@ -500,9 +489,9 @@ int boardctl(unsigned int cmd, uintptr_t arg) #ifdef CONFIG_BOARDCTL_OS_SYMTAB /* CMD: BOARDIOC_OS_SYMTAB - * DESCRIPTION: Select the OS symbol table. This symbol table provides - * the symbol definitions exported by the OS to kernel - * modules. + * DESCRIPTION: Select the OS symbol table. This symbol table + * provides the symbol definitions exported by the OS to + * kernal modules. * ARG: A pointer to an instance of struct boardioc_symtab_s * CONFIGURATION: CONFIG_BOARDCTL_OS_SYMTAB * DEPENDENCIES: None @@ -522,17 +511,18 @@ int boardctl(unsigned int cmd, uintptr_t arg) #ifdef CONFIG_BUILTIN /* CMD: BOARDIOC_BUILTINS - * DESCRIPTION: Provide the user-space list of built-in applications for - * use by BINFS in protected mode. Normally this is small - * set of globals provided by user-space logic. It provides - * name-value pairs for associating built-in application - * names with user-space entry point addresses. These - * globals are only needed for use by BINFS which executes - * built-in applications from kernel-space in PROTECTED mode. - * In the FLAT build, the user space globals are readily - * available. (BINFS is not supportable in KERNEL mode since - * user-space address have no general meaning that - * configuration). + * DESCRIPTION: Provide the user-space list of built-in applications + * for use by BINFS in protected mode. Normally this + * is small set of globals provided by user-space + * logic. It provides name-value pairs for associating + * built-in application names with user-space entry + * point addresses. These globals are only needed for + * use by BINFS which executes built-in applications + * from kernel-space in PROTECTED mode. In the FLAT + * build, the user space globals are readily + * available. (BINFS is not supportable in KERNEL mode + * since user-space address have no general meaning + * that configuration). * ARG: A pointer to an instance of struct boardioc_builtin_s * CONFIGURATION: This BOARDIOC command is always available when * CONFIG_BUILTIN is enabled, but does nothing unless @@ -557,7 +547,8 @@ int boardctl(unsigned int cmd, uintptr_t arg) #ifdef CONFIG_BOARDCTL_USBDEVCTRL /* CMD: BOARDIOC_USBDEV_CONTROL * DESCRIPTION: Manage USB device classes - * ARG: A pointer to an instance of struct boardioc_usbdev_ctrl_s + * ARG: A pointer to an instance of struct + * boardioc_usbdev_ctrl_s * CONFIGURATION: CONFIG_LIB_BOARDCTL && CONFIG_BOARDCTL_USBDEVCTRL * DEPENDENCIES: Board logic must provide board__initialize() */ @@ -673,9 +664,10 @@ int boardctl(unsigned int cmd, uintptr_t arg) break; /* CMD: BOARDIOC_NXTERM_IOCTL - * DESCRIPTION: Create an NX terminal IOCTL command. Normal IOCTLs - * cannot be be performed in most graphics contexts since - * the depend on the task holding an open file descriptor + * DESCRIPTION: Create an NX terminal IOCTL command. Normal + * IOCTLs cannot be be performed in most graphics + * contexts since the depend on the task holding an + * open file descriptor * ARG: A reference readable/writable instance of struct * boardioc_nxterm_ioctl_s * CONFIGURATION: CONFIG_NXTERM @@ -696,9 +688,9 @@ int boardctl(unsigned int cmd, uintptr_t arg) #ifdef CONFIG_BOARDCTL_TESTSET /* CMD: BOARDIOC_TESTSET * DESCRIPTION: Access architecture-specific up_testset() operation - * ARG: A pointer to a write-able spinlock object. On success - * the preceding spinlock state is returned: 0=unlocked, - * 1=locked. + * ARG: A pointer to a write-able spinlock object. On + * success the preceding spinlock state is returned: + * 0=unlocked, 1=locked. * CONFIGURATION: CONFIG_BOARDCTL_TESTSET * DEPENDENCIES: Architecture-specific logic provides up_testset() */ @@ -722,10 +714,10 @@ int boardctl(unsigned int cmd, uintptr_t arg) default: { #ifdef CONFIG_BOARDCTL_IOCTL - /* Boards may also select CONFIG_BOARDCTL_IOCTL=y to enable board- - * specific commands. In this case, all commands not recognized - * by boardctl() will be forwarded to the board-provided board_ioctl() - * function. + /* Boards may also select CONFIG_BOARDCTL_IOCTL=y to enable + * board-specific commands. In this case, all commands not + * recognized by boardctl() will be forwarded to the board- + * provided board_ioctl() function. */ ret = board_ioctl(cmd, arg); diff --git a/drivers/mmcsd/mmcsd_sdio.c b/drivers/mmcsd/mmcsd_sdio.c index 776c96ba1285..c34aedd6f4b7 100644 --- a/drivers/mmcsd/mmcsd_sdio.c +++ b/drivers/mmcsd/mmcsd_sdio.c @@ -72,11 +72,11 @@ /* Data delays (all in units of milliseconds). * - * For MMC & SD V1.x, these should be based on Nac = TAAC + NSAC; The maximum - * value of TAAC is 80MS and the maximum value of NSAC is 25.5K clock cycle. - * For SD V2.x, a fixed delay of 100MS is recommend which is pretty close to - * the worst case SD V1.x Nac. Here we just use 100MS delay for all data - * transfers. + * For MMC & SD V1.x, these should be based on Nac = TAAC + NSAC; The + * maximum value of TAAC is 80MS and the maximum value of NSAC is 25.5K + * clock cycle. For SD V2.x, a fixed delay of 100MS is recommend which is + * pretty close to the worst case SD V1.x Nac. Here we just use 100MS + * delay for all data transfers. */ #define MMCSD_SCR_DATADELAY (100) /* Wait up to 100MS to get SCR */ @@ -152,22 +152,23 @@ static void mmcsd_takesem(FAR struct mmcsd_state_s *priv); static int mmcsd_sendcmdpoll(FAR struct mmcsd_state_s *priv, uint32_t cmd, uint32_t arg); -static int mmcsd_recvR1(FAR struct mmcsd_state_s *priv, uint32_t cmd); -static int mmcsd_recvR6(FAR struct mmcsd_state_s *priv, uint32_t cmd); -static int mmcsd_getSCR(FAR struct mmcsd_state_s *priv, uint32_t scr[2]); +static int mmsd_recv_r1(FAR struct mmcsd_state_s *priv, uint32_t cmd); +static int mmsd_recv_r6(FAR struct mmcsd_state_s *priv, uint32_t cmd); +static int mmsd_get_scr(FAR struct mmcsd_state_s *priv, uint32_t scr[2]); -static void mmcsd_decodeCSD(FAR struct mmcsd_state_s *priv, +static void mmcsd_decode_csd(FAR struct mmcsd_state_s *priv, uint32_t csd[4]); #ifdef CONFIG_DEBUG_FS_INFO -static void mmcsd_decodeCID(FAR struct mmcsd_state_s *priv, +static void mmcsd_decode_cid(FAR struct mmcsd_state_s *priv, uint32_t cid[4]); #else -# define mmcsd_decodeCID(priv,cid) +# define mmcsd_decode_cid(priv,cid) #endif -static void mmcsd_decodeSCR(FAR struct mmcsd_state_s *priv, +static void mmsd_decode_scr(FAR struct mmcsd_state_s *priv, uint32_t scr[2]); -static int mmcsd_getR1(FAR struct mmcsd_state_s *priv, FAR uint32_t *r1); +static int mmcsd_get_r1(FAR struct mmcsd_state_s *priv, + FAR uint32_t *r1); static int mmcsd_verifystate(FAR struct mmcsd_state_s *priv, uint32_t status); @@ -196,7 +197,8 @@ static ssize_t mmcsd_writesingle(FAR struct mmcsd_state_s *priv, FAR const uint8_t *buffer, off_t startblock); #ifndef CONFIG_MMCSD_MULTIBLOCK_DISABLE static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv, - FAR const uint8_t *buffer, off_t startblock, size_t nblocks); + FAR const uint8_t *buffer, off_t startblock, + size_t nblocks); #endif #ifdef CONFIG_DRVR_WRITEBUFFER static ssize_t mmcsd_flush(FAR void *dev, FAR const uint8_t *buffer, @@ -223,7 +225,7 @@ static void mmcsd_mediachange(FAR void *arg); static int mmcsd_widebus(FAR struct mmcsd_state_s *priv); #ifdef CONFIG_MMCSD_MMCSUPPORT static int mmcsd_mmcinitialize(FAR struct mmcsd_state_s *priv); -static int mmcsd_mmcreadextCSD (FAR struct mmcsd_state_s *priv); +static int mmcsd_read_csd (FAR struct mmcsd_state_s *priv); #endif static int mmcsd_sdinitialize(FAR struct mmcsd_state_s *priv); static int mmcsd_cardidentify(FAR struct mmcsd_state_s *priv); @@ -311,7 +313,8 @@ static int mmcsd_sendcmdpoll(FAR struct mmcsd_state_s *priv, uint32_t cmd, ret = SDIO_WAITRESPONSE(priv->dev, cmd); if (ret != OK) { - ferr("ERROR: Wait for response to cmd: %08x failed: %d\n", cmd, ret); + ferr("ERROR: Wait for response to cmd: %08x failed: %d\n", + cmd, ret); } } @@ -359,14 +362,14 @@ static inline int mmcsd_sendcmd4(FAR struct mmcsd_state_s *priv) } /**************************************************************************** - * Name: mmcsd_recvR1 + * Name: mmsd_recv_r1 * * Description: * Receive R1 response and check for errors. * ****************************************************************************/ -static int mmcsd_recvR1(FAR struct mmcsd_state_s *priv, uint32_t cmd) +static int mmsd_recv_r1(FAR struct mmcsd_state_s *priv, uint32_t cmd) { uint32_t r1; int ret; @@ -394,7 +397,7 @@ static int mmcsd_recvR1(FAR struct mmcsd_state_s *priv, uint32_t cmd) } /**************************************************************************** - * Name: mmcsd_recvR6 + * Name: mmsd_recv_r6 * * Description: * Receive R6 response and check for errors. On success, priv->rca is set @@ -402,7 +405,7 @@ static int mmcsd_recvR1(FAR struct mmcsd_state_s *priv, uint32_t cmd) * ****************************************************************************/ -static int mmcsd_recvR6(FAR struct mmcsd_state_s *priv, uint32_t cmd) +static int mmsd_recv_r6(FAR struct mmcsd_state_s *priv, uint32_t cmd) { uint32_t r6 = 0; int ret; @@ -443,7 +446,7 @@ static int mmcsd_recvR6(FAR struct mmcsd_state_s *priv, uint32_t cmd) } /**************************************************************************** - * Name: mmcsd_getSCR + * Name: mmsd_get_scr * * Description: * Obtain the SD card's Configuration Register (SCR) @@ -453,7 +456,7 @@ static int mmcsd_recvR6(FAR struct mmcsd_state_s *priv, uint32_t cmd) * ****************************************************************************/ -static int mmcsd_getSCR(FAR struct mmcsd_state_s *priv, uint32_t scr[2]) +static int mmsd_get_scr(FAR struct mmcsd_state_s *priv, uint32_t scr[2]) { int ret; @@ -478,7 +481,7 @@ static int mmcsd_getSCR(FAR struct mmcsd_state_s *priv, uint32_t scr[2]) /* Send CMD55 APP_CMD with argument as card's RCA */ mmcsd_sendcmdpoll(priv, SD_CMD55, (uint32_t)priv->rca << 16); - ret = mmcsd_recvR1(priv, SD_CMD55); + ret = mmsd_recv_r1(priv, SD_CMD55); if (ret != OK) { ferr("ERROR: RECVR1 for CMD55 failed: %d\n", ret); @@ -488,7 +491,7 @@ static int mmcsd_getSCR(FAR struct mmcsd_state_s *priv, uint32_t scr[2]) /* Send ACMD51 SD_APP_SEND_SCR with argument as 0 to start data receipt */ mmcsd_sendcmdpoll(priv, SD_ACMD51, 0); - ret = mmcsd_recvR1(priv, SD_ACMD51); + ret = mmsd_recv_r1(priv, SD_ACMD51); if (ret != OK) { ferr("ERROR: RECVR1 for ACMD51 failed: %d\n", ret); @@ -509,7 +512,7 @@ static int mmcsd_getSCR(FAR struct mmcsd_state_s *priv, uint32_t scr[2]) } /**************************************************************************** - * Name: mmcsd_decodeCSD + * Name: mmcsd_decode_csd * * Description: * Decode and extract necessary information from the CSD. If debug is @@ -527,7 +530,7 @@ static int mmcsd_getSCR(FAR struct mmcsd_state_s *priv, uint32_t scr[2]) * ****************************************************************************/ -static void mmcsd_decodeCSD(FAR struct mmcsd_state_s *priv, uint32_t csd[4]) +static void mmcsd_decode_csd(FAR struct mmcsd_state_s *priv, uint32_t csd[4]) { #ifdef CONFIG_DEBUG_FS_INFO struct mmcsd_csd_s decoded; @@ -543,10 +546,11 @@ static void mmcsd_decodeCSD(FAR struct mmcsd_state_s *priv, uint32_t csd[4]) * TAAC 119:112 Data read access-time-1 * TIME_VALUE 6:3 Time mantissa * TIME_UNIT 2:0 Time exponent - * NSAC 111:104 Data read access-time-2 in CLK cycle(NSAC*100) - * TRAN_SPEED 103:96 Max. data transfer rate - * TIME_VALUE 6:3 Rate exponent - * TRANSFER_RATE_UNIT 2:0 Rate mantissa + * NSAC 111:104 Data read access-time-2 in CLK + * cycle(NSAC*100) + * TRAN_SPEED 103:96 Max. data transfer rate + * TIME_VALUE 6:3 Rate exponent + * TRANSFER_RATE_UNIT 2:0 Rate mantissa */ #ifdef CONFIG_DEBUG_FS_INFO @@ -633,7 +637,8 @@ static void mmcsd_decodeCSD(FAR struct mmcsd_state_s *priv, uint32_t csd[4]) */ #ifdef CONFIG_DEBUG_FS_INFO - uint16_t csize = ((csd[1] & 0x03ff) << 2) | ((csd[2] >> 30) & 3); + uint16_t csize = ((csd[1] & 0x03ff) << 2) | + ((csd[2] >> 30) & 3); uint8_t csizemult = (csd[2] >> 15) & 7; #endif @@ -700,19 +705,22 @@ static void mmcsd_decodeCSD(FAR struct mmcsd_state_s *priv, uint32_t csd[4]) * C_SIZE: 73:64 from Word 2 and 63:62 from Word 3 */ - uint16_t csize = ((csd[1] & 0x03ff) << 2) | ((csd[2] >> 30) & 3); + uint16_t csize = ((csd[1] & 0x03ff) << 2) | + ((csd[2] >> 30) & 3); uint8_t csizemult = (csd[2] >> 15) & 7; - priv->nblocks = ((uint32_t)csize + 1) * (1 << (csizemult + 2)); + priv->nblocks = ((uint32_t)csize + 1) * + (1 << (csizemult + 2)); priv->blockshift = readbllen; priv->blocksize = (1 << readbllen); priv->capacity = (priv->nblocks << readbllen); - /* Some devices, such as 2Gb devices, report blocksizes larger than 512 bytes - * but still expect to be accessed with a 512 byte blocksize. + /* Some devices, such as 2Gb devices, report blocksizes larger than + * 512 bytes but still expect to be accessed with a 512 byte blocksize. * - * NOTE: A minor optimization would be to eliminated priv->blocksize and - * priv->blockshift: Those values will be 512 and 9 in all cases anyway. + * NOTE: A minor optimization would be to eliminated priv->blocksize + * and priv->blockshift: Those values will be 512 and 9 in all cases + * anyway. */ if (priv->blocksize > 512) @@ -813,8 +821,10 @@ static void mmcsd_decodeCSD(FAR struct mmcsd_state_s *priv, uint32_t csd[4]) decoded.u.mmc.vddrcurrmin, decoded.u.mmc.vddrcurrmax); finfo(" VDD_W_CURR_MIN: %d VDD_W_CURR_MAX: %d\n", decoded.u.mmc.vddwcurrmin, decoded.u.mmc.vddwcurrmax); - finfo(" MMC_SECTOR_SIZE: %d MMC_ER_GRP_SIZE: %d MMC_WP_GRP_SIZE: %d\n", - decoded.u.mmc.er.mmc22.sectorsize, decoded.u.mmc.er.mmc22.ergrpsize, + finfo(" MMC_SECTOR_SIZE: %d MMC_ER_GRP_SIZE: %d " + "MMC_WP_GRP_SIZE: %d\n", + decoded.u.mmc.er.mmc22.sectorsize, + decoded.u.mmc.er.mmc22.ergrpsize, decoded.u.mmc.mmcwpgrpsize); } else @@ -824,7 +834,8 @@ static void mmcsd_decodeCSD(FAR struct mmcsd_state_s *priv, uint32_t csd[4]) finfo(" C_SIZE: %d SD_ER_BLK_EN: %d\n", decoded.u.sdblock.csize, decoded.u.sdblock.sderblen); finfo(" SD_SECTOR_SIZE: %d SD_WP_GRP_SIZE: %d\n", - decoded.u.sdblock.sdsectorsize, decoded.u.sdblock.sdwpgrpsize); + decoded.u.sdblock.sdsectorsize, + decoded.u.sdblock.sdwpgrpsize); } } else if (IS_SD(priv->type)) @@ -836,7 +847,8 @@ static void mmcsd_decodeCSD(FAR struct mmcsd_state_s *priv, uint32_t csd[4]) decoded.u.sdbyte.vddrcurrmin, decoded.u.sdbyte.vddrcurrmax); finfo(" VDD_W_CURR_MIN: %d VDD_W_CURR_MAX: %d\n", decoded.u.sdbyte.vddwcurrmin, decoded.u.sdbyte.vddwcurrmax); - finfo(" SD_ER_BLK_EN: %d SD_SECTOR_SIZE: %d (SD) SD_WP_GRP_SIZE: %d\n", + finfo(" SD_ER_BLK_EN: %d SD_SECTOR_SIZE: %d (SD) " + "SD_WP_GRP_SIZE: %d\n", decoded.u.sdbyte.sderblen, decoded.u.sdbyte.sdsectorsize, decoded.u.sdbyte.sdwpgrpsize); } @@ -850,8 +862,10 @@ static void mmcsd_decodeCSD(FAR struct mmcsd_state_s *priv, uint32_t csd[4]) decoded.u.mmc.vddrcurrmin, decoded.u.mmc.vddrcurrmax); finfo(" VDD_W_CURR_MIN: %d VDD_W_CURR_MAX: %d\n", decoded.u.mmc.vddwcurrmin, decoded.u.mmc.vddwcurrmax); - finfo(" MMC_SECTOR_SIZE: %d MMC_ER_GRP_SIZE: %d MMC_WP_GRP_SIZE: %d\n", - decoded.u.mmc.er.mmc22.sectorsize, decoded.u.mmc.er.mmc22.ergrpsize, + finfo(" MMC_SECTOR_SIZE: %d MMC_ER_GRP_SIZE: %d " + "MMC_WP_GRP_SIZE: %d\n", + decoded.u.mmc.er.mmc22.sectorsize, + decoded.u.mmc.er.mmc22.ergrpsize, decoded.u.mmc.mmcwpgrpsize); } #endif @@ -874,7 +888,7 @@ static void mmcsd_decodeCSD(FAR struct mmcsd_state_s *priv, uint32_t csd[4]) } /**************************************************************************** - * Name: mmcsd_decodeCID + * Name: mmcsd_decode_cid * * Description: * Show the contents of the Card Identification Data (CID) (for debug @@ -883,7 +897,7 @@ static void mmcsd_decodeCSD(FAR struct mmcsd_state_s *priv, uint32_t csd[4]) ****************************************************************************/ #ifdef CONFIG_DEBUG_FS_INFO -static void mmcsd_decodeCID(FAR struct mmcsd_state_s *priv, uint32_t cid[4]) +static void mmcsd_decode_cid(FAR struct mmcsd_state_s *priv, uint32_t cid[4]) { struct mmcsd_cid_s decoded; @@ -938,7 +952,7 @@ static void mmcsd_decodeCID(FAR struct mmcsd_state_s *priv, uint32_t cid[4]) #endif /**************************************************************************** - * Name: mmcsd_decodeSCR + * Name: mmsd_decode_scr * * Description: * Show the contents of the SD Configuration Register (SCR). The only @@ -946,7 +960,7 @@ static void mmcsd_decodeCID(FAR struct mmcsd_state_s *priv, uint32_t cid[4]) * ****************************************************************************/ -static void mmcsd_decodeSCR(FAR struct mmcsd_state_s *priv, uint32_t scr[2]) +static void mmsd_decode_scr(FAR struct mmcsd_state_s *priv, uint32_t scr[2]) { #ifdef CONFIG_DEBUG_FS_INFO struct mmcsd_scr_s decoded; @@ -968,16 +982,22 @@ static void mmcsd_decodeSCR(FAR struct mmcsd_state_s *priv, uint32_t scr[2]) #endif #ifdef CONFIG_DEBUG_FS_INFO -#ifdef CONFIG_ENDIAN_BIG /* Card SCR is big-endian order / CPU also big-endian - * 60 56 52 48 44 40 36 32 - * VVVV SSSS ESSS BBBB RRRR RRRR RRRR RRRR */ +#ifdef CONFIG_ENDIAN_BIG + /* Card SCR is big-endian order / CPU also big-endian + * 60 56 52 48 44 40 36 32 + * VVVV SSSS ESSS BBBB RRRR RRRR RRRR RRRR + */ + decoded.scrversion = scr[0] >> 28; decoded.sdversion = (scr[0] >> 24) & 15; decoded.erasestate = (scr[0] >> 23) & 1; decoded.security = (scr[0] >> 20) & 7; -#else /* Card SCR is big-endian order / CPU is little-endian - * 36 32 44 40 52 48 60 56 - * RRRR RRRR RRRR RRRR ESSS BBBB VVVV SSSS */ +#else + /* Card SCR is big-endian order / CPU is little-endian + * 36 32 44 40 52 48 60 56 + * RRRR RRRR RRRR RRRR ESSS BBBB VVVV SSSS + */ + decoded.scrversion = (scr[0] >> 4) & 15; decoded.sdversion = scr[0] & 15; decoded.erasestate = (scr[0] >> 15) & 1; @@ -1004,16 +1024,16 @@ static void mmcsd_decodeSCR(FAR struct mmcsd_state_s *priv, uint32_t scr[2]) } /**************************************************************************** - * Name: mmcsd_getR1 + * Name: mmcsd_get_r1 * * Description: * Get the R1 status of the card using CMD13 * ****************************************************************************/ -static int mmcsd_getR1(FAR struct mmcsd_state_s *priv, FAR uint32_t *r1) +static int mmcsd_get_r1(FAR struct mmcsd_state_s *priv, FAR uint32_t *r1) { - uint32_t localR1; + uint32_t local_r1; int ret; DEBUGASSERT(priv != NULL && r1 != NULL); @@ -1023,29 +1043,30 @@ static int mmcsd_getR1(FAR struct mmcsd_state_s *priv, FAR uint32_t *r1) */ mmcsd_sendcmdpoll(priv, MMCSD_CMD13, (uint32_t)priv->rca << 16); - ret = SDIO_RECVR1(priv->dev, MMCSD_CMD13, &localR1); + ret = SDIO_RECVR1(priv->dev, MMCSD_CMD13, &local_r1); if (ret == OK) { /* Check if R1 reports an error */ - if ((localR1 & MMCSD_R1_ERRORMASK) != 0) + if ((local_r1 & MMCSD_R1_ERRORMASK) != 0) { /* Card locked is considered an error. Save the card locked * indication for later use. */ - priv->locked = ((localR1 & MMCSD_R1_CARDISLOCKED) != 0); + priv->locked = ((local_r1 & MMCSD_R1_CARDISLOCKED) != 0); /* We must tell someone which error bits were set. */ - fwarn("WARNING: mmcsd_getR1 returned errors: R1=%08x\n", localR1); + fwarn("WARNING: mmcsd_get_r1 returned errors: R1=%08x\n", + local_r1); ret = -EIO; } else { /* No errors, return R1 */ - *r1 = localR1; + *r1 = local_r1; } } @@ -1067,10 +1088,10 @@ static int mmcsd_verifystate(FAR struct mmcsd_state_s *priv, uint32_t state) /* Get the current R1 status from the card */ - ret = mmcsd_getR1(priv, &r1); + ret = mmcsd_get_r1(priv, &r1); if (ret != OK) { - ferr("ERROR: mmcsd_getR1 failed: %d\n", ret); + ferr("ERROR: mmcsd_get_r1 failed: %d\n", ret); return ret; } @@ -1115,7 +1136,8 @@ static bool mmcsd_wrprotected(FAR struct mmcsd_state_s *priv) * Name: mmcsd_eventwait * * Description: - * Wait for the specified events to occur. Check for wakeup on error events. + * Wait for the specified events to occur. Check for wakeup on error + * events. * ****************************************************************************/ @@ -1183,14 +1205,15 @@ static int mmcsd_transferready(FAR struct mmcsd_state_s *priv) } /* The card is still present and the last transfer was a write transfer. - * Loop, querying the card state. Return when (1) the card is in the TRANSFER - * state, (2) the card stays in the PROGRAMMING state too long, or (3) the - * card is in any other state. + * Loop, querying the card state. Return when (1) the card is in the + * TRANSFER state, (2) the card stays in the PROGRAMMING state too long, + * or (3) the card is in any other state. * - * The PROGRAMMING state occurs normally after a WRITE operation. During this - * time, the card may be busy completing the WRITE and is not available for - * other operations. The card will transition from the PROGRAMMING state to - * the TRANSFER state when the card completes the WRITE operation. + * The PROGRAMMING state occurs normally after a WRITE operation. During + * this time, the card may be busy completing the WRITE and is not + * available for other operations. The card will transition from the + * PROGRAMMING state to the TRANSFER state when the card completes the + * WRITE operation. */ #if defined(CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE) @@ -1207,10 +1230,10 @@ static int mmcsd_transferready(FAR struct mmcsd_state_s *priv) { /* Get the current R1 status from the card */ - ret = mmcsd_getR1(priv, &r1); + ret = mmcsd_get_r1(priv, &r1); if (ret != OK) { - ferr("ERROR: mmcsd_getR1 failed: %d\n", ret); + ferr("ERROR: mmcsd_get_r1 failed: %d\n", ret); goto errorout; } @@ -1276,10 +1299,10 @@ static int mmcsd_stoptransmission(FAR struct mmcsd_state_s *priv) /* Send CMD12, STOP_TRANSMISSION, and verify good R1 return status */ mmcsd_sendcmdpoll(priv, MMCSD_CMD12, 0); - ret = mmcsd_recvR1(priv, MMCSD_CMD12); + ret = mmsd_recv_r1(priv, MMCSD_CMD12); if (ret != OK) { - ferr("ERROR: mmcsd_recvR1 for CMD12 failed: %d\n", ret); + ferr("ERROR: mmsd_recv_r1 for CMD12 failed: %d\n", ret); } return ret; @@ -1294,7 +1317,8 @@ static int mmcsd_stoptransmission(FAR struct mmcsd_state_s *priv) * ****************************************************************************/ -static int mmcsd_setblocklen(FAR struct mmcsd_state_s *priv, uint32_t blocklen) +static int mmcsd_setblocklen(FAR struct mmcsd_state_s *priv, + uint32_t blocklen) { int ret = OK; @@ -1308,14 +1332,14 @@ static int mmcsd_setblocklen(FAR struct mmcsd_state_s *priv, uint32_t blocklen) */ mmcsd_sendcmdpoll(priv, MMCSD_CMD16, blocklen); - ret = mmcsd_recvR1(priv, MMCSD_CMD16); + ret = mmsd_recv_r1(priv, MMCSD_CMD16); if (ret == OK) { priv->selblocklen = blocklen; } else { - ferr("ERROR: mmcsd_recvR1 for CMD16 failed: %d\n", ret); + ferr("ERROR: mmsd_recv_r1 for CMD16 failed: %d\n", ret); } } @@ -1430,10 +1454,10 @@ static ssize_t mmcsd_readsingle(FAR struct mmcsd_state_s *priv, */ mmcsd_sendcmdpoll(priv, MMCSD_CMD17, offset); - ret = mmcsd_recvR1(priv, MMCSD_CMD17); + ret = mmsd_recv_r1(priv, MMCSD_CMD17); if (ret != OK) { - ferr("ERROR: mmcsd_recvR1 for CMD17 failed: %d\n", ret); + ferr("ERROR: mmsd_recv_r1 for CMD17 failed: %d\n", ret); SDIO_CANCEL(priv->dev); return ret; } @@ -1514,8 +1538,9 @@ static ssize_t mmcsd_readmultiple(FAR struct mmcsd_state_s *priv, return ret; } - /* If this is a byte addressed SD card, then convert both the total transfer - * size to bytes and the sector start sector number to a byte offset + /* If this is a byte addressed SD card, then convert both the total + * transfer size to bytes and the sector start sector number to a byte + * offset */ nbytes = nblocks << priv->blockshift; @@ -1566,10 +1591,10 @@ static ssize_t mmcsd_readmultiple(FAR struct mmcsd_state_s *priv, */ mmcsd_sendcmdpoll(priv, MMCSD_CMD18, offset); - ret = mmcsd_recvR1(priv, MMCSD_CMD18); + ret = mmsd_recv_r1(priv, MMCSD_CMD18); if (ret != OK) { - ferr("ERROR: mmcsd_recvR1 for CMD18 failed: %d\n", ret); + ferr("ERROR: mmsd_recv_r1 for CMD18 failed: %d\n", ret); SDIO_CANCEL(priv->dev); return ret; } @@ -1756,10 +1781,10 @@ static ssize_t mmcsd_writesingle(FAR struct mmcsd_state_s *priv, /* Send CMD24, WRITE_BLOCK, and verify that good R1 status is returned */ mmcsd_sendcmdpoll(priv, MMCSD_CMD24, offset); - ret = mmcsd_recvR1(priv, MMCSD_CMD24); + ret = mmsd_recv_r1(priv, MMCSD_CMD24); if (ret != OK) { - ferr("ERROR: mmcsd_recvR1 for CMD24 failed: %d\n", ret); + ferr("ERROR: mmsd_recv_r1 for CMD24 failed: %d\n", ret); return ret; } } @@ -1793,10 +1818,10 @@ static ssize_t mmcsd_writesingle(FAR struct mmcsd_state_s *priv, /* Send CMD24, WRITE_BLOCK, and verify that good R1 status is returned */ mmcsd_sendcmdpoll(priv, MMCSD_CMD24, offset); - ret = mmcsd_recvR1(priv, MMCSD_CMD24); + ret = mmsd_recv_r1(priv, MMCSD_CMD24); if (ret != OK) { - ferr("ERROR: mmcsd_recvR1 for CMD24 failed: %d\n", ret); + ferr("ERROR: mmsd_recv_r1 for CMD24 failed: %d\n", ret); return ret; } } @@ -1804,7 +1829,8 @@ static ssize_t mmcsd_writesingle(FAR struct mmcsd_state_s *priv, /* Wait for the transfer to complete */ ret = mmcsd_eventwait(priv, - SDIOWAIT_TIMEOUT | SDIOWAIT_ERROR, MMCSD_BLOCK_WDATADELAY); + SDIOWAIT_TIMEOUT | SDIOWAIT_ERROR, + MMCSD_BLOCK_WDATADELAY); if (ret != OK) { ferr("ERROR: CMD24 transfer failed: %d\n", ret); @@ -1840,8 +1866,8 @@ static ssize_t mmcsd_writesingle(FAR struct mmcsd_state_s *priv, #if !defined(CONFIG_MMCSD_MULTIBLOCK_DISABLE) static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv, - FAR const uint8_t *buffer, off_t startblock, - size_t nblocks) + FAR const uint8_t *buffer, + off_t startblock, size_t nblocks) { off_t offset; size_t nbytes; @@ -1891,8 +1917,9 @@ static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv, return ret; } - /* If this is a byte addressed SD card, then convert both the total transfer - * size to bytes and the sector start sector number to a byte offset + /* If this is a byte addressed SD card, then convert both the total + * transfer size to bytes and the sector start sector number to a byte + * offset */ nbytes = nblocks << priv->blockshift; @@ -1918,8 +1945,8 @@ static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv, /* If this is an SD card, then send ACMD23 (SET_WR_BLK_ERASE_COUNT) just * before sending CMD25 (WRITE_MULTIPLE_BLOCK). This sets the number of - * write blocks to be pre-erased and might make the following multiple block - * write command faster. + * write blocks to be pre-erased and might make the following multiple + * block write command faster. */ if (IS_SD(priv->type)) @@ -1927,10 +1954,10 @@ static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv, /* Send CMD55, APP_CMD, a verify that good R1 status is returned */ mmcsd_sendcmdpoll(priv, SD_CMD55, (uint32_t)priv->rca << 16); - ret = mmcsd_recvR1(priv, SD_CMD55); + ret = mmsd_recv_r1(priv, SD_CMD55); if (ret != OK) { - ferr("ERROR: mmcsd_recvR1 for CMD55 (ACMD23) failed: %d\n", ret); + ferr("ERROR: mmsd_recv_r1 for CMD55 (ACMD23) failed: %d\n", ret); return ret; } @@ -1939,10 +1966,10 @@ static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv, */ mmcsd_sendcmdpoll(priv, SD_ACMD23, nblocks); - ret = mmcsd_recvR1(priv, SD_ACMD23); + ret = mmsd_recv_r1(priv, SD_ACMD23); if (ret != OK) { - ferr("ERROR: mmcsd_recvR1 for ACMD23 failed: %d\n", ret); + ferr("ERROR: mmsd_recv_r1 for ACMD23 failed: %d\n", ret); return ret; } } @@ -1958,10 +1985,10 @@ static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv, */ mmcsd_sendcmdpoll(priv, MMCSD_CMD25, offset); - ret = mmcsd_recvR1(priv, MMCSD_CMD25); + ret = mmsd_recv_r1(priv, MMCSD_CMD25); if (ret != OK) { - ferr("ERROR: mmcsd_recvR1 for CMD25 failed: %d\n", ret); + ferr("ERROR: mmsd_recv_r1 for CMD25 failed: %d\n", ret); return ret; } } @@ -1997,10 +2024,10 @@ static ssize_t mmcsd_writemultiple(FAR struct mmcsd_state_s *priv, */ mmcsd_sendcmdpoll(priv, MMCSD_CMD25, offset); - ret = mmcsd_recvR1(priv, MMCSD_CMD25); + ret = mmsd_recv_r1(priv, MMCSD_CMD25); if (ret != OK) { - ferr("ERROR: mmcsd_recvR1 for CMD25 failed: %d\n", ret); + ferr("ERROR: mmsd_recv_r1 for CMD25 failed: %d\n", ret); return ret; } } @@ -2107,9 +2134,6 @@ static ssize_t mmcsd_flush(FAR void *dev, FAR const uint8_t *buffer, } #endif -/**************************************************************************** - * Block Driver Methods - ****************************************************************************/ /**************************************************************************** * Name: mmcsd_open * @@ -2241,7 +2265,8 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer, * ****************************************************************************/ -static ssize_t mmcsd_write(FAR struct inode *inode, FAR const unsigned char *buffer, +static ssize_t mmcsd_write(FAR struct inode *inode, + FAR const unsigned char *buffer, size_t startsector, unsigned int nsectors) { FAR struct mmcsd_state_s *priv; @@ -2451,18 +2476,20 @@ static void mmcsd_mediachange(FAR void *arg) mmcsd_takesem(priv); if (SDIO_PRESENT(priv->dev)) { - /* No... process the card insertion. This could cause chaos if we think - * that a card is already present and there are mounted file systems! - * NOTE that mmcsd_probe() will always re-enable callbacks appropriately. + /* No... process the card insertion. This could cause chaos if we + * think that a card is already present and there are mounted file + * systems! NOTE that mmcsd_probe() will always re-enable callbacks + * appropriately. */ mmcsd_probe(priv); } else { - /* No... process the card removal. This could have very bad implications - * for any mounted file systems! NOTE that mmcsd_removed() does NOT - * re-enable callbacks so we will need to do that here. + /* No... process the card removal. This could have very bad + * implications for any mounted file systems! NOTE that + * mmcsd_removed() does NOT re-enable callbacks so we will need to + * do that here. */ mmcsd_removed(priv); @@ -2508,7 +2535,7 @@ static int mmcsd_widebus(FAR struct mmcsd_state_s *priv) */ mmcsd_sendcmdpoll(priv, SD_CMD55, (uint32_t)priv->rca << 16); - ret = mmcsd_recvR1(priv, SD_CMD55); + ret = mmsd_recv_r1(priv, SD_CMD55); if (ret != OK) { ferr("ERROR: RECVR1 for CMD55 of ACMD42: %d\n", ret); @@ -2523,7 +2550,7 @@ static int mmcsd_widebus(FAR struct mmcsd_state_s *priv) */ mmcsd_sendcmdpoll(priv, SD_ACMD42, MMCSD_ACMD42_CD_DISCONNECT); - ret = mmcsd_recvR1(priv, SD_ACMD42); + ret = mmsd_recv_r1(priv, SD_ACMD42); if (ret != OK) { fwarn("WARNING: SD card does not support ACMD42: %d\n", ret); @@ -2535,7 +2562,7 @@ static int mmcsd_widebus(FAR struct mmcsd_state_s *priv) */ mmcsd_sendcmdpoll(priv, SD_CMD55, (uint32_t)priv->rca << 16); - ret = mmcsd_recvR1(priv, SD_CMD55); + ret = mmsd_recv_r1(priv, SD_CMD55); if (ret != OK) { ferr("ERROR: RECVR1 for CMD55 of ACMD6: %d\n", ret); @@ -2545,7 +2572,7 @@ static int mmcsd_widebus(FAR struct mmcsd_state_s *priv) /* Then send ACMD6 */ mmcsd_sendcmdpoll(priv, SD_ACMD6, MMCSD_ACMD6_BUSWIDTH_4); - ret = mmcsd_recvR1(priv, SD_ACMD6); + ret = mmsd_recv_r1(priv, SD_ACMD6); if (ret != OK) { return ret; @@ -2589,12 +2616,12 @@ static int mmcsd_mmcinitialize(FAR struct mmcsd_state_s *priv) * so there is good evidence that we have an MMC card inserted into the * slot. * - * Send CMD2, ALL_SEND_CID. This implementation supports only one MMC slot. - * If multiple cards were installed, each card would respond to CMD2 by - * sending its CID (only one card completes the response at a time). The - * driver should send CMD2 and assign an RCAs until no response to - * ALL_SEND_CID is received. CMD2 causes transition to identification state/ - * card-identification mode. + * Send CMD2, ALL_SEND_CID. This implementation supports only one MMC + * slot. If multiple cards were installed, each card would respond to + * CMD2 by sending its CID (only one card completes the response at a + * time). The driver should send CMD2 and assign an RCAs until no + * response to ALL_SEND_CID is received. CMD2 causes transition to + * identification state / card-identification mode. */ mmcsd_sendcmdpoll(priv, MMCSD_CMD2, 0); @@ -2605,7 +2632,7 @@ static int mmcsd_mmcinitialize(FAR struct mmcsd_state_s *priv) return ret; } - mmcsd_decodeCID(priv, cid); + mmcsd_decode_cid(priv, cid); /* Send CMD3, SET_RELATIVE_ADDR. This command is used to assign a logical * address to the card. For MMC, the host assigns the address. CMD3 causes @@ -2614,16 +2641,17 @@ static int mmcsd_mmcinitialize(FAR struct mmcsd_state_s *priv) priv->rca = 1; /* There is only one card */ mmcsd_sendcmdpoll(priv, MMC_CMD3, priv->rca << 16); - ret = mmcsd_recvR1(priv, MMC_CMD3); + ret = mmsd_recv_r1(priv, MMC_CMD3); if (ret != OK) { - ferr("ERROR: mmcsd_recvR1(CMD3) failed: %d\n", ret); + ferr("ERROR: mmsd_recv_r1(CMD3) failed: %d\n", ret); return ret; } - /* This should have caused a transition to standby state. However, this will - * not be reflected in the present R1 status. R1/6 contains the state of the - * card when the command was received, not when it completed execution. + /* This should have caused a transition to standby state. However, this + * will not be reflected in the present R1 status. R1/6 contains the + * state of the card when the command was received, not when it completed + * execution. * * Verify that we are in standby state/data-transfer mode */ @@ -2661,10 +2689,10 @@ static int mmcsd_mmcinitialize(FAR struct mmcsd_state_s *priv) */ mmcsd_sendcmdpoll(priv, MMCSD_CMD7S, (uint32_t)priv->rca << 16); - ret = mmcsd_recvR1(priv, MMCSD_CMD7S); + ret = mmsd_recv_r1(priv, MMCSD_CMD7S); if (ret != OK) { - ferr("ERROR: mmcsd_recvR1 for CMD7 failed: %d\n", ret); + ferr("ERROR: mmsd_recv_r1 for CMD7 failed: %d\n", ret); return ret; } @@ -2676,7 +2704,7 @@ static int mmcsd_mmcinitialize(FAR struct mmcsd_state_s *priv) if (IS_BLOCK(priv->type)) { - ret = mmcsd_mmcreadextCSD(priv); + ret = mmcsd_read_csd(priv); if (ret != OK) { ferr("ERROR: Failed to determinate number of blocks: %d\n", ret); @@ -2684,7 +2712,7 @@ static int mmcsd_mmcinitialize(FAR struct mmcsd_state_s *priv) } } - mmcsd_decodeCSD(priv, csd); + mmcsd_decode_csd(priv, csd); /* Select high speed MMC clocking (which may depend on the DSR setting) */ @@ -2694,18 +2722,18 @@ static int mmcsd_mmcinitialize(FAR struct mmcsd_state_s *priv) } /**************************************************************************** - * Name: mmcsd_mmcreadextCSD + * Name: mmcsd_read_csd * * Description: * MMC card is detected with block addressing and this function will read * the correct number of blocks and capacity. Returns OK if ext CSD is read - * correctly or error in not. + * correctly or error in not. * * Note: For some MCU architectures, buffer[] must be aligned. * ****************************************************************************/ -static int mmcsd_mmcreadextCSD (FAR struct mmcsd_state_s *priv) +static int mmcsd_read_csd(FAR struct mmcsd_state_s *priv) { uint8_t buffer[512] aligned_data(16); int ret; @@ -2781,12 +2809,12 @@ static int mmcsd_mmcreadextCSD (FAR struct mmcsd_state_s *priv) } /* Send CMD8 in data-transfer mode to obtain the - * extended Card Specific Data (CSD) register, e.g., block length, card storage - * capacity, etc. + * extended Card Specific Data (CSD) register, e.g., block length, card + * storage capacity, etc. */ mmcsd_sendcmdpoll(priv, MMC_CMD8, 0); - ret = mmcsd_recvR1(priv, MMC_CMD8); + ret = mmsd_recv_r1(priv, MMC_CMD8); if (ret != OK) { ferr("ERROR: Could not get MMC extended CSD register: %d\n", ret); @@ -2859,7 +2887,7 @@ static int mmcsd_sdinitialize(FAR struct mmcsd_state_s *priv) return ret; } - mmcsd_decodeCID(priv, cid); + mmcsd_decode_cid(priv, cid); /* Send CMD3, SET_RELATIVE_ADDR. In both protocols, this command is used * to assign a logical address to the card. For MMC, the host assigns the @@ -2870,7 +2898,7 @@ static int mmcsd_sdinitialize(FAR struct mmcsd_state_s *priv) */ mmcsd_sendcmdpoll(priv, SD_CMD3, 0); - ret = mmcsd_recvR6(priv, SD_CMD3); + ret = mmsd_recv_r6(priv, SD_CMD3); if (ret != OK) { ferr("ERROR: mmcsd_recvR2 for SD RCA failed: %d\n", ret); @@ -2879,9 +2907,10 @@ static int mmcsd_sdinitialize(FAR struct mmcsd_state_s *priv) finfo("RCA: %04x\n", priv->rca); - /* This should have caused a transition to standby state. However, this will - * not be reflected in the present R1 status. R1/6 contains the state of - * the card when the command was received, not when it completed execution. + /* This should have caused a transition to standby state. However, this + * will not be reflected in the present R1 status. R1/6 contains the + * state of the card when the command was received, not when it + * completed execution. * * Verify that we are in standby state/data-transfer mode */ @@ -2907,7 +2936,7 @@ static int mmcsd_sdinitialize(FAR struct mmcsd_state_s *priv) return ret; } - mmcsd_decodeCSD(priv, csd); + mmcsd_decode_csd(priv, csd); /* Send CMD7 with the argument == RCA in order to select the card. * Since we are supporting only a single card, we just leave the @@ -2915,10 +2944,10 @@ static int mmcsd_sdinitialize(FAR struct mmcsd_state_s *priv) */ mmcsd_sendcmdpoll(priv, MMCSD_CMD7S, (uint32_t)priv->rca << 16); - ret = mmcsd_recvR1(priv, MMCSD_CMD7S); + ret = mmsd_recv_r1(priv, MMCSD_CMD7S); if (ret != OK) { - ferr("ERROR: mmcsd_recvR1 for CMD7 failed: %d\n", ret); + ferr("ERROR: mmsd_recv_r1 for CMD7 failed: %d\n", ret); return ret; } @@ -2939,14 +2968,14 @@ static int mmcsd_sdinitialize(FAR struct mmcsd_state_s *priv) * this card supports wide bus operation. */ - ret = mmcsd_getSCR(priv, scr); + ret = mmsd_get_scr(priv, scr); if (ret != OK) { ferr("ERROR: Could not get SD SCR register(%d)\n", ret); return ret; } - mmcsd_decodeSCR(priv, scr); + mmsd_decode_scr(priv, scr); /* Select width (4-bit) bus operation (if the card supports it) */ @@ -2988,8 +3017,8 @@ static int mmcsd_cardidentify(FAR struct mmcsd_state_s *priv) priv->type = MMCSD_CARDTYPE_UNKNOWN; - /* Check if there is a card present in the slot. This is normally a matter is - * of GPIO sensing. + /* Check if there is a card present in the slot. This is normally a + * matter is of GPIO sensing. */ if (!SDIO_PRESENT(priv->dev)) @@ -3002,8 +3031,8 @@ static int mmcsd_cardidentify(FAR struct mmcsd_state_s *priv) SDIO_CLOCK(priv->dev, CLOCK_IDMODE); - /* After power up at least 74 clock cycles are required prior to starting bus - * communication + /* After power up at least 74 clock cycles are required prior to starting + * bus communication */ up_udelay(MMCSD_POWERUP_DELAY); @@ -3058,8 +3087,8 @@ static int mmcsd_cardidentify(FAR struct mmcsd_state_s *priv) if ((response & MMCSD_CARD_BUSY) != 0) { /* NO.. We really should check the current state to see if the - * MMC successfully made it to the IDLE state, but at least for now, - * we will simply assume that that is the case. + * MMC successfully made it to the IDLE state, but at least for + * now, we will simply assume that that is the case. * * Then break out of the look with an MMC card identified */ @@ -3095,8 +3124,9 @@ static int mmcsd_cardidentify(FAR struct mmcsd_state_s *priv) if (ret == OK) { - /* CMD8 succeeded this is probably a SDHC card. Verify the operating - * voltage and that the check pattern was correctly echoed + /* CMD8 succeeded this is probably a SDHC card. Verify the + * operating voltage and that the check pattern was correctly + * echoed */ if (((response & MMCSD_R7VOLTAGE_MASK) == MMCSD_R7VOLTAGE_27) && @@ -3135,36 +3165,40 @@ static int mmcsd_cardidentify(FAR struct mmcsd_state_s *priv) /* Send CMD55 with argument = 0 */ mmcsd_sendcmdpoll(priv, SD_CMD55, 0); - ret = mmcsd_recvR1(priv, SD_CMD55); + ret = mmsd_recv_r1(priv, SD_CMD55); if (ret != OK) { - /* I am a little confused.. I think both SD and MMC cards support - * CMD55 (but maybe only SD cards support CMD55). We'll make the - * the MMC vs. SD decision based on CMD1 and ACMD41. + /* I am a little confused.. I think both SD and MMC cards + * support CMD55 (but maybe only SD cards support CMD55). + * We'll make the the MMC vs. SD decision based on CMD1 and + * ACMD41. */ - ferr("ERROR: mmcsd_recvR1(CMD55) failed: %d\n", ret); + ferr("ERROR: mmsd_recv_r1(CMD55) failed: %d\n", ret); } else { /* Send ACMD41 */ mmcsd_sendcmdpoll(priv, SD_ACMD41, - MMCSD_ACMD41_VOLTAGEWINDOW_33_32 | sdcapacity); + MMCSD_ACMD41_VOLTAGEWINDOW_33_32 | + sdcapacity); ret = SDIO_RECVR3(priv->dev, SD_ACMD41, &response); if (ret != OK) { - /* If the error is a timeout, then it is probably an MMC card, - * but we will make the decision based on CMD1 below + /* If the error is a timeout, then it is probably an MMC + * card, but we will make the decision based on CMD1 + * below. */ ferr("ERROR: ACMD41 RECVR3: %d\n", ret); } else { - /* ACMD41 succeeded. ACMD41 is supported by SD V1.x and SD V2.x, - * but not MMC. If we did not previously determine that this is - * an SD V2.x (via CMD8), then this must be SD V1.x + /* ACMD41 succeeded. ACMD41 is supported by SD V1.x and + * SD V2.x, but not MMC. If we did not previously + * determine that this is an SD V2.x (via CMD8), then this + * must be SD V1.x */ finfo("R3: %08x\n", response); @@ -3174,20 +3208,20 @@ static int mmcsd_cardidentify(FAR struct mmcsd_state_s *priv) priv->type = MMCSD_CARDTYPE_SDV1; } - /* Check if the card is busy. Very confusing, BUSY is set LOW - * if the card has not finished its initialization, so it really - * means NOT busy. + /* Check if the card is busy. Very confusing, BUSY is set + * LOW if the card has not finished its initialization, + * so it really means NOT busy. */ if ((response & MMCSD_CARD_BUSY) != 0) { - /* No.. We really should check the current state to see if - * the SD card successfully made it to the IDLE state, but - * at least for now, we will simply assume that that is the - * case. + /* No.. We really should check the current state to + * see if the SD card successfully made it to the IDLE + * state, but at least for now, we will simply assume + * that that is the case. * - * Now, check if this is a SD V2.x card that supports block - * addressing + * Now, check if this is a SD V2.x card that supports + * block addressing */ if ((response & MMCSD_R3_HIGHCAPACITY) != 0) @@ -3205,27 +3239,27 @@ static int mmcsd_cardidentify(FAR struct mmcsd_state_s *priv) } } - /* If we get here then either (1) CMD55 failed, (2) CMD41 failed, or (3) - * and SD or MMC card has been identified, but it is not yet in the IDLE state. - * If SD card has not been identified, then we might be looking at an - * MMC card. We can send the CMD1 to find out for sure. CMD1 is supported - * by MMC cards, but not by SD cards. + /* If we get here then either (1) CMD55 failed, (2) CMD41 failed, or + * (3) and SD or MMC card has been identified, but it is not yet in + * the IDLE state. If SD card has not been identified, then we might + * be looking at an MMC card. We can send the CMD1 to find out for + * sure. CMD1 is supported by MMC cards, but not by SD cards. */ #ifdef CONFIG_MMCSD_MMCSUPPORT if (IS_MMC(priv->type)) { /* Send the MMC CMD1 to specify the operating voltage. CMD1 causes - * transition to ready state/ card-identification mode. NOTE: If the - * card does not support this voltage range, it will go the inactive - * state. + * transition to ready state/ card-identification mode. NOTE: If + * the card does not support this voltage range, it will go the + * inactive state. * - * NOTE: An MMC card will only respond once to CMD1 (unless it is busy). - * This is part of the logic used to determine how many MMC cards are - * connected (This implementation supports only a single MMC card). So - * we cannot re-send CMD1 without first placing the card back into - * stand-by state (if the card is busy, it will automatically - * go back to the standby state). + * NOTE: An MMC card will only respond once to CMD1 (unless it is + * busy). This is part of the logic used to determine how many + * MMC cards are connected (This implementation supports only a + * single MMC card). So we cannot re-send CMD1 without first + * placing the card back into stand-by state (if the card is busy, + * it will automatically go back to the standby state). */ mmcsd_sendcmdpoll(priv, MMC_CMD1, MMCSD_VDD_33_34 | mmccapacity); @@ -3258,15 +3292,16 @@ static int mmcsd_cardidentify(FAR struct mmcsd_state_s *priv) } /* Check if the card is busy. Very confusing, BUSY is set LOW - * if the card has not finished its initialization, so it really - * means NOT busy. + * if the card has not finished its initialization, so it + * really means NOT busy. */ if ((response & MMCSD_CARD_BUSY) != 0) { - /* NO.. We really should check the current state to see if the - * MMC successfully made it to the IDLE state, but at least for now, - * we will simply assume that that is the case. + /* NO.. We really should check the current state to see if + * the MMC successfully made it to the IDLE state, but at + * least for now we will simply assume that that is the + * case. * * Then break out of the look with an MMC card identified */ @@ -3277,6 +3312,7 @@ static int mmcsd_cardidentify(FAR struct mmcsd_state_s *priv) } } #endif + /* Check the elapsed time. We won't keep trying this forever! */ elapsed = clock_systimer() - start; @@ -3395,7 +3431,8 @@ static int mmcsd_probe(FAR struct mmcsd_state_s *priv) { /* Yes... */ - finfo("Capacity: %lu Kbytes\n", (unsigned long)(priv->capacity / 1024)); + finfo("Capacity: %lu Kbytes\n", + (unsigned long)(priv->capacity / 1024)); priv->mediachanged = true; } } @@ -3404,11 +3441,11 @@ static int mmcsd_probe(FAR struct mmcsd_state_s *priv) priv->probed = true; - /* Regardless of whether or not a card was successfully initialized, there - * is appartently a card inserted. If it wasn't successfully initialized, - * there's nothing we can do about it now. Perhaps it's a bad card? The best - * we can do is wait for the card to be ejected and re-inserted. Then we - * can try to initialize again. + /* Regardless of whether or not a card was successfully initialized, + * there is apparently a card inserted. If it wasn't successfully + * initialized, there's nothing we can do about it now. Perhaps it's + * a bad card? The best we can do is wait for the card to be ejected + * and re-inserted. Then we can try to initialize again. */ #ifdef CONFIG_MMCSD_HAVE_CARDDETECT @@ -3515,10 +3552,10 @@ static int mmcsd_hwinitialize(FAR struct mmcsd_state_s *priv) * on CD/DAT3 (both SD/MMC), * 3. Or by periodic attempts to initialize the card from software. * - * The behavior of SDIO_PRESENT() is to use whatever information is available - * on the particular platform. If no card insertion information is available - * (polling only), then SDIO_PRESENT() will always return true and we will - * try to initialize the card. + * The behavior of SDIO_PRESENT() is to use whatever information is + * available on the particular platform. If no card insertion information + * is available (polling only), then SDIO_PRESENT() will always return + * true and we will try to initialize the card. */ if (SDIO_PRESENT(priv->dev)) @@ -3614,7 +3651,8 @@ int mmcsd_slotinitialize(int minor, FAR struct sdio_dev_s *dev) /* Allocate a MMC/SD state structure */ - priv = (FAR struct mmcsd_state_s *)kmm_malloc(sizeof(struct mmcsd_state_s)); + priv = (FAR struct mmcsd_state_s *) + kmm_malloc(sizeof(struct mmcsd_state_s)); if (priv) { /* Initialize the MMC/SD state structure */ @@ -3634,9 +3672,10 @@ int mmcsd_slotinitialize(int minor, FAR struct sdio_dev_s *dev) if (ret != OK) { - /* No... But the error ENODEV is returned if hardware initialization - * succeeded but no card is inserted in the slot. In this case, the - * no error occurred, but the driver is still not ready. + /* No... But the error ENODEV is returned if hardware + * initialization succeeded but no card is inserted in the slot. + * In this case, the no error occurred, but the driver is still + * not ready. */ if (ret == -ENODEV) @@ -3683,6 +3722,7 @@ int mmcsd_slotinitialize(int minor, FAR struct sdio_dev_s *dev) goto errout_with_buffers; } } + return OK; errout_with_buffers: diff --git a/drivers/mmcsd/mmcsd_spi.c b/drivers/mmcsd/mmcsd_spi.c index e5ff295ae433..ce82a86329e9 100644 --- a/drivers/mmcsd/mmcsd_spi.c +++ b/drivers/mmcsd/mmcsd_spi.c @@ -82,6 +82,7 @@ #endif /* Slot struct info *********************************************************/ + /* Slot status definitions */ #define MMCSD_SLOTSTATUS_NOTREADY 0x01 /* Card not initialized */ @@ -90,6 +91,7 @@ #define MMCSD_SLOTSTATUS_MEDIACHGD 0x08 /* Media changed in slot */ /* Values in the MMC/SD command table ***************************************/ + /* These define the value returned by the MMC/SD command */ #define MMCSD_CMDRESP_R1 0 @@ -250,9 +252,9 @@ static struct mmcsd_slot_s g_mmcsdslot[CONFIG_MMCSD_NSLOTS]; static const uint32_t g_transpeedru[8] = { - 10000, /* 0: 100 Kbit/sec / 10 */ - 100000, /* 1: 1 Mbit/sec / 10 */ - 1000000, /* 2: 10 Mbit/sec / 10 */ + 10000, /* 0: 100 Kbit/sec / 10 */ + 100000, /* 1: 1 Mbit/sec / 10 */ + 1000000, /* 2: 10 Mbit/sec / 10 */ 10000000, /* 3: 100 Mbit/sec / 10 */ 0, 0, 0, 0 /* 4-7: Reserved values */ @@ -260,7 +262,7 @@ static const uint32_t g_transpeedru[8] = static const uint32_t g_transpeedtu[16] = { - 0, 10, 12, 13, /* 0-3: Reserved, 1.0, 1.1, 1.2, 1.3 */ + 0, 10, 12, 13, /* 0-3: Reserved, 1.0, 1.1, 1.2, 1.3 */ 15, 20, 25, 30, /* 4-7: 1.5, 2.0, 2.5, 3.0 */ 35, 40, 45, 50, /* 8-11: 3.5, 4.0, 4.5, 5.0 */ 55, 60, 70, 80, /* 12-15: 5.5, 6.0, 7.0, 8.0 */ @@ -286,16 +288,16 @@ static const uint16_t g_taactu[8] = { /* Units of nanoseconds */ - 1, /* 0: 1 ns */ - 10, /* 1: 10 ns */ - 100, /* 2: 100 ns */ + 1, /* 0: 1 ns */ + 10, /* 1: 10 ns */ + 100, /* 2: 100 ns */ /* Units of microseconds */ - 1, /* 3: 1 us 1,000 ns */ - 10, /* 4: 10 us 10,000 ns */ - 100, /* 5: 100 us 100,000 ns */ - 1000, /* 6: 1 ms 1,000,000 ns */ + 1, /* 3: 1 us 1,000 ns */ + 10, /* 4: 10 us 10,000 ns */ + 100, /* 5: 100 us 100,000 ns */ + 1000, /* 6: 1 ms 1,000,000 ns */ 10000, /* 7: 10 ms 10,000,000 ns */ }; @@ -309,27 +311,72 @@ static const uint16_t g_taactv[] = /* Commands *****************************************************************/ -static const struct mmcsd_cmdinfo_s g_cmd0 = {CMD0, MMCSD_CMDRESP_R1, 0x95}; -static const struct mmcsd_cmdinfo_s g_cmd1 = {CMD1, MMCSD_CMDRESP_R1, 0xff}; -static const struct mmcsd_cmdinfo_s g_cmd8 = {CMD8, MMCSD_CMDRESP_R7, 0x87}; -static const struct mmcsd_cmdinfo_s g_cmd9 = {CMD9, MMCSD_CMDRESP_R1, 0xff}; +static const struct mmcsd_cmdinfo_s g_cmd0 = +{ + CMD0, MMCSD_CMDRESP_R1, 0x95 +}; +static const struct mmcsd_cmdinfo_s g_cmd1 = +{ + CMD1, MMCSD_CMDRESP_R1, 0xff +}; +static const struct mmcsd_cmdinfo_s g_cmd8 = +{ + CMD8, MMCSD_CMDRESP_R7, 0x87 +}; +static const struct mmcsd_cmdinfo_s g_cmd9 = +{ + CMD9, MMCSD_CMDRESP_R1, 0xff +}; #if 0 /* Not used */ -static const struct mmcsd_cmdinfo_s g_cmd10 = {CMD10, MMCSD_CMDRESP_R1, 0xff}; +static const struct mmcsd_cmdinfo_s g_cmd10 = +{ + CMD10, MMCSD_CMDRESP_R1, 0xff +}; #endif -static const struct mmcsd_cmdinfo_s g_cmd12 = {CMD12, MMCSD_CMDRESP_R1, 0xff}; -static const struct mmcsd_cmdinfo_s g_cmd16 = {CMD16, MMCSD_CMDRESP_R1, 0xff}; -static const struct mmcsd_cmdinfo_s g_cmd17 = {CMD17, MMCSD_CMDRESP_R1, 0xff}; -static const struct mmcsd_cmdinfo_s g_cmd18 = {CMD18, MMCSD_CMDRESP_R1, 0xff}; +static const struct mmcsd_cmdinfo_s g_cmd12 = +{ + CMD12, MMCSD_CMDRESP_R1, 0xff +}; +static const struct mmcsd_cmdinfo_s g_cmd16 = +{ + CMD16, MMCSD_CMDRESP_R1, 0xff +}; +static const struct mmcsd_cmdinfo_s g_cmd17 = +{ + CMD17, MMCSD_CMDRESP_R1, 0xff +}; +static const struct mmcsd_cmdinfo_s g_cmd18 = +{ + CMD18, MMCSD_CMDRESP_R1, 0xff +}; #if !defined(CONFIG_MMCSD_READONLY) -static const struct mmcsd_cmdinfo_s g_cmd24 = {CMD24, MMCSD_CMDRESP_R1, 0xff}; -static const struct mmcsd_cmdinfo_s g_cmd25 = {CMD25, MMCSD_CMDRESP_R1, 0xff}; +static const struct mmcsd_cmdinfo_s g_cmd24 = +{ + CMD24, MMCSD_CMDRESP_R1, 0xff +}; +static const struct mmcsd_cmdinfo_s g_cmd25 = +{ + CMD25, MMCSD_CMDRESP_R1, 0xff +}; #endif -static const struct mmcsd_cmdinfo_s g_cmd55 = {CMD55, MMCSD_CMDRESP_R1, 0xff}; -static const struct mmcsd_cmdinfo_s g_cmd58 = {CMD58, MMCSD_CMDRESP_R3, 0xff}; +static const struct mmcsd_cmdinfo_s g_cmd55 = +{ + CMD55, MMCSD_CMDRESP_R1, 0xff +}; +static const struct mmcsd_cmdinfo_s g_cmd58 = +{ + CMD58, MMCSD_CMDRESP_R3, 0xff +}; #if !defined(CONFIG_MMCSD_READONLY) -static const struct mmcsd_cmdinfo_s g_acmd23 = {ACMD23, MMCSD_CMDRESP_R1, 0xff}; +static const struct mmcsd_cmdinfo_s g_acmd23 = +{ + ACMD23, MMCSD_CMDRESP_R1, 0xff +}; #endif -static const struct mmcsd_cmdinfo_s g_acmd41 = {ACMD41, MMCSD_CMDRESP_R1, 0xff}; +static const struct mmcsd_cmdinfo_s g_acmd41 = +{ + ACMD41, MMCSD_CMDRESP_R1, 0xff +}; /**************************************************************************** * Private Functions @@ -416,11 +463,11 @@ static int mmcsd_waitready(FAR struct mmcsd_slot_s *slot) elapsed = ELAPSED_TIME(start); if (elapsed > MMCSD_DELAY_10MS) - { - /* Give other threads time to run */ + { + /* Give other threads time to run */ - nxsig_usleep(10000); - } + nxsig_usleep(10000); + } } while (elapsed < MMCSD_DELAY_500MS); @@ -440,7 +487,8 @@ static int mmcsd_waitready(FAR struct mmcsd_slot_s *slot) ****************************************************************************/ static uint32_t mmcsd_sendcmd(FAR struct mmcsd_slot_s *slot, - const struct mmcsd_cmdinfo_s *cmd, uint32_t arg) + FAR const struct mmcsd_cmdinfo_s *cmd, + uint32_t arg) { FAR struct spi_dev_s *spi = slot->spi; uint32_t result; @@ -624,7 +672,7 @@ static uint32_t mmcsd_nsac(FAR struct mmcsd_slot_s *slot, uint8_t *csd, * the maximum value is 25.5K clock cycles. */ - uint32_t nsac = MMCSD_CSD_NSAC(csd) * ((uint32_t)100*1000); + uint32_t nsac = MMCSD_CSD_NSAC(csd) * ((uint32_t)100 * 1000); uint32_t fhkz = (frequency + 500) / 1000; return (nsac + (fhkz >> 1)) / fhkz; } @@ -647,7 +695,8 @@ static uint32_t mmcsd_taac(FAR struct mmcsd_slot_s *slot, uint8_t *csd) * taccess = TU*TV + NSAC/spifrequency * * g_taactu holds TU in units of nanoseconds and microseconds (you have to - * use the index to distinguish. g_taactv holds TV with 8-bits of fraction. + * use the index to distinguish. g_taactv holds TV with 8-bits of + * fraction. */ tundx = MMCSD_CSD_TAAC_TIMEUNIT(csd); @@ -663,7 +712,8 @@ static uint32_t mmcsd_taac(FAR struct mmcsd_slot_s *slot, uint8_t *csd) { /* Return the answer in microseconds */ - return (g_taactu[tundx]*g_taactv[MMCSD_CSD_TAAC_TIMEVALUE(csd)] + 0x80) >> 8; + return (g_taactu[tundx] * g_taactv[MMCSD_CSD_TAAC_TIMEVALUE(csd)] + + 0x80) >> 8; } } @@ -714,24 +764,31 @@ static void mmcsd_decodecsd(FAR struct mmcsd_slot_s *slot, uint8_t *csd) * * Example: TAAC = 1.5 ms, NSAC = 0, r2wfactor = 4, CLK_TCK=100 * taccessus = 1,500uS - * taccess = (1,500 * 100) / 100,000) + 1 = 2 (ideal, 1.5) - * twrite = (1,500 * 4 * 100) / 100,000) + 1 = 7 (ideal 6.0) + * taccess = (1,500 * 100) / 100,000) + 1 = 2 + * (ideal, 1.5) + * twrite = (1,500 * 4 * 100) / 100,000) + 1 = 7 + * (ideal 6.0) * * First get the access time in microseconds */ - uint32_t taccessus = mmcsd_taac(slot, csd) + mmcsd_nsac(slot, csd, frequency); + uint32_t taccessus = mmcsd_taac(slot, csd) + + mmcsd_nsac(slot, csd, frequency); - /* Then convert to system clock ticks. The maximum read access is 10 times - * the tacc value: taccess = 10 * (taccessus / 1,000,000) * CLK_TCK, or + /* Then convert to system clock ticks. The maximum read access is 10 + * times the tacc value: + * + * taccess = 10 * (taccessus / 1,000,000) * CLK_TCK */ slot->taccess = (taccessus * CLK_TCK) / 100000 + 1; - /* NOTE that we add one to taccess to assure that we wait at least this - * time. The write access time is larger by the R2WFACTOR: */ + /* NOTE that we add one to taccess to assure that we wait at least + * this time. The write access time is larger by the R2WFACTOR: + */ - slot->taccess = (taccessus * MMCSD_CSD_R2WFACTOR(csd) * CLK_TCK) / 100000 + 1; + slot->taccess = (taccessus * MMCSD_CSD_R2WFACTOR(csd) * CLK_TCK) / + 100000 + 1; } else { @@ -769,6 +826,7 @@ static void mmcsd_decodecsd(FAR struct mmcsd_slot_s *slot, uint8_t *csd) if (MMCSD_CSD_CSDSTRUCT(csd) != 0) { /* SDC structure ver 2.xx */ + /* Note: On SD card WRITE_BL_LEN is always the same as READ_BL_LEN */ readbllen = SD20_CSD_READBLLEN(csd); @@ -778,6 +836,7 @@ static void mmcsd_decodecsd(FAR struct mmcsd_slot_s *slot, uint8_t *csd) else { /* MMC or SD structure ver 1.xx */ + /* Note: On SD card WRITE_BL_LEN is always the same as READ_BL_LEN */ readbllen = MMCSD_CSD_READBLLEN(csd); @@ -930,7 +989,8 @@ static int mmcsd_recvblock(FAR struct mmcsd_slot_s *slot, uint8_t *buffer, /* Wait up to the maximum to receive a valid data token. taccess is the * time from when the command is sent until the first byte of data is - * received */ + * received. + */ start = START_TIME; do @@ -1218,8 +1278,8 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer, goto errout_with_eio; } - buffer += SECTORSIZE(slot); - } + buffer += SECTORSIZE(slot); + } /* Send CMD12: Stops transmission */ @@ -1251,8 +1311,9 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer, ****************************************************************************/ #if !defined(CONFIG_MMCSD_READONLY) -static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer, - size_t start_sector, unsigned int nsectors) +static ssize_t mmcsd_write(FAR struct inode *inode, + FAR const unsigned char *buffer, + size_t start_sector, unsigned int nsectors) { FAR struct mmcsd_slot_s *slot; FAR struct spi_dev_s *spi; @@ -1376,7 +1437,7 @@ static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer, ferr("ERROR: ACMD23 failed: R1=%02x\n", response); goto errout_with_sem; } - } + } /* Send CMD25: Continuously write blocks of data until the * transmission is stopped. @@ -1398,6 +1459,7 @@ static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer, ferr("ERROR: Failed: to receive the block\n"); goto errout_with_sem; } + buffer += SECTORSIZE(slot); if (mmcsd_waitready(slot) != OK) @@ -1493,7 +1555,8 @@ static int mmcsd_geometry(FAR struct inode *inode, struct geometry *geometry) /* Then return the card geometry */ geometry->geo_available = - ((slot->state & (MMCSD_SLOTSTATUS_NOTREADY | MMCSD_SLOTSTATUS_NODISK)) == 0); + ((slot->state & (MMCSD_SLOTSTATUS_NOTREADY | + MMCSD_SLOTSTATUS_NODISK)) == 0); geometry->geo_mediachanged = ((slot->state & MMCSD_SLOTSTATUS_MEDIACHGD) != 0); #if !defined(CONFIG_MMCSD_READONLY) @@ -1521,10 +1584,6 @@ static int mmcsd_geometry(FAR struct inode *inode, struct geometry *geometry) return OK; } -/**************************************************************************** - * Initialization - ****************************************************************************/ - /**************************************************************************** * Name: mmcsd_mediainitialize * @@ -1551,10 +1610,10 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot) slot->state |= MMCSD_SLOTSTATUS_NOTREADY; - /* Check if there is a card present in the slot. This is normally a matter is - * of GPIO sensing and does not really involve SPI, but by putting this - * functionality in the SPI interface, we encapsulate the SPI MMC/SD - * interface + /* Check if there is a card present in the slot. This is normally a + * matter is of GPIO sensing and does not really involve SPI, but by + * putting this functionality in the SPI interface, we encapsulate the + * SPI MMC/SD interface */ if ((SPI_STATUS(spi, SPIDEV_MMCSD(0)) & SPI_STATUS_PRESENT) == 0) @@ -1632,7 +1691,8 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot) { /* Verify the operating voltage and that the 0xaa was correctly echoed */ - if (((slot->r7 & MMCSD_SPIR7_VOLTAGE_MASK) == MMCSD_SPIR7_VOLTAGE_27) && + if (((slot->r7 & MMCSD_SPIR7_VOLTAGE_MASK) == + MMCSD_SPIR7_VOLTAGE_27) && ((slot->r7 & MMCSD_SPIR7_ECHO_MASK) == 0xaa)) { /* Try CMD55/ACMD41 for up to 1 second or until the card exits @@ -1645,7 +1705,8 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot) { finfo("%d. Send CMD55/ACMD41\n", elapsed); result = mmcsd_sendcmd(slot, &g_cmd55, 0); - if (result == MMCSD_SPIR1_IDLESTATE || result == MMCSD_SPIR1_OK) + if (result == MMCSD_SPIR1_IDLESTATE || + result == MMCSD_SPIR1_OK) { result = mmcsd_sendcmd(slot, &g_acmd41, (uint32_t)1 << 30); if (result == MMCSD_SPIR1_OK) @@ -1661,26 +1722,27 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot) /* Check if ACMD41 was sent successfully */ if (elapsed < MMCSD_DELAY_1SEC) - { - finfo("Send CMD58\n"); + { + finfo("Send CMD58\n"); - SPI_SEND(spi, 0xff); - result = mmcsd_sendcmd(slot, &g_cmd58, 0); - if (result == MMCSD_SPIR1_OK) - { + SPI_SEND(spi, 0xff); + result = mmcsd_sendcmd(slot, &g_cmd58, 0); + if (result == MMCSD_SPIR1_OK) + { finfo("OCR: %08x\n", slot->ocr); if ((slot->ocr & MMCSD_OCR_CCS) != 0) { finfo("Identified SD ver2 card/with block access\n"); - slot->type = MMCSD_CARDTYPE_SDV2 | MMCSD_CARDTYPE_BLOCK; + slot->type = MMCSD_CARDTYPE_SDV2 | + MMCSD_CARDTYPE_BLOCK; } else { finfo("Identified SD ver2 card\n"); slot->type = MMCSD_CARDTYPE_SDV2; } - } - } + } + } } } @@ -1714,7 +1776,8 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot) { finfo("%d. Send CMD55/ACMD41\n", elapsed); result = mmcsd_sendcmd(slot, &g_cmd55, 0); - if (result == MMCSD_SPIR1_IDLESTATE || result == MMCSD_SPIR1_OK) + if (result == MMCSD_SPIR1_IDLESTATE || + result == MMCSD_SPIR1_OK) { result = mmcsd_sendcmd(slot, &g_acmd41, 0); if (result == MMCSD_SPIR1_OK) @@ -1733,7 +1796,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot) slot->type = MMCSD_CARDTYPE_MMC; break; } - } + } elapsed = ELAPSED_TIME(start); } @@ -1785,13 +1848,13 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot) */ #ifdef CONFIG_MMCSD_SECTOR512 - /* Using 512 byte sectors, the maximum ver1.x capacity is 4096 x 512 blocks. - * The saved slot->nsectors is converted to 512 byte blocks, so if slot->nsectors - * exceeds 4096 x 512, then we must be dealing with a card with read_bl_len - * of 1024 or 2048. + /* Using 512 byte sectors, the maximum ver1.x capacity is 4096 x 512 + * blocks. The saved slot->nsectors is converted to 512 byte blocks, so + * if slot->nsectors exceeds 4096 x 512, then we must be dealing with a + * card with read_bl_len of 1024 or 2048. */ - if (!IS_SDV2(slot->type) && slot->nsectors <= ((uint32_t)4096*12)) + if (!IS_SDV2(slot->type) && slot->nsectors <= ((uint32_t)4096 * 12)) { /* Don't set the block len on high capacity cards (ver1.x or ver2.x) */ @@ -1865,7 +1928,8 @@ static void mmcsd_mediachanged(void *arg) * ready, then try re-initializing it */ - else if ((oldstate & (MMCSD_SLOTSTATUS_NODISK | MMCSD_SLOTSTATUS_NOTREADY)) != 0) + else if ((oldstate & (MMCSD_SLOTSTATUS_NODISK | + MMCSD_SLOTSTATUS_NOTREADY)) != 0) { /* (Re-)initialize for the media in the slot */ @@ -1909,7 +1973,8 @@ int mmcsd_spislotinitialize(int minor, int slotno, FAR struct spi_dev_s *spi) int ret; #ifdef CONFIG_DEBUG_FEATURES - if ((unsigned)slotno >= CONFIG_MMCSD_NSLOTS || (unsigned)minor > 255 || !spi) + if ((unsigned)slotno >= CONFIG_MMCSD_NSLOTS || (unsigned)minor > 255 || + spi == NULL) { ferr("ERROR: Invalid arguments\n"); return -EINVAL; diff --git a/drivers/mtd/filemtd.c b/drivers/mtd/filemtd.c index ed9eb2c12d92..252d50aeefb5 100644 --- a/drivers/mtd/filemtd.c +++ b/drivers/mtd/filemtd.c @@ -56,6 +56,7 @@ /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ + /* Configuration ************************************************************/ #ifndef CONFIG_FILEMTD_BLOCKSIZE @@ -383,9 +384,9 @@ static ssize_t filemtd_byteread(FAR struct mtd_dev_s *dev, off_t offset, /* Don't let read read past end of buffer */ if (offset + nbytes > priv->nblocks * priv->erasesize) - { - return 0; - } + { + return 0; + } filemtd_read(priv, buf, offset, nbytes); return nbytes; @@ -438,8 +439,8 @@ static int filemtd_ioctl(FAR struct mtd_dev_s *dev, int cmd, if (geo) { - /* Populate the geometry structure with information need to know - * the capacity and how to access the device. + /* Populate the geometry structure with information need to + * know the capacity and how to access the device. */ geo->blocksize = priv->blocksize; @@ -486,8 +487,9 @@ static int filemtd_ioctl(FAR struct mtd_dev_s *dev, int cmd, * ****************************************************************************/ -FAR struct mtd_dev_s *blockmtd_initialize(FAR const char *path, size_t offset, - size_t mtdlen, int16_t sectsize, +FAR struct mtd_dev_s *blockmtd_initialize(FAR const char *path, + size_t offset, size_t mtdlen, + int16_t sectsize, int32_t erasesize) { FAR struct file_dev_s *priv; diff --git a/drivers/mtd/smart.c b/drivers/mtd/smart.c index 8700c130229d..bc2d8632e579 100644 --- a/drivers/mtd/smart.c +++ b/drivers/mtd/smart.c @@ -117,12 +117,14 @@ #define SMART_PARTNAME_SIZE 4 #define SMART_FIRST_DIR_SECTOR 3 /* First root directory sector */ -#define SMART_FIRST_ALLOC_SECTOR 12 /* First logical sector number we will - * use for assignment of requested alloc - * sectors. All entries below this are - * reserved (some for root dir entries, - * other for our use, such as format - * sector, etc. */ +#define SMART_FIRST_ALLOC_SECTOR 12 /* First logical sector number + * we will use for assignment + * of requested alloc sectors. + * All entries below this are + * reserved (some for root dir + * entries other for our use + * such as format, sector, + * etc.) */ #if defined(CONFIG_MTD_SMART_READAHEAD) || (defined(CONFIG_DRVR_WRITABLE) && \ defined(CONFIG_MTD_SMART_WRITEBUFFER)) @@ -252,7 +254,7 @@ struct smart_struct_s FAR uint8_t *releasecount; /* Count of released sectors per erase block */ FAR uint8_t *freecount; /* Count of free sectors per erase block */ FAR char *rwbuffer; /* Our sector read/write buffer */ - char partname[SMART_PARTNAME_SIZE]; /* Optional partition name */ + char partname[SMART_PARTNAME_SIZE]; uint8_t formatversion; /* Format version on the device */ uint8_t formatstatus; /* Indicates the status of the device format */ uint8_t namesize; /* Length of filenames on this device */ @@ -375,27 +377,27 @@ typedef uint32_t crc_t; #if defined(CONFIG_MTD_SMART_ENABLE_CRC) && defined(CONFIG_SMART_CRC_32) struct smart_chain_header_s { - uint8_t nextsector[4];/* Next logical sector in the chain */ - uint8_t used[4]; /* Number of bytes used in this sector */ - uint8_t type; /* Type of sector entry (file or dir) */ + uint8_t nextsector[4]; /* Next logical sector in the chain */ + uint8_t used[4]; /* Number of bytes used in this sector */ + uint8_t type; /* Type of sector entry (file or dir) */ }; #else struct smart_chain_header_s { - uint8_t type; /* Type of sector entry (file or dir) */ - uint8_t nextsector[2];/* Next logical sector in the chain */ - uint8_t used[2]; /* Number of bytes used in this sector */ + uint8_t type; /* Type of sector entry (file or dir) */ + uint8_t nextsector[2]; /* Next logical sector in the chain */ + uint8_t used[2]; /* Number of bytes used in this sector */ }; #endif struct smart_entry_header_s { - uint16_t flags; /* Flags, including permissions: - * 15: Empty entry - * 14: Active entry - * 12-0: Permissions bits */ - int16_t firstsector; /* Sector number of the name */ - uint32_t utc; /* Time stamp */ + uint16_t flags; /* Flags, including permissions: + * 15: Empty entry + * 14: Active entry + * 12-0: Permissions bits */ + int16_t firstsector; /* Sector number of the name */ + uint32_t utc; /* Time stamp */ }; /**************************************************************************** @@ -408,40 +410,47 @@ static ssize_t smart_reload(struct smart_struct_s *dev, FAR uint8_t *buffer, off_t startblock, size_t nblocks); static ssize_t smart_read(FAR struct inode *inode, unsigned char *buffer, size_t start_sector, unsigned int nsectors); -static ssize_t smart_write(FAR struct inode *inode, const unsigned char *buffer, - size_t start_sector, unsigned int nsectors); -static int smart_geometry(FAR struct inode *inode, struct geometry *geometry); -static int smart_ioctl(FAR struct inode *inode, int cmd, unsigned long arg); +static ssize_t smart_write(FAR struct inode *inode, + FAR const unsigned char *buffer, size_t start_sector, + unsigned int nsectors); +static int smart_geometry(FAR struct inode *inode, + FAR struct geometry *geometry); +static int smart_ioctl(FAR struct inode *inode, int cmd, + unsigned long arg); static int smart_findfreephyssector(FAR struct smart_struct_s *dev, uint8_t canrelocate); -static int smart_writesector(FAR struct smart_struct_s *dev, unsigned long arg); +static int smart_writesector(FAR struct smart_struct_s *dev, + unsigned long arg); static inline int smart_allocsector(FAR struct smart_struct_s *dev, unsigned long requested); -static int smart_readsector(FAR struct smart_struct_s *dev, unsigned long arg); +static int smart_readsector(FAR struct smart_struct_s *dev, + unsigned long arg); #ifdef CONFIG_MTD_SMART_ENABLE_CRC -static int smart_validate_crc(FAR struct smart_struct_s *dev); +static int smart_validate_crc(FAR struct smart_struct_s *dev); #endif #ifdef CONFIG_MTD_SMART_WEAR_LEVEL -static int smart_read_wearstatus(FAR struct smart_struct_s *dev); -static int smart_relocate_static_data(FAR struct smart_struct_s *dev, uint16_t block); +static int smart_read_wearstatus(FAR struct smart_struct_s *dev); +static int smart_relocate_static_data(FAR struct smart_struct_s *dev, + uint16_t block); #endif -static int smart_relocate_sector(FAR struct smart_struct_s *dev, +static int smart_relocate_sector(FAR struct smart_struct_s *dev, uint16_t oldsector, uint16_t newsector); #ifdef CONFIG_MTD_SMART_FSCK -static int smart_fsck(FAR struct smart_struct_s *dev); +static int smart_fsck(FAR struct smart_struct_s *dev); #endif #ifdef CONFIG_SMART_DEV_LOOP static ssize_t smart_loop_read(FAR struct file *filep, FAR char *buffer, size_t buflen); -static ssize_t smart_loop_write(FAR struct file *filep, FAR const char *buffer, - size_t buflen); -static int smart_loop_ioctl(FAR struct file *filep, int cmd, unsigned long arg); +static ssize_t smart_loop_write(FAR struct file *filep, + FAR const char *buffer, size_t buflen); +static int smart_loop_ioctl(FAR struct file *filep, int cmd, + unsigned long arg); #endif /* CONFIG_SMART_DEV_LOOP */ /**************************************************************************** @@ -625,15 +634,17 @@ static void smart_set_count(FAR struct smart_struct_s *dev, if (block & 0x01) { - pcount[block >> 1] = (pcount[block >> 1] & 0xf0) | (count & 0x0f); + pcount[block >> 1] = (pcount[block >> 1] & 0xf0) | + (count & 0x0f); } else { - pcount[block >> 1] = (pcount[block >> 1] & 0x0f) | ((count & 0x0f) << 4); + pcount[block >> 1] = (pcount[block >> 1] & 0x0f) | + ((count & 0x0f) << 4); } - /* If we have 16 sectors per block, then the upper bit (representing 16) - * all get packed into shared bytes. + /* If we have 16 sectors per block, then the upper bit (representing + * 16) all get packed into shared bytes. */ if (dev->sectorsperblk == 16) @@ -684,8 +695,8 @@ static uint8_t smart_get_count(FAR struct smart_struct_s *dev, count = pcount[block >> 1] >> 4; } - /* If we have 16 sectors per block, then the upper bit (representing 16) - * all get packed into shared bytes. + /* If we have 16 sectors per block, then the upper bit (representing + * 16) all get packed into shared bytes. */ if (dev->sectorsperblk == 16) @@ -731,9 +742,11 @@ static void smart_add_count(struct smart_struct_s *dev, uint8_t *pcount, #ifdef CONFIG_SMART_LOCAL_CHECKFREE int smart_checkfree(FAR struct smart_struct_s *dev, int lineno) { - uint16_t x, freecount; + uint16_t x; + uint16_t freecount; #ifdef CONFIG_DEBUG_FS - uint16_t blockfree, blockrelease; + uint16_t blockfree; + uint16_t blockrelease; static uint16_t prev_freesectors = 0; static uint16_t prev_releasesectors = 0; static uint8_t *prev_freecount = NULL; @@ -790,8 +803,8 @@ int smart_checkfree(FAR struct smart_struct_s *dev, int lineno) } } - /* Modify the freesector count to reflect the actual calculated freecount - * to get us back in line. + /* Modify the freesector count to reflect the actual calculated + * freecount to get us back in line. */ dev->freesectors = freecount; @@ -914,7 +927,8 @@ static ssize_t smart_write(FAR struct inode *inode, size_t remaining; size_t nxfrd; int ret; - off_t mtdstartblock, mtdblockcount; + off_t mtdstartblock; + off_t mtdblockcount; finfo("sector: %d nsectors: %d\n", start_sector, nsectors); @@ -1183,15 +1197,17 @@ static int smart_setsectorsize(FAR struct smart_struct_s *dev, uint16_t size) #ifndef CONFIG_MTD_SMART_MINIMIZE_RAM allocsize = dev->neraseblocks << 1; - dev->smap = (FAR uint16_t *) smart_malloc(dev, totalsectors * sizeof(uint16_t) + - allocsize, "Sector map"); + dev->smap = (FAR uint16_t *) + smart_malloc(dev, totalsectors * sizeof(uint16_t) + allocsize, + "Sector map"); if (!dev->smap) { ferr("ERROR: Error allocating SMART virtual map buffer\n"); goto errexit; } - dev->releasecount = (FAR uint8_t *) dev->smap + (totalsectors * sizeof(uint16_t)); + dev->releasecount = (FAR uint8_t *) dev->smap + + (totalsectors * sizeof(uint16_t)); dev->freecount = dev->releasecount + dev->neraseblocks; #else dev->sbitmap = (FAR uint8_t *) @@ -1411,7 +1427,8 @@ static ssize_t smart_bytewrite(FAR struct smart_struct_s *dev, size_t offset, /* Write the data back to the device */ - ret = MTD_BWRITE(dev->mtd, startblock, nblocks, (FAR uint8_t *) dev->rwbuffer); + ret = MTD_BWRITE(dev->mtd, startblock, nblocks, + (FAR uint8_t *) dev->rwbuffer); if (ret < 0) { ferr("ERROR: Error %d writing to device\n", -ret); @@ -1442,8 +1459,9 @@ static ssize_t smart_bytewrite(FAR struct smart_struct_s *dev, size_t offset, static int smart_add_sector_to_cache(FAR struct smart_struct_s *dev, uint16_t logical, uint16_t physical, int line) { - uint16_t index, x; - uint16_t oldest; + uint16_t index; + uint16_t x; + uint16_t oldest; /* If we aren't full yet, just add the sector to the end of the list */ @@ -1512,16 +1530,21 @@ static int smart_add_sector_to_cache(FAR struct smart_struct_s *dev, * If the sector is in the cache, then update the hitcount and * return the physical mapping. If a cache miss occurs, then * the routine will scan the volume to find the logical sector - * and add / replace a cache entry with the newly located sector. + * and add / replace a cache entry with the newly located + * sector. * ****************************************************************************/ #ifdef CONFIG_MTD_SMART_MINIMIZE_RAM -static uint16_t smart_cache_lookup(FAR struct smart_struct_s *dev, uint16_t logical) +static uint16_t smart_cache_lookup(FAR struct smart_struct_s *dev, + uint16_t logical) { int ret; - uint16_t block, sector; - uint16_t x, physical, logicalsector; + uint16_t block; + uint16_t sector; + uint16_t x; + uint16_t physical; + uint16_t logicalsector; struct smart_sect_header_s header; size_t readaddress; @@ -1560,7 +1583,9 @@ static uint16_t smart_cache_lookup(FAR struct smart_struct_s *dev, uint16_t logi * numbers in each erase block first. */ - for (sector = 0; sector < dev->availsectperblk && physical == 0xffff; sector++) + for (sector = 0; + sector < dev->availsectperblk && physical == 0xffff; + sector++) { /* Now scan across each erase block */ @@ -1574,7 +1599,8 @@ static uint16_t smart_cache_lookup(FAR struct smart_struct_s *dev, uint16_t logi /* Read the header for this sector */ ret = MTD_READ(dev->mtd, readaddress, - sizeof(struct smart_sect_header_s), (FAR uint8_t *) &header); + sizeof(struct smart_sect_header_s), + (FAR uint8_t *) &header); if (ret != sizeof(struct smart_sect_header_s)) { goto err_out; @@ -1606,7 +1632,8 @@ static uint16_t smart_cache_lookup(FAR struct smart_struct_s *dev, uint16_t logi continue; } - if ((header.status & SMART_STATUS_VERBITS) != SMART_STATUS_VERSION) + if ((header.status & SMART_STATUS_VERBITS) != + SMART_STATUS_VERSION) { continue; } @@ -1618,7 +1645,8 @@ static uint16_t smart_cache_lookup(FAR struct smart_struct_s *dev, uint16_t logi /* This is the sector we are looking for! Add it to the cache */ physical = block * dev->sectorsperblk + sector; - smart_add_sector_to_cache(dev, logical, physical, __LINE__); + smart_add_sector_to_cache(dev, logical, physical, + __LINE__); break; } } @@ -1701,9 +1729,10 @@ static void smart_update_cache(FAR struct smart_struct_s *dev, uint16_t ****************************************************************************/ #ifdef CONFIG_MTD_SMART_WEAR_LEVEL -static uint8_t smart_get_wear_level(FAR struct smart_struct_s *dev, uint16_t block) +static uint8_t smart_get_wear_level(FAR struct smart_struct_s *dev, + uint16_t block) { - uint8_t bits; + uint8_t bits; bits = dev->wearstatus[block >> SMART_WEAR_BIT_DIVIDE]; if (block & 0x01) @@ -1730,8 +1759,8 @@ static uint8_t smart_get_wear_level(FAR struct smart_struct_s *dev, uint16_t blo * * Description: Find the minimum and maximum wear levels. This is used when * we increment the wear level of a minimum value block so that - * we can detect if a new minimum exists and perform normalization - * of the wear-levels. + * we can detect if a new minimum exists and perform + * normalization of the wear-levels. * ****************************************************************************/ @@ -1801,10 +1830,11 @@ static void smart_find_wear_minmax(FAR struct smart_struct_s *dev) ****************************************************************************/ #ifdef CONFIG_MTD_SMART_WEAR_LEVEL -static int smart_set_wear_level(FAR struct smart_struct_s *dev, uint16_t block, - uint8_t level) +static int smart_set_wear_level(FAR struct smart_struct_s *dev, + uint16_t block, uint8_t level) { - uint8_t bits, oldlevel; + uint8_t bits; + uint8_t oldlevel; /* Get the old wear level to test if we need to update min / max */ @@ -1891,7 +1921,8 @@ static int smart_scan(FAR struct smart_struct_s *dev) int sector; int ret; uint16_t totalsectors; - uint16_t sectorsize, prerelease; + uint16_t sectorsize; + uint16_t prerelease; uint16_t logicalsector; uint16_t winner; uint16_t loser; @@ -1937,7 +1968,8 @@ static int smart_scan(FAR struct smart_struct_s *dev) { /* Read the next sector from the device */ - ret = MTD_READ(dev->mtd, readaddress, sizeof(struct smart_sect_header_s), + ret = MTD_READ(dev->mtd, readaddress, + sizeof(struct smart_sect_header_s), (FAR uint8_t *) &header); if (ret != sizeof(struct smart_sect_header_s)) { @@ -1946,7 +1978,8 @@ static int smart_scan(FAR struct smart_struct_s *dev) if (header.status != CONFIG_SMARTFS_ERASEDSTATE) { - sectorsize = sizetbl[(header.status & SMART_STATUS_SIZEBITS) >> 2]; + sectorsize = + sizetbl[(header.status & SMART_STATUS_SIZEBITS) >> 2]; break; } @@ -1998,7 +2031,8 @@ static int smart_scan(FAR struct smart_struct_s *dev) } #ifdef CONFIG_MTD_SMART_PACK_COUNTS - smart_set_count(dev, dev->freecount, sector, dev->availsectperblk - prerelease); + smart_set_count(dev, dev->freecount, sector, + dev->availsectperblk - prerelease); smart_set_count(dev, dev->releasecount, sector, prerelease); #else dev->freecount[sector] = dev->availsectperblk - prerelease; @@ -2037,8 +2071,9 @@ static int smart_scan(FAR struct smart_struct_s *dev) /* Read the header for this sector */ - ret = MTD_READ(dev->mtd, readaddress, sizeof(struct smart_sect_header_s), - (FAR uint8_t *) &header); + ret = MTD_READ(dev->mtd, readaddress, + sizeof(struct smart_sect_header_s), + (FAR uint8_t *)&header); if (ret != sizeof(struct smart_sect_header_s)) { goto err_out; @@ -2086,7 +2121,8 @@ static int smart_scan(FAR struct smart_struct_s *dev) dev->releasesectors++; #ifdef CONFIG_MTD_SMART_PACK_COUNTS - smart_add_count(dev, dev->releasecount, sector / dev->sectorsperblk, 1); + smart_add_count(dev, dev->releasecount, + sector / dev->sectorsperblk, 1); #else dev->releasecount[sector / dev->sectorsperblk]++; #endif @@ -2156,13 +2192,14 @@ static int smart_scan(FAR struct smart_struct_s *dev) { if (dev->partname[0] != '\0') { - snprintf(dev->rwbuffer, sizeof(devname), "/dev/smart%d%sd%d", - dev->minor, dev->partname, x + 1); + snprintf(dev->rwbuffer, sizeof(devname), + "/dev/smart%d%sd%d", + dev->minor, dev->partname, x + 1); } else { - snprintf(devname, sizeof(devname), "/dev/smart%dd%d", dev->minor, - x + 1); + snprintf(devname, sizeof(devname), "/dev/smart%dd%d", + dev->minor, x + 1); } /* Inode private data is a reference to a struct containing @@ -2182,9 +2219,12 @@ static int smart_scan(FAR struct smart_struct_s *dev) rootdirdev->dev = dev; rootdirdev->rootdirnum = x; - ret = register_blockdriver(dev->rwbuffer, &g_bops, 0, rootdirdev); + ret = register_blockdriver(dev->rwbuffer, &g_bops, 0, + rootdirdev); - /* Inode private data is a reference to the SMART device structure */ + /* Inode private data is a reference to the SMART device + * structure. + */ ret = register_blockdriver(devname, &g_bops, 0, rootdirdev); } @@ -2232,7 +2272,8 @@ static int smart_scan(FAR struct smart_struct_s *dev) { /* Calculate the read address for this sector */ - readaddress = dupsector * dev->mtdblkspersector * dev->geo.blocksize; + readaddress = dupsector * dev->mtdblkspersector * + dev->geo.blocksize; /* Read the header for this sector */ @@ -2271,7 +2312,8 @@ static int smart_scan(FAR struct smart_struct_s *dev) continue; } - if ((header.status & SMART_STATUS_VERBITS) != SMART_STATUS_VERSION) + if ((header.status & SMART_STATUS_VERBITS) != + SMART_STATUS_VERSION) { continue; } @@ -2285,8 +2327,9 @@ static int smart_scan(FAR struct smart_struct_s *dev) } #endif - ret = MTD_READ(dev->mtd, readaddress, sizeof(struct smart_sect_header_s), - (FAR uint8_t *) &header); + ret = MTD_READ(dev->mtd, readaddress, + sizeof(struct smart_sect_header_s), + (FAR uint8_t *) &header); if (ret != sizeof(struct smart_sect_header_s)) { goto err_out; @@ -2340,7 +2383,8 @@ static int smart_scan(FAR struct smart_struct_s *dev) /* Check CRC of the winner sector just in case */ ret = MTD_BREAD(dev->mtd, winner * dev->mtdblkspersector, - dev->mtdblkspersector, (FAR uint8_t *) dev->rwbuffer); + dev->mtdblkspersector, + (FAR uint8_t *) dev->rwbuffer); if (ret == dev->mtdblkspersector) { /* Validate the CRC of the read-back data */ @@ -2350,9 +2394,9 @@ static int smart_scan(FAR struct smart_struct_s *dev) if (ret != OK) { - /* The winner sector has CRC error, so we select the loser sector. - * After swapping the winner and the loser sector, we will release - * the loser sector with CRC error. + /* The winner sector has CRC error, so we select the loser + * sector. After swapping the winner and the loser sector, we + * will release the loser sector with CRC error. */ if (sector == winner) @@ -2381,8 +2425,9 @@ static int smart_scan(FAR struct smart_struct_s *dev) /* Now release the loser sector */ readaddress = loser * dev->mtdblkspersector * dev->geo.blocksize; - ret = MTD_READ(dev->mtd, readaddress, sizeof(struct smart_sect_header_s), - (FAR uint8_t *) &header); + ret = MTD_READ(dev->mtd, readaddress, + sizeof(struct smart_sect_header_s), + (FAR uint8_t *)&header); if (ret != sizeof(struct smart_sect_header_s)) { goto err_out; @@ -2393,8 +2438,9 @@ static int smart_scan(FAR struct smart_struct_s *dev) #else header.status |= SMART_STATUS_RELEASED; #endif - offset = readaddress + offsetof(struct smart_sect_header_s, status); - ret = smart_bytewrite(dev, offset, 1, &header.status); + offset = readaddress + + offsetof(struct smart_sect_header_s, status); + ret = smart_bytewrite(dev, offset, 1, &header.status); if (ret < 0) { ferr("ERROR: Error %d releasing duplicate sector\n", -ret); @@ -2490,8 +2536,10 @@ static int smart_scan(FAR struct smart_struct_s *dev) #else smart_update_cache(dev, 0, newsector); #ifdef CONFIG_MTD_SMART_PACK_COUNTS - smart_add_count(dev, dev->freecount, newsector / dev->sectorsperblk, -1); - smart_add_count(dev, dev->releasecount, sector / dev->sectorsperblk, 1); + smart_add_count(dev, dev->freecount, + newsector / dev->sectorsperblk, -1); + smart_add_count(dev, dev->releasecount, + sector / dev->sectorsperblk, 1); #endif #endif } @@ -2531,7 +2579,8 @@ static int smart_scan(FAR struct smart_struct_s *dev) { if (dev->alloc[sector].ptr != NULL) { - finfo(" %s: %d\n", dev->alloc[sector].name, dev->alloc[sector].size); + finfo(" %s: %d\n", + dev->alloc[sector].name, dev->alloc[sector].size); } } #endif @@ -2593,10 +2642,10 @@ static inline int smart_getformat(FAR struct smart_struct_s *dev, } fmt->sectorsize = dev->sectorsize; - fmt->availbytes = dev->sectorsize - sizeof(struct smart_sect_header_s); + fmt->availbytes = dev->sectorsize - + sizeof(struct smart_sect_header_s); fmt->nsectors = dev->totalsectors; - - fmt->nfreesectors = dev->freesectors; + fmt->nfreesectors = dev->freesectors; fmt->namesize = dev->namesize; #ifdef CONFIG_SMARTFS_MULTI_ROOT_DIRS fmt->nrootdirentries = dev->rootdirentries; @@ -2687,11 +2736,11 @@ static void smart_erase_block_if_empty(FAR struct smart_struct_s *dev, dev->freecount[block] = dev->availsectperblk - prerelease; #endif - /* Now that we have erased this block and updated the release / free counts, - * if we are in WEAR LEVELING enabled mode, we must check if this erase block's - * wear level has reached the threshold to warrant moving a minimum wear level - * block's data into it (i.e. relocating static data to this block so it will - * be worn less). + /* Now that we have erased this block and updated the release / free + * counts, if we are in WEAR LEVELING enabled mode, we must check if + * this erase block's wear level has reached the threshold to warrant + * moving a minimum wear level block's data into it (i.e. relocating + * static data to this block so it will be worn less). */ #ifdef CONFIG_MTD_SMART_WEAR_LEVEL @@ -2720,7 +2769,8 @@ static void smart_erase_block_if_empty(FAR struct smart_struct_s *dev, ****************************************************************************/ #ifdef CONFIG_MTD_SMART_WEAR_LEVEL -static int smart_relocate_static_data(FAR struct smart_struct_s *dev, uint16_t block) +static int smart_relocate_static_data(FAR struct smart_struct_s *dev, + uint16_t block) { uint16_t freecount, x, sector, minblock; uint16_t nextsector, newsector, mincount; @@ -2730,11 +2780,11 @@ static int smart_relocate_static_data(FAR struct smart_struct_s *dev, uint16_t b FAR struct smart_allocsector_s *allocsector; #endif - /* Now that we have erased this block and updated the release / free counts, - * if we are in WEAR LEVELING enabled mode, we must check if this erase block's - * wear level has reached the threshold to warrant moving a minimum wear level - * block's data into it (i.e. relocating static data to this block so it will - * be worn less). + /* Now that we have erased this block and updated the release / free + * counts, if we are in WEAR LEVELING enabled mode, we must check if this + * erase block's wear level has reached the threshold to warrant moving a + * minimum wear level block's data into it (i.e. relocating static data to + * this block so it will be worn less). */ ret = OK; @@ -2791,8 +2841,9 @@ static int smart_relocate_static_data(FAR struct smart_struct_s *dev, uint16_t b if (freecount == 0) { - /* We found a minimum wear-level block with no free sectors. - * relocate this block to the more highly worn block. + /* We found a minimum wear-level block with no free + * sectors. relocate this block to the more highly worn + * block. */ break; @@ -2819,10 +2870,11 @@ static int smart_relocate_static_data(FAR struct smart_struct_s *dev, uint16_t b nextsector = dev->freecount[x]; newsector = dev->releasecount[x]; #endif - finfo("Moving block %d, wear %d, free %d, released %d to block %d, wear %d\n", - x, smart_get_wear_level(dev, x), - nextsector, newsector, - block, smart_get_wear_level(dev, block)); + finfo("Moving block %d, wear %d, free %d, " + "released %d to block %d, wear %d\n", + x, smart_get_wear_level(dev, x), + nextsector, newsector, + block, smart_get_wear_level(dev, block)); nextsector = block * dev->sectorsperblk; for (sector = x * dev->sectorsperblk; sector < @@ -2878,7 +2930,8 @@ static int smart_relocate_static_data(FAR struct smart_struct_s *dev, uint16_t b /* Update the temporary allocation's physical sector */ allocsector->physical = newsector; - *((FAR uint16_t *) header->logicalsector) = allocsector->logical; + *((FAR uint16_t *) header->logicalsector) = + allocsector->logical; } else #endif @@ -2992,8 +3045,8 @@ static crc_t smart_calc_sector_crc(FAR struct smart_struct_s *dev) /* Add status and seq to the CRC calculation */ - crc = crc16part((uint8_t *) &dev->rwbuffer[offsetof(struct smart_sect_header_s, - status)], 2, crc); + crc = crc16part((uint8_t *) + &dev->rwbuffer[offsetof(struct smart_sect_header_s, status)], 2, crc); #elif defined(CONFIG_SMART_CRC_32) /* Calculate CRC on data region of the sector */ @@ -3028,7 +3081,8 @@ static crc_t smart_calc_sector_crc(FAR struct smart_struct_s *dev) * ****************************************************************************/ -static inline int smart_llformat(FAR struct smart_struct_s *dev, unsigned long arg) +static inline int smart_llformat(FAR struct smart_struct_s *dev, + unsigned long arg) { FAR struct smart_sect_header_s *sectorheader; size_t wrcount; @@ -3061,10 +3115,14 @@ static inline int smart_llformat(FAR struct smart_struct_s *dev, unsigned long a { dev->erasesize = dev->geo.erasesize; - ferr("ERROR: Invalid geometery ... Sectors per erase block must be 1-256\n"); - ferr(" Erase block size = %d\n", dev->erasesize); - ferr(" Sector size = %d\n", dev->sectorsize); - ferr(" Sectors/erase block = %d\n", dev->erasesize / dev->sectorsize); + ferr("ERROR: Invalid geometery ... " + "Sectors per erase block must be 1-256\n"); + ferr(" Erase block size = %d\n", + dev->erasesize); + ferr(" Sector size = %d\n", + dev->sectorsize); + ferr(" Sectors/erase block = %d\n", + dev->erasesize / dev->sectorsize); return -EINVAL; } @@ -3106,17 +3164,20 @@ static inline int smart_llformat(FAR struct smart_struct_s *dev, unsigned long a #if ( CONFIG_SMARTFS_ERASEDSTATE == 0xff ) *((FAR uint16_t *) sectorheader->logicalsector) = 0; - sectorheader->status = (uint8_t) ~(SMART_STATUS_COMMITTED | SMART_STATUS_VERBITS | - SMART_STATUS_SIZEBITS) | SMART_STATUS_VERSION | - sectsize; + sectorheader->status = (uint8_t)~(SMART_STATUS_COMMITTED | + SMART_STATUS_VERBITS | + SMART_STATUS_SIZEBITS) | + SMART_STATUS_VERSION | + sectsize; #ifdef CONFIG_MTD_SMART_ENABLE_CRC sectorheader->status &= ~SMART_STATUS_CRC; #endif /* CONFIG_MTD_SMART_ENABLE_CRC */ #else /* CONFIG_SMARTFS_ERASEDSTATE == 0xff */ *((FAR uint16_t *) sectorheader->logicalsector) = 0xffff; - sectorheader->status = (uint8_t) (SMART_STATUS_COMMITTED | SMART_STATUS_VERSION | - sectsize); + sectorheader->status = (uint8_t)(SMART_STATUS_COMMITTED | + SMART_STATUS_VERSION | + sectsize); #ifdef CONFIG_MTD_SMART_ENABLE_CRC sectorheader->status |= SMART_STATUS_CRC; #endif /* CONFIG_MTD_SMART_ENABLE_CRC */ @@ -3193,7 +3254,8 @@ static inline int smart_llformat(FAR struct smart_struct_s *dev, unsigned long a #ifdef CONFIG_MTD_SMART_PACK_COUNTS smart_set_count(dev, dev->releasecount, x, prerelease); - smart_set_count(dev, dev->freecount, x, dev->availsectperblk - prerelease); + smart_set_count(dev, dev->freecount, x, + dev->availsectperblk - prerelease); #else dev->releasecount[x] = prerelease; dev->freecount[x] = dev->availsectperblk - prerelease; @@ -3352,9 +3414,11 @@ static int smart_relocate_sector(FAR struct smart_struct_s *dev, /* Release the old physical sector */ #if CONFIG_SMARTFS_ERASEDSTATE == 0xff - newstatus = header->status & ~(SMART_STATUS_RELEASED | SMART_STATUS_COMMITTED); + newstatus = header->status & ~(SMART_STATUS_RELEASED | + SMART_STATUS_COMMITTED); #else - newstatus = header->status | SMART_STATUS_RELEASED | SMART_STATUS_COMMITTED; + newstatus = header->status | SMART_STATUS_RELEASED | + SMART_STATUS_COMMITTED; #endif offset = oldsector * dev->mtdblkspersector * dev->geo.blocksize + offsetof(struct smart_sect_header_s, status); @@ -3377,7 +3441,8 @@ static int smart_relocate_sector(FAR struct smart_struct_s *dev, * ****************************************************************************/ -static int smart_relocate_block(FAR struct smart_struct_s *dev, uint16_t block) +static int smart_relocate_block(FAR struct smart_struct_s *dev, + uint16_t block) { uint16_t newsector, oldrelease; int x; @@ -3420,7 +3485,8 @@ static int smart_relocate_block(FAR struct smart_struct_s *dev, uint16_t block) if (freecount >= dev->freesectors) { - ferr("ERROR: Program bug! Relocating the only block (%d) with free sectors!\n", + ferr("ERROR: Program bug! " + "Relocating the only block (%d) with free sectors!\n", block); ret = -EIO; goto errout; @@ -3531,11 +3597,13 @@ static int smart_relocate_block(FAR struct smart_struct_s *dev, uint16_t block) #ifndef CONFIG_MTD_SMART_MINIMIZE_RAM dev->smap[*((FAR uint16_t *) header->logicalsector)] = newsector; #else - smart_update_cache(dev, *((FAR uint16_t *) header->logicalsector), newsector); + smart_update_cache(dev, *((FAR uint16_t *) header->logicalsector), + newsector); #endif #ifdef CONFIG_MTD_SMART_PACK_COUNTS - smart_add_count(dev, dev->freecount, newsector / dev->sectorsperblk, -1); + smart_add_count(dev, dev->freecount, newsector / dev->sectorsperblk, + -1); #else dev->freecount[newsector / dev->sectorsperblk]--; #endif @@ -3582,7 +3650,8 @@ static int smart_relocate_block(FAR struct smart_struct_s *dev, uint16_t block) oldrelease = smart_get_count(dev, dev->releasecount, block); dev->freesectors += oldrelease - prerelease; dev->releasesectors -= oldrelease - prerelease; - smart_set_count(dev, dev->freecount, block, dev->availsectperblk - prerelease); + smart_set_count(dev, dev->freecount, block, + dev->availsectperblk - prerelease); smart_set_count(dev, dev->releasecount, block, prerelease); #else oldrelease = dev->releasecount[block]; @@ -3595,7 +3664,8 @@ static int smart_relocate_block(FAR struct smart_struct_s *dev, uint16_t block) #ifdef CONFIG_SMART_LOCAL_CHECKFREE if (smart_checkfree(dev, __LINE__) != OK) { - fwarn(" ...while relocating block %d, free=%d, release=%d, oldrelease=%d\n", + fwarn(" ...while relocating block %d, " + "free=%d, release=%d, oldrelease=%d\n", block, freecount, releasecount, oldrelease); } #endif @@ -3694,8 +3764,8 @@ static int smart_findfreephyssector(FAR struct smart_struct_s *dev, if (count > wornfreecount || (count > 0 && wearlevel < wornlevel)) { - /* Keep track of this block. If there are only worn blocks with - * free sectors left, then we will use it. + /* Keep track of this block. If there are only worn blocks + * with free sectors left, then we will use it. */ if (i < dev->neraseblocks - 1 || !wornfreecount) @@ -3744,12 +3814,13 @@ static int smart_findfreephyssector(FAR struct smart_struct_s *dev, block = 0; for (i = 0; i < 8; ) { - if (smart_get_wear_level(dev, block) < SMART_WEAR_FORCE_REORG_THRESHOLD) + if (smart_get_wear_level(dev, block) < + SMART_WEAR_FORCE_REORG_THRESHOLD) { if (smart_relocate_block(dev, block) < 0) { - ferr("ERROR: Error relocating block while finding free " - "phys sector\n"); + ferr("ERROR: Error relocating block while finding " + "free phys sector\n"); return -1; } @@ -3872,7 +3943,8 @@ static int smart_findfreephyssector(FAR struct smart_struct_s *dev, { /* The FLASH may be not erased in the initial delivery state. * Just in case for the recovery of this fatal situation, - * after once erasing the sector, return the sector as a free sector. + * after once erasing the sector, return the sector as a free + * sector. */ if (1 == dev->availsectperblk) @@ -4098,7 +4170,8 @@ static int smart_write_wearstatus(struct smart_struct_s *dev) sizeof(struct smart_sect_header_s))) { towrite = dev->sectorsize - - (SMARTFS_FMT_WEAR_POS + sizeof(struct smart_sect_header_s)); + (SMARTFS_FMT_WEAR_POS + + sizeof(struct smart_sect_header_s)); } /* Setup the sector write request (we are our own client) */ @@ -4130,7 +4203,8 @@ static int smart_write_wearstatus(struct smart_struct_s *dev) { /* Error, wear status bit too large! */ - ferr("ERROR: Invalid geometry - wear level status too large\n"); + ferr("ERROR: Invalid geometry " + "- wear level status too large\n"); ret = -EINVAL; goto errout; } @@ -4216,16 +4290,18 @@ static inline int smart_read_wearstatus(FAR struct smart_struct_s *dev) (SMARTFS_FMT_WEAR_POS + sizeof(struct smart_sect_header_s))) { toread = dev->sectorsize - - (SMARTFS_FMT_WEAR_POS + sizeof(struct smart_sect_header_s)); + (SMARTFS_FMT_WEAR_POS + + sizeof(struct smart_sect_header_s)); } /* Setup the sector read request (we are our own client) */ req.logsector = sector; - req.offset = SMARTFS_FMT_WEAR_POS; - req.count = toread; - req.buffer = &dev->wearstatus[(dev->geo.neraseblocks >> SMART_WEAR_BIT_DIVIDE) - - remaining]; + req.offset = SMARTFS_FMT_WEAR_POS; + req.count = toread; + req.buffer = + &dev->wearstatus[(dev->geo.neraseblocks >> SMART_WEAR_BIT_DIVIDE) - + remaining]; /* Validate wear status sector has been allocated */ @@ -4241,7 +4317,8 @@ static inline int smart_read_wearstatus(FAR struct smart_struct_s *dev) ret = smart_allocsector(dev, sector); if (ret != sector) { - ferr("ERROR: Unable to allocate wear level status sector %d\n", sector); + ferr("ERROR: Unable to allocate wear level status sector %d\n", + sector); ret = -EINVAL; goto errout; } @@ -4267,7 +4344,8 @@ static inline int smart_read_wearstatus(FAR struct smart_struct_s *dev) { /* Error, wear status bit too large! */ - ferr("ERROR: Invalid geometry - wear level status too large\n"); + ferr("ERROR: Invalid geometry " + "- wear level status too large\n"); ret = -EINVAL; goto errout; } @@ -4476,15 +4554,18 @@ static int smart_writesector(FAR struct smart_struct_s *dev, /* Test if an adjustment to the wear levels is needed */ if (dev->minwearlevel >= SMART_WEAR_MIN_LEVEL || - (dev->minwearlevel > 0 && dev->maxwearlevel >= SMART_WEAR_REORG_THRESHOLD)) + (dev->minwearlevel > 0 && + dev->maxwearlevel >= SMART_WEAR_REORG_THRESHOLD)) { /* Subtract dev->minwearlevel from all wear levels */ offset = dev->minwearlevel; finfo("Reducing wear level bits by %d\n", offset); + for (x = 0; x < dev->geo.neraseblocks; x++) { - smart_set_wear_level(dev, x, smart_get_wear_level(dev, x) - offset); + smart_set_wear_level(dev, x, + smart_get_wear_level(dev, x) - offset); } dev->minwearlevel -= offset; @@ -4557,7 +4638,8 @@ static int smart_writesector(FAR struct smart_struct_s *dev, { /* Test if the next byte can be written to the flash */ - byte = dev->rwbuffer[sizeof(struct smart_sect_header_s) + req->offset + x]; + byte = dev->rwbuffer[sizeof(struct smart_sect_header_s) + + req->offset + x]; #if CONFIG_SMARTFS_ERASEDSTATE == 0xff if (((byte ^ req->buffer[x]) | byte) != byte) { @@ -4630,7 +4712,8 @@ static int smart_writesector(FAR struct smart_struct_s *dev, if (allocsector) { - smart_write_alloc_sector(dev, allocsector->logical, allocsector->physical); + smart_write_alloc_sector(dev, allocsector->logical, + allocsector->physical); /* Remove allocsector from the list and free the memory */ @@ -4737,9 +4820,11 @@ static int smart_writesector(FAR struct smart_struct_s *dev, /* Release the old physical sector */ #if CONFIG_SMARTFS_ERASEDSTATE == 0xff - byte = header->status & ~(SMART_STATUS_RELEASED | SMART_STATUS_COMMITTED); + byte = header->status & ~(SMART_STATUS_RELEASED | + SMART_STATUS_COMMITTED); #else - byte = header->status | SMART_STATUS_RELEASED | SMART_STATUS_COMMITTED; + byte = header->status | SMART_STATUS_RELEASED | + SMART_STATUS_COMMITTED; #endif offset = mtdblock * dev->geo.blocksize + offsetof(struct smart_sect_header_s, status); @@ -4752,7 +4837,8 @@ static int smart_writesector(FAR struct smart_struct_s *dev, block = oldphyssector / dev->sectorsperblk; #ifdef CONFIG_MTD_SMART_PACK_COUNTS smart_add_count(dev, dev->releasecount, block, 1); - smart_add_count(dev, dev->freecount, physsector / dev->sectorsperblk, -1); + smart_add_count(dev, dev->freecount, physsector / dev->sectorsperblk, + -1); #else dev->releasecount[block]++; dev->freecount[physsector / dev->sectorsperblk]--; @@ -4858,10 +4944,11 @@ static int smart_readsector(FAR struct smart_struct_s *dev, #endif finfo("Entry\n"); + req = (FAR struct smart_read_write_s *) arg; DEBUGASSERT(req->offset < dev->sectorsize); - DEBUGASSERT(req->offset + req->count + sizeof(struct smart_sect_header_s) <= - dev->sectorsize); + DEBUGASSERT(req->offset + req->count + sizeof(struct smart_sect_header_s) + <= dev->sectorsize); /* Ensure the logical sector has been allocated */ @@ -4923,7 +5010,8 @@ static int smart_readsector(FAR struct smart_struct_s *dev, { /* TODO: Mark the block bad */ - ferr("ERROR: Error validating sector %d CRC during read\n", physsector); + ferr("ERROR: Error validating sector %d CRC during read\n", + physsector); ret = -EIO; goto errout; } @@ -4939,8 +5027,9 @@ static int smart_readsector(FAR struct smart_struct_s *dev, /* Read the sector header data to validate as a sanity check */ - ret = MTD_READ(dev->mtd, physsector * dev->mtdblkspersector * dev->geo.blocksize, - sizeof(struct smart_sect_header_s), (FAR uint8_t *) &header); + ret = MTD_READ(dev->mtd, physsector * dev->mtdblkspersector * + dev->geo.blocksize, sizeof(struct smart_sect_header_s), + (FAR uint8_t *)&header); if (ret != sizeof(struct smart_sect_header_s)) { ferr("ERROR: Error reading sector %d header\n", physsector); @@ -4964,8 +5053,9 @@ static int smart_readsector(FAR struct smart_struct_s *dev, /* Read the sector data into the buffer */ - readaddr = (uint32_t) physsector * dev->mtdblkspersector * dev->geo.blocksize + - req->offset + sizeof(struct smart_sect_header_s); + readaddr = (uint32_t)physsector * dev->mtdblkspersector * + dev->geo.blocksize + req->offset + + sizeof(struct smart_sect_header_s); ret = MTD_READ(dev->mtd, readaddr, req->count, (FAR uint8_t *) req->buffer); @@ -5173,24 +5263,26 @@ static inline int smart_allocsector(FAR struct smart_struct_s *dev, * our temporary allocsector list and we'll pick it up later. */ - { - FAR struct smart_allocsector_s *allocsect = (FAR struct smart_allocsector_s *) - kmm_malloc(sizeof(struct smart_allocsector_s)); - if (allocsect == NULL) - { - ferr("ERROR: Out of memory allocting sector\n"); - return -ENOMEM; - } + { + FAR struct smart_allocsector_s *allocsect = + (FAR struct smart_allocsector_s *) + kmm_malloc(sizeof(struct smart_allocsector_s)); - /* Fill in the struct and add to the list. We are protected by the - * smartfs layer's mutex, so no locking is required. - */ + if (allocsect == NULL) + { + ferr("ERROR: Out of memory allocting sector\n"); + return -ENOMEM; + } + + /* Fill in the struct and add to the list. We are protected by the + * smartfs layer's mutex, so no locking is required. + */ - allocsect->logical = logsector; - allocsect->physical = physicalsector; - allocsect->next = dev->allocsector; - dev->allocsector = allocsect; - } + allocsect->logical = logsector; + allocsect->physical = physicalsector; + allocsect->next = dev->allocsector; + dev->allocsector = allocsect; + } #else /* CONFIG_MTD_SMART_ENABLE_CRC */ @@ -5215,7 +5307,8 @@ static inline int smart_allocsector(FAR struct smart_struct_s *dev, #endif #ifdef CONFIG_MTD_SMART_PACK_COUNTS - smart_add_count(dev, dev->freecount, physicalsector / dev->sectorsperblk, -1); + smart_add_count(dev, dev->freecount, + physicalsector / dev->sectorsperblk, -1); #else dev->freecount[physicalsector / dev->sectorsperblk]--; #endif @@ -5254,10 +5347,12 @@ static inline int smart_freesector(FAR struct smart_struct_s *dev, #ifndef CONFIG_MTD_SMART_MINIMIZE_RAM if (dev->smap[logicalsector] == (uint16_t) -1) #else - if (!(dev->sbitmap[logicalsector >> 3] & (1 << (logicalsector & 0x07)))) + if (!(dev->sbitmap[logicalsector >> 3] & + (1 << (logicalsector & 0x07)))) #endif { - ferr("ERROR: Invalid release - sector %d not allocated\n", logicalsector); + ferr("ERROR: Invalid release - sector %d not allocated\n", + logicalsector); ret = -EINVAL; goto errout; } @@ -5394,7 +5489,8 @@ static int smart_ioctl(FAR struct inode *inode, int cmd, unsigned long arg) #ifdef CONFIG_SMARTFS_MULTI_ROOT_DIRS ret = smart_getformat(dev, (FAR struct smart_format_s *) arg, - ((FAR struct smart_multiroot_device_s *)inode->i_private)->rootdirnum); + ((FAR struct smart_multiroot_device_s *) + inode->i_private)->rootdirnum); #else ret = smart_getformat(dev, (FAR struct smart_format_s *) arg); #endif @@ -5533,7 +5629,8 @@ static int smart_ioctl(FAR struct inode *inode, int cmd, unsigned long arg) ****************************************************************************/ #ifdef CONFIG_MTD_SMART_FSCK_ENABLE_CRC -static int smart_fsck_crc(FAR struct smart_struct_s *dev, uint16_t physsector) +static int smart_fsck_crc(FAR struct smart_struct_s *dev, + uint16_t physsector) { int ret; @@ -5643,7 +5740,8 @@ static int smart_fsck_file(FAR struct smart_struct_s *dev, (CONFIG_SMARTFS_ERASEDSTATE & SMART_STATUS_RELEASED))) { ret = -ENOENT; - ferr("ERROR: status(%02x) phys sector %d\n", header->status, physsector); + ferr("ERROR: status(%02x) phys sector %d\n", + header->status, physsector); break; } @@ -5706,7 +5804,8 @@ static int smart_fsck_directory(FAR struct smart_struct_s *dev, char entryname[dev->namesize + 1]; #endif - if ((logsector < SMART_FIRST_DIR_SECTOR) || (logsector >= dev->totalsectors)) + if ((logsector < SMART_FIRST_DIR_SECTOR) || + (logsector >= dev->totalsectors)) { ret = -EINVAL; ferr("ERROR: Invalid log sector %d\n", logsector); @@ -5771,7 +5870,8 @@ static int smart_fsck_directory(FAR struct smart_struct_s *dev, (CONFIG_SMARTFS_ERASEDSTATE & SMART_STATUS_RELEASED))) { ret = -ENOENT; - ferr("ERROR: status(%02x) phys sector %d\n", header->status, physsector); + ferr("ERROR: status(%02x) phys sector %d\n", + header->status, physsector); goto errout; } @@ -5850,13 +5950,16 @@ static int smart_fsck_directory(FAR struct smart_struct_s *dev, if (ret != OK) { - finfo("Remove entry (name=%s flags=%02x)\n", entryname, entry->flags); + finfo("Remove entry (name=%s flags=%02x)\n", + entryname, entry->flags); + if ((cur + (2 * entrysize)) <= bottom) { /* Truncate the current entry and overwrite with next entries */ memmove(cur, cur + entrysize, bottom - (cur + entrysize)); - memset(bottom - entrysize, CONFIG_SMARTFS_ERASEDSTATE, entrysize); + memset(bottom - entrysize, CONFIG_SMARTFS_ERASEDSTATE, + entrysize); } else { @@ -5903,11 +6006,13 @@ static int smart_fsck_directory(FAR struct smart_struct_s *dev, #ifndef CONFIG_MTD_SMART_MINIMIZE_RAM dev->smap[*((FAR uint16_t *)header->logicalsector)] = newsector; #else - smart_update_cache(dev, *((FAR uint16_t *)header->logicalsector), newsector); + smart_update_cache(dev, *((FAR uint16_t *)header->logicalsector), + newsector); #endif #ifdef CONFIG_MTD_SMART_PACK_COUNTS - smart_add_count(dev, dev->freecount, newsector / dev->sectorsperblk, -1); + smart_add_count(dev, dev->freecount, + newsector / dev->sectorsperblk, -1); #else dev->freecount[newsector / dev->sectorsperblk]--; #endif @@ -6018,7 +6123,8 @@ static int smart_fsck(FAR struct smart_struct_s *dev) * ****************************************************************************/ -int smart_initialize(int minor, FAR struct mtd_dev_s *mtd, FAR const char *partname) +int smart_initialize(int minor, FAR struct mtd_dev_s *mtd, + FAR const char *partname) { FAR struct smart_struct_s *dev; int ret = -ENOMEM; @@ -6038,8 +6144,8 @@ int smart_initialize(int minor, FAR struct mtd_dev_s *mtd, FAR const char *partn /* Allocate a SMART device structure */ - dev = (FAR struct smart_struct_s *)smart_zalloc(NULL, sizeof(struct smart_struct_s), - "Dev struct"); + dev = (FAR struct smart_struct_s *) + smart_zalloc(NULL, sizeof(struct smart_struct_s), "Dev struct"); if (dev) { /* Initialize the SMART device structure */ @@ -6053,7 +6159,8 @@ int smart_initialize(int minor, FAR struct mtd_dev_s *mtd, FAR const char *partn /* Set these to zero in case the device doesn't support them */ - ret = MTD_IOCTL(mtd, MTDIOC_GEOMETRY, (unsigned long)((uintptr_t)&dev->geo)); + ret = MTD_IOCTL(mtd, MTDIOC_GEOMETRY, + (unsigned long)((uintptr_t)&dev->geo)); if (ret < 0) { ferr("ERROR: MTD ioctl(MTDIOC_GEOMETRY) failed: %d\n", ret); @@ -6080,13 +6187,14 @@ int smart_initialize(int minor, FAR struct mtd_dev_s *mtd, FAR const char *partn } else if (totalsectors == 65536) { - totalsectors -= 2; + totalsectors -= 2; } - dev->totalsectors = (uint16_t)totalsectors; - dev->freesectors = (uint16_t)dev->availsectperblk * dev->geo.neraseblocks; + dev->totalsectors = (uint16_t)totalsectors; + dev->freesectors = (uint16_t)dev->availsectperblk * + dev->geo.neraseblocks; dev->lastallocblock = 0; - dev->debuglevel = 0; + dev->debuglevel = 0; /* Mark the device format status an unknown */ @@ -6283,8 +6391,8 @@ static int smart_loteardown(FAR const char *devname) } #endif - /* Open the block driver associated with devname so that we can get the inode - * reference. + /* Open the block driver associated with devname so that we can get the + * inode reference. */ ret = open_blockdriver(devname, MS_RDONLY, &inode); @@ -6324,7 +6432,8 @@ static int smart_loteardown(FAR const char *devname) ****************************************************************************/ #ifdef CONFIG_SMART_DEV_LOOP -static ssize_t smart_loop_read(FAR struct file *filep, FAR char *buffer, size_t len) +static ssize_t smart_loop_read(FAR struct file *filep, FAR char *buffer, + size_t len) { return 0; /* Return EOF */ } @@ -6347,7 +6456,8 @@ static ssize_t smart_loop_write(FAR struct file *filep, ****************************************************************************/ #ifdef CONFIG_SMART_DEV_LOOP -static int smart_loop_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +static int smart_loop_ioctl(FAR struct file *filep, int cmd, + unsigned long arg) { int ret; @@ -6370,14 +6480,16 @@ static int smart_loop_ioctl(FAR struct file *filep, int cmd, unsigned long arg) } else { - ret = smart_losetup(setup->minor, setup->filename, setup->sectsize, - setup->erasesize, setup->offset, setup->readonly); + ret = smart_losetup(setup->minor, setup->filename, + setup->sectsize, setup->erasesize, + setup->offset, setup->readonly); } } break; /* Command: LOOPIOC_TEARDOWN - * Description: Teardown a loop device previously setup vis LOOPIOC_SETUP + * Description: Teardown a loop device previously setup via + * LOOPIOC_SETUP * Argument: A read-able pointer to the path of the device to be * torn down * Dependencies: The loop device must be enabled (CONFIG_DEV_LOOP=y) diff --git a/drivers/ramdisk.c b/drivers/ramdisk.c index 21d2f41bdc0e..4ca5ad620ea9 100644 --- a/drivers/ramdisk.c +++ b/drivers/ramdisk.c @@ -414,7 +414,8 @@ int ramdisk_register(int minor, FAR uint8_t *buffer, uint32_t nsectors, char devname[16]; int ret = -ENOMEM; - finfo("buffer: %p nsectors: %d sectsize: %d\n", buffer, nsectors, sectsize); + finfo("buffer: %p nsectors: %d sectsize: %d\n", + buffer, nsectors, sectsize); /* Sanity check */ diff --git a/drivers/usbhost/usbhost_storage.c b/drivers/usbhost/usbhost_storage.c index 0d41ad7b2f41..db78ddc5d266 100644 --- a/drivers/usbhost/usbhost_storage.c +++ b/drivers/usbhost/usbhost_storage.c @@ -76,6 +76,7 @@ #endif /* Driver support ***********************************************************/ + /* This format is used to construct the /dev/sd[n] device driver path. It * defined here so that it will be used consistently in all places. */ @@ -174,6 +175,7 @@ static inline void usbhost_readcbw (size_t startsector, uint16_t blocksize, static inline void usbhost_writecbw(size_t startsector, uint16_t blocksize, unsigned int nsectors, FAR struct usbmsc_cbw_s *cbw); + /* Command helpers */ static inline int usbhost_maxlunreq(FAR struct usbhost_state_s *priv); @@ -189,7 +191,8 @@ static void usbhost_destroy(FAR void *arg); /* Helpers for usbhost_connect() */ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv, - FAR const uint8_t *configdesc, int desclen); + FAR const uint8_t *configdesc, + int desclen); static inline int usbhost_initvolume(FAR struct usbhost_state_s *priv); /* (Little Endian) Data helpers */ @@ -207,7 +210,8 @@ static void usbhost_putbe32(uint8_t *dest, uint32_t val); static inline int usbhost_talloc(FAR struct usbhost_state_s *priv); static inline int usbhost_tfree(FAR struct usbhost_state_s *priv); -static FAR struct usbmsc_cbw_s *usbhost_cbwalloc(FAR struct usbhost_state_s *priv); +static FAR struct usbmsc_cbw_s * + usbhost_cbwalloc(FAR struct usbhost_state_s *priv); /* struct usbhost_registry_s methods */ @@ -225,11 +229,12 @@ static int usbhost_disconnected(FAR struct usbhost_class_s *usbclass); static int usbhost_open(FAR struct inode *inode); static int usbhost_close(FAR struct inode *inode); -static ssize_t usbhost_read(FAR struct inode *inode, FAR unsigned char *buffer, - size_t startsector, unsigned int nsectors); +static ssize_t usbhost_read(FAR struct inode *inode, + FAR unsigned char *buffer, size_t startsector, + unsigned int nsectors); static ssize_t usbhost_write(FAR struct inode *inode, - FAR const unsigned char *buffer, size_t startsector, - unsigned int nsectors); + FAR const unsigned char *buffer, + size_t startsector, unsigned int nsectors); static int usbhost_geometry(FAR struct inode *inode, FAR struct geometry *geometry); static int usbhost_ioctl(FAR struct inode *inode, int cmd, @@ -247,8 +252,8 @@ static int usbhost_ioctl(FAR struct inode *inode, int cmd, static const struct usbhost_id_s g_id = { USB_CLASS_MASS_STORAGE, /* base */ - USBMSC_SUBCLASS_SCSI, /* subclass */ - USBMSC_PROTO_BULKONLY, /* proto */ + USBMSC_SUBCLASS_SCSI, /* subclass */ + USBMSC_PROTO_BULKONLY, /* proto */ 0, /* vid */ 0 /* pid */ }; @@ -361,7 +366,10 @@ static inline FAR struct usbhost_state_s *usbhost_allocclass(void) */ DEBUGASSERT(!up_interrupt_context()); - priv = (FAR struct usbhost_state_s *)kmm_malloc(sizeof(struct usbhost_state_s)); + + priv = (FAR struct usbhost_state_s *) + kmm_malloc(sizeof(struct usbhost_state_s)); + uinfo("Allocated: %p\n", priv); return priv; } @@ -384,7 +392,8 @@ static inline FAR struct usbhost_state_s *usbhost_allocclass(void) #if CONFIG_USBHOST_NPREALLOC > 0 static inline void usbhost_freeclass(FAR struct usbhost_state_s *usbclass) { - FAR struct usbhost_freestate_s *entry = (FAR struct usbhost_freestate_s *)usbclass; + FAR struct usbhost_freestate_s *entry = + (FAR struct usbhost_freestate_s *)usbclass; irqstate_t flags; DEBUGASSERT(entry != NULL); @@ -415,7 +424,8 @@ static inline void usbhost_freeclass(FAR struct usbhost_state_s *usbclass) * Name: Device name management * * Description: - * Some tiny functions to coordinate management of mass storage device names. + * Some tiny functions to coordinate management of mass storage device + * names. * ****************************************************************************/ @@ -453,7 +463,8 @@ static void usbhost_freedevno(FAR struct usbhost_state_s *priv) } } -static inline void usbhost_mkdevname(FAR struct usbhost_state_s *priv, char *devname) +static inline void usbhost_mkdevname(FAR struct usbhost_state_s *priv, + FAR char *devname) { snprintf(devname, DEV_NAMELEN, DEV_FORMAT, priv->sdchar); } @@ -489,8 +500,9 @@ static void usbhost_dumpcbw(FAR struct usbmsc_cbw_s *cbw) for (i = 0; i < cbw->cdblen; i += 8) { uinfo(" %02x %02x %02x %02x %02x %02x %02x %02x\n", - cbw->cdb[i], cbw->cdb[i+1], cbw->cdb[i+2], cbw->cdb[i+3], - cbw->cdb[i+4], cbw->cdb[i+5], cbw->cdb[i+6], cbw->cdb[i+7]); + cbw->cdb[i], cbw->cdb[i + 1], cbw->cdb[i + 2], + cbw->cdb[i + 3], cbw->cdb[i + 4], cbw->cdb[i + 5], + cbw->cdb[i + 6], cbw->cdb[i + 7]); } } @@ -659,7 +671,8 @@ static inline int usbhost_maxlunreq(FAR struct usbhost_state_s *priv) uinfo("Request maximum logical unit number\n"); memset(req, 0, sizeof(struct usb_ctrlreq_s)); - req->type = USB_DIR_IN | USB_REQ_TYPE_CLASS | USB_REQ_RECIPIENT_INTERFACE; + req->type = USB_DIR_IN | USB_REQ_TYPE_CLASS | + USB_REQ_RECIPIENT_INTERFACE; req->req = USBMSC_REQ_GETMAXLUN; usbhost_putle16(req->len, 1); @@ -796,7 +809,8 @@ static inline int usbhost_readcapacity(FAR struct usbhost_state_s *priv) { /* Save the capacity information */ - resp = (FAR struct scsiresp_readcapacity10_s *)priv->tbuffer; + resp = (FAR struct scsiresp_readcapacity10_s *) + priv->tbuffer; priv->nblocks = usbhost_getbe32(resp->lba) + 1; priv->blocksize = usbhost_getbe32(resp->blklen); @@ -870,9 +884,9 @@ static inline int usbhost_inquiry(FAR struct usbhost_state_s *priv) * Name: usbhost_destroy * * Description: - * The USB mass storage device has been disconnected and the reference count - * on the USB host class instance has gone to 1.. Time to destroy the USB - * host class instance. + * The USB mass storage device has been disconnected and the reference + * count on the USB host class instance has gone to 1.. Time to destroy + * the USB host class instance. * * Input Parameters: * arg - A reference to the class instance to be destroyed. @@ -952,8 +966,8 @@ static void usbhost_destroy(FAR void *arg) * desclen - The length in bytes of the configuration descriptor. * * Returned Value: - * On success, zero (OK) is returned. On a failure, a negated errno value is - * returned indicating the nature of the failure + * On success, zero (OK) is returned. On a failure, a negated errno value + * is returned indicating the nature of the failure * * Assumptions: * This function will *not* be called from an interrupt handler. @@ -1015,7 +1029,8 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv, case USB_DESC_TYPE_INTERFACE: { - FAR struct usb_ifdesc_s *ifdesc = (FAR struct usb_ifdesc_s *)configdesc; + FAR struct usb_ifdesc_s *ifdesc = + (FAR struct usb_ifdesc_s *)configdesc; uinfo("Interface descriptor\n"); DEBUGASSERT(remaining >= USB_SIZEOF_IFDESC); @@ -1033,7 +1048,8 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv, case USB_DESC_TYPE_ENDPOINT: { - FAR struct usb_epdesc_s *epdesc = (FAR struct usb_epdesc_s *)configdesc; + FAR struct usb_epdesc_s *epdesc = + (FAR struct usb_epdesc_s *)configdesc; uinfo("Endpoint descriptor\n"); DEBUGASSERT(remaining >= USB_SIZEOF_EPDESC); @@ -1042,7 +1058,8 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv, * protocol so I suppose anything else should really be an error. */ - if ((epdesc->attr & USB_EP_ATTR_XFERTYPE_MASK) == USB_EP_ATTR_XFER_BULK) + if ((epdesc->attr & USB_EP_ATTR_XFERTYPE_MASK) == + USB_EP_ATTR_XFER_BULK) { /* Yes.. it is a bulk endpoint. IN or OUT? */ @@ -1060,16 +1077,19 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv, return -EINVAL; } + found |= USBHOST_BOUTFOUND; /* Save the bulk OUT endpoint information */ boutdesc.hport = hport; - boutdesc.addr = epdesc->addr & USB_EP_ADDR_NUMBER_MASK; + boutdesc.addr = epdesc->addr & + USB_EP_ADDR_NUMBER_MASK; boutdesc.in = false; boutdesc.xfrtype = USB_EP_ATTR_XFER_BULK; boutdesc.interval = epdesc->interval; - boutdesc.mxpacketsize = usbhost_getle16(epdesc->mxpacketsize); + boutdesc.mxpacketsize = + usbhost_getle16(epdesc->mxpacketsize); uinfo("Bulk OUT EP addr:%d mxpacketsize:%d\n", boutdesc.addr, boutdesc.mxpacketsize); @@ -1088,16 +1108,20 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv, return -EINVAL; } + found |= USBHOST_BINFOUND; /* Save the bulk IN endpoint information */ bindesc.hport = hport; - bindesc.addr = epdesc->addr & USB_EP_ADDR_NUMBER_MASK; + bindesc.addr = epdesc->addr & + USB_EP_ADDR_NUMBER_MASK; bindesc.in = 1; bindesc.xfrtype = USB_EP_ATTR_XFER_BULK; bindesc.interval = epdesc->interval; - bindesc.mxpacketsize = usbhost_getle16(epdesc->mxpacketsize); + bindesc.mxpacketsize = + usbhost_getle16(epdesc->mxpacketsize); + uinfo("Bulk IN EP addr:%d mxpacketsize:%d\n", bindesc.addr, bindesc.mxpacketsize); } @@ -1126,8 +1150,9 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv, remaining -= desc->len; } - /* Sanity checking... did we find all of things that we need? Hmmm.. I wonder.. - * can we work read-only or write-only if only one bulk endpoint found? + /* Sanity checking... did we find all of things that we need? Hmmm.. + * I wonder.. can we work read-only or write-only if only one bulk + * endpoint found? */ if (found != USBHOST_ALLFOUND) @@ -1208,7 +1233,7 @@ static inline int usbhost_initvolume(FAR struct usbhost_state_s *priv) uinfo("Get max LUN\n"); ret = usbhost_maxlunreq(priv); - for (retries = 0; retries < USBHOST_MAX_RETRIES /* && ret >= 0 */; retries++) + for (retries = 0; retries < USBHOST_MAX_RETRIES; retries++) { uinfo("Test unit ready, retries=%d\n", retries); @@ -1216,9 +1241,9 @@ static inline int usbhost_initvolume(FAR struct usbhost_state_s *priv) nxsig_usleep(USBHOST_RETRY_USEC); - /* Send TESTUNITREADY to see if the unit is ready. The most likely error - * error that can occur here is a a stall which simply means that the - * the device is not yet able to respond. + /* Send TESTUNITREADY to see if the unit is ready. The most likely + * error error that can occur here is a a stall which simply means + * that the the device is not yet able to respond. */ ret = usbhost_testunitready(priv); @@ -1455,7 +1480,8 @@ static inline uint32_t usbhost_getle32(const uint8_t *val) { /* Little endian means LS halfword first in byte stream */ - return (uint32_t)usbhost_getle16(&val[2]) << 16 | (uint32_t)usbhost_getle16(val); + return (uint32_t)usbhost_getle16(&val[2]) << 16 | + (uint32_t)usbhost_getle16(val); } /**************************************************************************** @@ -1477,7 +1503,8 @@ static inline uint32_t usbhost_getbe32(const uint8_t *val) { /* Big endian means MS halfword first in byte stream */ - return (uint32_t)usbhost_getbe16(val) << 16 | (uint32_t)usbhost_getbe16(&val[2]); + return (uint32_t)usbhost_getbe16(val) << 16 | + (uint32_t)usbhost_getbe16(&val[2]); } /**************************************************************************** @@ -1500,7 +1527,7 @@ static void usbhost_putle32(uint8_t *dest, uint32_t val) /* Little endian means LS halfword first in byte stream */ usbhost_putle16(dest, (uint16_t)(val & 0xffff)); - usbhost_putle16(dest+2, (uint16_t)(val >> 16)); + usbhost_putle16(dest + 2, (uint16_t)(val >> 16)); } /**************************************************************************** @@ -1523,7 +1550,7 @@ static void usbhost_putbe32(uint8_t *dest, uint32_t val) /* Big endian means MS halfword first in byte stream */ usbhost_putbe16(dest, (uint16_t)(val >> 16)); - usbhost_putbe16(dest+2, (uint16_t)(val & 0xffff)); + usbhost_putbe16(dest + 2, (uint16_t)(val & 0xffff)); } /**************************************************************************** @@ -1590,7 +1617,8 @@ static inline int usbhost_tfree(FAR struct usbhost_state_s *priv) * * Description: * Initialize a CBW (re-using the allocated transfer buffer). Upon - * successful return, the CBW is cleared and has the CBW signature in place. + * successful return, the CBW is cleared and has the CBW signature in + * place. * * Input Parameters: * priv - A reference to the class instance. @@ -1600,7 +1628,8 @@ static inline int usbhost_tfree(FAR struct usbhost_state_s *priv) * ****************************************************************************/ -static FAR struct usbmsc_cbw_s *usbhost_cbwalloc(FAR struct usbhost_state_s *priv) +static FAR struct usbmsc_cbw_s * + usbhost_cbwalloc(FAR struct usbhost_state_s *priv) { FAR struct usbmsc_cbw_s *cbw = NULL; @@ -1614,20 +1643,17 @@ static FAR struct usbmsc_cbw_s *usbhost_cbwalloc(FAR struct usbhost_state_s *pri return cbw; } -/**************************************************************************** - * struct usbhost_registry_s methods - ****************************************************************************/ - /**************************************************************************** * Name: usbhost_create * * Description: - * This function implements the create() method of struct usbhost_registry_s. - * The create() method is a callback into the class implementation. It is - * used to (1) create a new instance of the USB host class state and to (2) - * bind a USB host driver "session" to the class instance. Use of this - * create() method will support environments where there may be multiple - * USB ports and multiple USB devices simultaneously connected. + * This function implements the create() method of struct + * usbhost_registry_s. The create() method is a callback into the class + * implementation. It is used to (1) create a new instance of the USB host + * class state and to (2) bind a USB host driver "session" to the class + * instance. Use of this create() method will support environments where + * there may be multiple USB ports and multiple USB devices simultaneously + * connected. * * Input Parameters: * hport - The hub port that manages the new class instance. @@ -1644,8 +1670,8 @@ static FAR struct usbmsc_cbw_s *usbhost_cbwalloc(FAR struct usbhost_state_s *pri ****************************************************************************/ static FAR struct usbhost_class_s * -usbhost_create(FAR struct usbhost_hubport_s *hport, - FAR const struct usbhost_id_s *id) + usbhost_create(FAR struct usbhost_hubport_s *hport, + FAR const struct usbhost_id_s *id) { FAR struct usbhost_state_s *priv; @@ -1662,13 +1688,15 @@ usbhost_create(FAR struct usbhost_hubport_s *hport, if (usbhost_allocdevno(priv) == OK) { - /* Initialize class method function pointers */ + /* Initialize class method function pointers */ priv->usbclass.hport = hport; priv->usbclass.connect = usbhost_connect; priv->usbclass.disconnected = usbhost_disconnected; - /* The initial reference count is 1... One reference is held by the driver */ + /* The initial reference count is 1... One reference is held by + * the driver. + */ priv->crefs = 1; @@ -1676,7 +1704,9 @@ usbhost_create(FAR struct usbhost_hubport_s *hport, nxsem_init(&priv->exclsem, 0, 1); - /* NOTE: We do not yet know the geometry of the USB mass storage device */ + /* NOTE: We do not yet know the geometry of the USB mass storage + * device. + */ /* Return the instance of the USB mass storage class */ @@ -1694,9 +1724,6 @@ usbhost_create(FAR struct usbhost_hubport_s *hport, return NULL; } -/**************************************************************************** - * struct usbhost_class_s methods - ****************************************************************************/ /**************************************************************************** * Name: usbhost_connect * @@ -1714,11 +1741,11 @@ usbhost_create(FAR struct usbhost_hubport_s *hport, * desclen - The length in bytes of the configuration descriptor. * * Returned Value: - * On success, zero (OK) is returned. On a failure, a negated errno value is - * returned indicating the nature of the failure + * On success, zero (OK) is returned. On a failure, a negated errno value + * is returned indicating the nature of the failure * - * NOTE that the class instance remains valid upon return with a failure. It is - * the responsibility of the higher level enumeration logic to call + * NOTE that the class instance remains valid upon return with a failure. + * It is the responsibility of the higher level enumeration logic to call * CLASS_DISCONNECTED to free up the class driver resources. * * Assumptions: @@ -1788,8 +1815,8 @@ static int usbhost_disconnected(struct usbhost_class_s *usbclass) DEBUGASSERT(priv != NULL); - /* Set an indication to any users of the mass storage device that the device - * is no longer available. + /* Set an indication to any users of the mass storage device that the + * device is no longer available. */ flags = enter_critical_section(); @@ -1813,10 +1840,11 @@ static int usbhost_disconnected(struct usbhost_class_s *usbclass) { /* Destroy the instance on the worker thread. */ - uinfo("Queuing destruction: worker %p->%p\n", priv->work.worker, usbhost_destroy); + uinfo("Queuing destruction: worker %p->%p\n", + priv->work.worker, usbhost_destroy); DEBUGASSERT(priv->work.worker == NULL); work_queue(HPWORK, &priv->work, usbhost_destroy, priv, 0); - } + } else { /* Do the work now */ @@ -1829,9 +1857,6 @@ static int usbhost_disconnected(struct usbhost_class_s *usbclass) return OK; } -/**************************************************************************** - * struct block_operations methods - ****************************************************************************/ /**************************************************************************** * Name: usbhost_open * @@ -1854,17 +1879,17 @@ static int usbhost_open(FAR struct inode *inode) DEBUGASSERT(priv->crefs > 0 && priv->crefs < USBHOST_MAX_CREFS); usbhost_takesem(&priv->exclsem); - /* Check if the mass storage device is still connected. We need to disable - * interrupts momentarily to assure that there are no asynchronous disconnect - * events. + /* Check if the mass storage device is still connected. We need to + * disable interrupts momentarily to assure that there are no asynchronous + * disconnect events. */ flags = enter_critical_section(); if (priv->disconnected) { - /* No... the block driver is no longer bound to the class. That means that - * the USB storage device is no longer connected. Refuse any further - * attempts to open the driver. + /* No... the block driver is no longer bound to the class. That means + * that the USB storage device is no longer connected. Refuse any + * further attempts to open the driver. */ ret = -ENODEV; @@ -1876,6 +1901,7 @@ static int usbhost_open(FAR struct inode *inode) priv->crefs++; ret = OK; } + leave_critical_section(flags); usbhost_givesem(&priv->exclsem); @@ -2012,7 +2038,8 @@ static ssize_t usbhost_read(FAR struct inode *inode, unsigned char *buffer, /* Receive the CSW */ nbytes = DRVR_TRANSFER(hport->drvr, priv->bulkin, - priv->tbuffer, USBMSC_CSW_SIZEOF); + priv->tbuffer, + USBMSC_CSW_SIZEOF); if (nbytes >= 0) { FAR struct usbmsc_csw_s *csw; @@ -2022,7 +2049,8 @@ static ssize_t usbhost_read(FAR struct inode *inode, unsigned char *buffer, csw = (FAR struct usbmsc_csw_s *)priv->tbuffer; if (csw->status != 0) { - uerr("ERROR: CSW status error: %d\n", csw->status); + uerr("ERROR: CSW status error: %d\n", + csw->status); nbytes = -ENODEV; } } @@ -2049,8 +2077,9 @@ static ssize_t usbhost_read(FAR struct inode *inode, unsigned char *buffer, * ****************************************************************************/ -static ssize_t usbhost_write(FAR struct inode *inode, const unsigned char *buffer, - size_t startsector, unsigned int nsectors) +static ssize_t usbhost_write(FAR struct inode *inode, + FAR const unsigned char *buffer, + size_t startsector, unsigned int nsectors) { FAR struct usbhost_state_s *priv; FAR struct usbhost_hubport_s *hport; @@ -2081,7 +2110,7 @@ static ssize_t usbhost_write(FAR struct inode *inode, const unsigned char *buffe usbhost_takesem(&priv->exclsem); - /* Assume allocation failure */ + /* Assume allocation failure */ nbytes = -ENOMEM; @@ -2104,7 +2133,8 @@ static ssize_t usbhost_write(FAR struct inode *inode, const unsigned char *buffe /* Send the user data */ nbytes = DRVR_TRANSFER(hport->drvr, priv->bulkout, - (FAR uint8_t *)buffer, priv->blocksize * nsectors); + (FAR uint8_t *)buffer, + priv->blocksize * nsectors); if (nbytes >= 0) { /* Receive the CSW */ @@ -2143,7 +2173,8 @@ static ssize_t usbhost_write(FAR struct inode *inode, const unsigned char *buffe * ****************************************************************************/ -static int usbhost_geometry(FAR struct inode *inode, struct geometry *geometry) +static int usbhost_geometry(FAR struct inode *inode, + FAR struct geometry *geometry) { FAR struct usbhost_state_s *priv; int ret = -EINVAL; @@ -2225,8 +2256,10 @@ static int usbhost_ioctl(FAR struct inode *inode, int cmd, unsigned long arg) ret = -ENOTTY; break; } + usbhost_givesem(&priv->exclsem); } + return ret; } diff --git a/fs/driver/fs_blockpartition.c b/fs/driver/fs_blockpartition.c index 3e662af4ab84..f42d7fc2407e 100644 --- a/fs/driver/fs_blockpartition.c +++ b/fs/driver/fs_blockpartition.c @@ -68,13 +68,15 @@ struct part_struct_s static int part_open(FAR struct inode *inode); static int part_close(FAR struct inode *inode); -static ssize_t part_read(FAR struct inode *inode, unsigned char *buffer, - size_t start_sector, unsigned int nsectors); -static ssize_t part_write(FAR struct inode *inode, const unsigned char *buffer, - size_t start_sector, unsigned int nsectors); -static int part_geometry(FAR struct inode *inode, struct geometry *geometry); -static int part_ioctl(FAR struct inode *inode, int cmd, unsigned long arg); - +static ssize_t part_read(FAR struct inode *inode, FAR unsigned char *buffer, + size_t start_sector, unsigned int nsectors); +static ssize_t part_write(FAR struct inode *inode, + FAR const unsigned char *buffer, size_t start_sector, + unsigned int nsectors); +static int part_geometry(FAR struct inode *inode, + FAR struct geometry *geometry); +static int part_ioctl(FAR struct inode *inode, int cmd, + unsigned long arg); #ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS static int part_unlink(FAR struct inode *inode); #endif @@ -174,8 +176,9 @@ static ssize_t part_read(FAR struct inode *inode, unsigned char *buffer, * ****************************************************************************/ -static ssize_t part_write(FAR struct inode *inode, const unsigned char *buffer, - size_t start_sector, unsigned int nsectors) +static ssize_t part_write(FAR struct inode *inode, + FAR const unsigned char *buffer, + size_t start_sector, unsigned int nsectors) { FAR struct part_struct_s *dev = inode->i_private; FAR struct inode *parent = dev->parent; @@ -245,12 +248,14 @@ static int part_ioctl(FAR struct inode *inode, int cmd, unsigned long arg) ret = parent->u.i_bops->geometry(parent, &geo); if (ret >= 0) { - *(FAR uint8_t *)base += dev->firstsector * geo.geo_sectorsize; + *(FAR uint8_t *)base += + dev->firstsector * geo.geo_sectorsize; } } else if (cmd == MTDIOC_GEOMETRY) { - FAR struct mtd_geometry_s *mgeo = (FAR struct mtd_geometry_s *)arg; + FAR struct mtd_geometry_s *mgeo = + (FAR struct mtd_geometry_s *)arg; uint32_t blkper = mgeo->erasesize / mgeo->blocksize; mgeo->neraseblocks = dev->nsectors / blkper; diff --git a/fs/vfs/fs_rename.c b/fs/vfs/fs_rename.c index e6983b5b48b1..72950a1a1591 100644 --- a/fs/vfs/fs_rename.c +++ b/fs/vfs/fs_rename.c @@ -488,8 +488,8 @@ int rename(FAR const char *oldpath, FAR const char *newpath) FAR struct inode *oldinode; int ret; - /* Ignore paths that are interpreted as the root directory which has no name - * and cannot be moved + /* Ignore paths that are interpreted as the root directory which has no + * name and cannot be moved */ if (!oldpath || *oldpath == '\0' || oldpath[0] != '/' || diff --git a/fs/vfs/fs_rmdir.c b/fs/vfs/fs_rmdir.c index 3c90b8208a9c..25afcf6cc767 100644 --- a/fs/vfs/fs_rmdir.c +++ b/fs/vfs/fs_rmdir.c @@ -138,9 +138,9 @@ int rmdir(FAR const char *pathname) } /* Remove the inode. NOTE: Because we hold a reference count on the - * inode, it will not be deleted now. But probably when inode_release() - * is called below. inode_remove should return -EBUSY to indicate that - * the inode was not deleted now. + * inode, it will not be deleted now. But probably when + * inode_release() is called below. inode_remove should return + * -EBUSY to indicate that the inode was not deleted now. */ inode_semtake(); diff --git a/include/nuttx/drivers/ramdisk.h b/include/nuttx/drivers/ramdisk.h index 63848be1b517..ddffaa6071d7 100644 --- a/include/nuttx/drivers/ramdisk.h +++ b/include/nuttx/drivers/ramdisk.h @@ -1,35 +1,20 @@ /**************************************************************************** * include/nuttx/drivers/ramdisk.h * - * Copyright (C) 2008-2009, 2012-2013, 2015-2016 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: + * http://www.apache.org/licenses/LICENSE-2.0 * - * 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. + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. * ****************************************************************************/ diff --git a/libs/libc/stdlib/lib_mkstemp.c b/libs/libc/stdlib/lib_mkstemp.c index ee996e578255..5b6e5dd071c5 100644 --- a/libs/libc/stdlib/lib_mkstemp.c +++ b/libs/libc/stdlib/lib_mkstemp.c @@ -157,14 +157,14 @@ static void get_base62(FAR uint8_t *ptr) static void copy_base62(FAR const uint8_t *src, FAR char *dest, int len) { if (len < MAX_XS) - { - src += MAX_XS - len; - } - - for (; len > 0; len--) - { - *dest++ = base62_to_char(*src++); - } + { + src += MAX_XS - len; + } + + for (; len > 0; len--) + { + *dest++ = base62_to_char(*src++); + } } /****************************************************************************