summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/Documentation/NuttX.html4
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_spi.c42
-rw-r--r--nuttx/examples/nsh/nsh_fscmds.c2
-rw-r--r--nuttx/fs/fat/fs_fat32.c4
-rw-r--r--nuttx/fs/fs_mount.c11
6 files changed, 50 insertions, 15 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 95fced4fe..a21520a72 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -749,5 +749,7 @@
* configs/mcu123-lpc214x/src: Corrected some logic in the LPC2148 SPI receive block
logic. Re-verified SDC ver1.x support with 1Gb Toshiba SDC, 1Gb PNY SDC, 2Gb SanDisk SDC,
and 4Gb Kingston SDHC.
+ * fs/fs_mount.c: Corrected error handling that could cause a deadlock on certain
+ mount() failures.
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index 035d5d084..4e651caa4 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -8,7 +8,7 @@
<tr align="center" bgcolor="#e4e4e4">
<td>
<h1><big><font color="#3c34ec"><i>NuttX RTOS</i></font></big></h1>
- <p>Last Updated: May 28, 2009</p>
+ <p>Last Updated: May 29, 2009</p>
</td>
</tr>
</table>
@@ -1439,6 +1439,8 @@ nuttx-0.4.7 2009-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
* configs/mcu123-lpc214x/src: Corrected some logic in the LPC2148 SPI receive block
logic. Re-verified SDC ver1.x support with 1Gb Toshiba SDC, 1Gb PNY SDC, 2Gb SanDisk SDC,
and 4Gb Kingston SDHC.
+ * fs/fs_mount.c: Corrected error handling that could cause a deadlock on certain
+ mount() failures.
pascal-0.1.3 2009-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
diff --git a/nuttx/drivers/mmcsd/mmcsd_spi.c b/nuttx/drivers/mmcsd/mmcsd_spi.c
index dafcc4fc2..cadf8bbd8 100644
--- a/nuttx/drivers/mmcsd/mmcsd_spi.c
+++ b/nuttx/drivers/mmcsd/mmcsd_spi.c
@@ -431,8 +431,17 @@ static uint32 mmcsd_sendcmd(FAR struct mmcsd_slot_s *slot,
FAR struct spi_dev_s *spi = slot->spi;
uint32 result;
ubyte response = 0xff;
+ int ret;
int i;
+ /* Wait until the card is not busy */
+
+ ret = mmcsd_waitready(slot);
+ if (ret != OK)
+ {
+ return ret;
+ }
+
/* Send command code */
SPI_SEND(spi, cmd->cmd);
@@ -1012,15 +1021,34 @@ static int mmcsd_open(FAR struct inode *inode)
}
#endif
- /* Select the slave */
+ /* Verify that an MMC/SD card has been inserted */
+ ret = -ENODEV;
mmcsd_semtake(&slot->sem);
- SPI_SELECT(spi, SPIDEV_MMCSD, TRUE);
+ if ((SPI_STATUS(spi, SPIDEV_MMCSD) & SPI_STATUS_PRESENT) != 0)
+ {
+ /* Yes.. a card is present. Has it been initialized? */
- /* Verify that the MMC/SD card is alive and ready for business */
+ if (slot->type == MMCSD_CARDTYPE_UNKNOWN)
+ {
+ /* Ininitialize for the media in the slot */
- ret = mmcsd_waitready(slot);
- SPI_SELECT(spi, SPIDEV_MMCSD, FALSE);
+ ret = mmcsd_mediainitialize(slot);
+ if (ret < 0)
+ {
+ fvdbg("Failed to initialize card\n");
+ goto errout_with_sem;
+ }
+ }
+
+ /* Make sure that the card is ready */
+
+ SPI_SELECT(spi, SPIDEV_MMCSD, TRUE);
+ ret = mmcsd_waitready(slot);
+ SPI_SELECT(spi, SPIDEV_MMCSD, FALSE);
+ }
+
+errout_with_sem:
mmcsd_semgive(&slot->sem);
return ret;
}
@@ -1084,7 +1112,7 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer,
}
#endif
- /* Verify that card is availabled */
+ /* Verify that card is available */
if (slot->state & MMCSD_SLOTSTATUS_NOTREADY)
{
@@ -1237,7 +1265,7 @@ static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer,
}
#endif
- /* Verify that card is availabled */
+ /* Verify that card is available */
if (slot->state & MMCSD_SLOTSTATUS_NOTREADY)
{
diff --git a/nuttx/examples/nsh/nsh_fscmds.c b/nuttx/examples/nsh/nsh_fscmds.c
index 301abddbb..5b51a4db0 100644
--- a/nuttx/examples/nsh/nsh_fscmds.c
+++ b/nuttx/examples/nsh/nsh_fscmds.c
@@ -1,7 +1,7 @@
/****************************************************************************
* examples/nsh/nsh_fscmds.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/fs/fat/fs_fat32.c b/nuttx/fs/fat/fs_fat32.c
index a0a277475..a28d57a4e 100644
--- a/nuttx/fs/fat/fs_fat32.c
+++ b/nuttx/fs/fat/fs_fat32.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs_fat32.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* References:
@@ -1482,7 +1482,7 @@ static int fat_bind(FAR struct inode *blkdriver, const void *data,
}
if (blkdriver->u.i_bops->open &&
- blkdriver->u.i_bops->open(blkdriver) != OK)
+ blkdriver->u.i_bops->open(blkdriver) != OK)
{
return -ENODEV;
}
diff --git a/nuttx/fs/fs_mount.c b/nuttx/fs/fs_mount.c
index d0806ba7d..22af7a136 100644
--- a/nuttx/fs/fs_mount.c
+++ b/nuttx/fs/fs_mount.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/fs_mount.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -231,7 +231,7 @@ int mount(const char *source, const char *target,
fdbg("Bind method failed: %d\n", status);
errcode = -status;
- goto errout_with_blkdrvr;
+ goto errout_with_mountpt;
}
/* We have it, now populate it with driver specific information. */
@@ -256,13 +256,16 @@ int mount(const char *source, const char *target,
/* A lot of goto's! But they make the error handling much simpler */
-errout_with_blkdrvr:
- inode_release(blkdrvr_inode);
errout_with_mountpt:
+ inode_semgive();
+ inode_release(blkdrvr_inode);
inode_release(mountpt_inode);
+ goto errout;
+
errout_with_semaphore:
inode_semgive();
inode_release(blkdrvr_inode);
+
errout:
errno = errcode;
return ERROR;