forked from Archive/PX4-Autopilot
Additional patches from Petteri Aimonen for FAT, STM32 SPI, and AT25
git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5593 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
parent
04a4ef84f0
commit
a6d4497461
|
@ -263,3 +263,6 @@
|
|||
for other widgets. Subclasses will override drawContents and decide
|
||||
themselves how to draw the background.
|
||||
* CNxWidgets::CTabPanel: A new widget contributed by Petteri Aimonen.
|
||||
This widget provides a tab panel, which has a button bar at the top
|
||||
and panels below it. Pressing a button will select the corresponding
|
||||
panel.
|
||||
|
|
|
@ -4078,4 +4078,21 @@
|
|||
override CROSSDEV with a make command line argument.
|
||||
* include/assert.h: Mark assertion functions as non-returning.
|
||||
* arch/*/src/*/up_assert.h: Mark _up_assert() as non-returning.
|
||||
|
||||
* drivers/mtd/at25.c: When the AT25 device was not available the
|
||||
initialization did not fail like it should. From Petteri Aimonen.
|
||||
* fs/fat/fs_configfat.c: Fix some errors in FAT formatting logic
|
||||
for large devices and for FAT32. From Petteri Aimonen.
|
||||
* fs/fat/fs_fat32util.c: Fix an initialization error found by
|
||||
Petteri Aimonen. freecount and next freecount initialization were
|
||||
reversed.
|
||||
* drivers/mmcsd/mmcsd_spi.c: Some SD cards will appear busy until
|
||||
switched to SPI mode for first time. Having a pull-up resistor on
|
||||
MISO may avoid this problem, but this patch makes it work also
|
||||
without pull-up. From Petteri Aimonen.
|
||||
* fs/fat/fs_fat32.c: Fix a compilation error when FAT_DMAMEMORY=y.
|
||||
From Petteri Aimonen.
|
||||
* arch/arm/src/stm32/chip/stm32_spi.h: STM32F4 max SPI clock freq is
|
||||
37.5 MHz. Patch from Petteri Aimonen.
|
||||
* arch/arm/src/stm32/stm32_spi.c: Fixes for SPI DMA work on the
|
||||
STM32F4. Includes untested additions for the F1 implementation as
|
||||
well. From Petteri Aimonen.
|
||||
|
|
|
@ -47,7 +47,13 @@
|
|||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
#define STM32_SPI_CLK_MAX 18000000UL /* Maximum allowed speed as per specifications for all SPIs */
|
||||
/* Maximum allowed speed as per specifications for all SPIs */
|
||||
|
||||
#if defined(CONFIG_STM32_STM32F40XX)
|
||||
# define STM32_SPI_CLK_MAX 37500000UL
|
||||
#else
|
||||
# define STM32_SPI_CLK_MAX 18000000UL
|
||||
#endif
|
||||
|
||||
/* Register Offsets *****************************************************************/
|
||||
|
||||
|
|
|
@ -130,14 +130,28 @@
|
|||
|
||||
/* DMA channel configuration */
|
||||
|
||||
#define SPI_RXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC )
|
||||
#define SPI_RXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC )
|
||||
#define SPI_RXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS )
|
||||
#define SPI_RXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS )
|
||||
#define SPI_TXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC|DMA_CCR_DIR)
|
||||
#define SPI_TXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC|DMA_CCR_DIR)
|
||||
#define SPI_TXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS |DMA_CCR_DIR)
|
||||
#define SPI_TXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_DIR)
|
||||
#if defined(CONFIG_STM32_STM32F10XX)
|
||||
# define SPI_RXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC )
|
||||
# define SPI_RXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC )
|
||||
# define SPI_RXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS )
|
||||
# define SPI_RXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS )
|
||||
# define SPI_TXDMA16_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_16BITS|DMA_CCR_PSIZE_16BITS|DMA_CCR_MINC|DMA_CCR_DIR)
|
||||
# define SPI_TXDMA8_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_MINC|DMA_CCR_DIR)
|
||||
# define SPI_TXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_16BITS |DMA_CCR_DIR)
|
||||
# define SPI_TXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_CCR_MSIZE_8BITS |DMA_CCR_PSIZE_8BITS |DMA_CCR_DIR)
|
||||
#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
|
||||
# define SPI_RXDMA16_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_16BITS|DMA_SCR_PSIZE_16BITS|DMA_SCR_MINC|DMA_SCR_DIR_P2M)
|
||||
# define SPI_RXDMA8_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_MINC|DMA_SCR_DIR_P2M)
|
||||
# define SPI_RXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_16BITS |DMA_SCR_DIR_P2M)
|
||||
# define SPI_RXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_DIR_P2M)
|
||||
# define SPI_TXDMA16_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_16BITS|DMA_SCR_PSIZE_16BITS|DMA_SCR_MINC|DMA_SCR_DIR_M2P)
|
||||
# define SPI_TXDMA8_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_MINC|DMA_SCR_DIR_M2P)
|
||||
# define SPI_TXDMA16NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_16BITS |DMA_SCR_DIR_M2P)
|
||||
# define SPI_TXDMA8NULL_CONFIG (SPI_DMA_PRIO|DMA_SCR_MSIZE_8BITS |DMA_SCR_PSIZE_8BITS |DMA_SCR_DIR_M2P)
|
||||
#else
|
||||
# error "Unknown STM32 DMA"
|
||||
#endif
|
||||
|
||||
|
||||
/* Debug ****************************************************************************/
|
||||
/* Check if (non-standard) SPI debug is enabled */
|
||||
|
@ -549,6 +563,21 @@ static inline void spi_dmarxwakeup(FAR struct stm32_spidev_s *priv)
|
|||
}
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: spi_dmatxwakeup
|
||||
*
|
||||
* Description:
|
||||
* Signal that DMA is complete
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_STM32_SPI_DMA
|
||||
static inline void spi_dmatxwakeup(FAR struct stm32_spidev_s *priv)
|
||||
{
|
||||
(void)sem_post(&priv->txsem);
|
||||
}
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: spi_dmarxcallback
|
||||
*
|
||||
|
@ -1183,8 +1212,8 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
|
|||
FAR void *rxbuffer, size_t nwords)
|
||||
{
|
||||
FAR struct stm32_spidev_s *priv = (FAR struct stm32_spidev_s *)dev;
|
||||
uint16_t rxdummy = 0xffff;
|
||||
uint16_t txdummy;
|
||||
static uint16_t rxdummy = 0xffff;
|
||||
static const uint16_t txdummy = 0xffff;
|
||||
|
||||
spivdbg("txbuffer=%p rxbuffer=%p nwords=%d\n", txbuffer, rxbuffer, nwords);
|
||||
DEBUGASSERT(priv && priv->spibase);
|
||||
|
@ -1330,6 +1359,8 @@ static void spi_portinitialize(FAR struct stm32_spidev_s *priv)
|
|||
priv->rxdma = stm32_dmachannel(priv->rxch);
|
||||
priv->txdma = stm32_dmachannel(priv->txch);
|
||||
DEBUGASSERT(priv->rxdma && priv->txdma);
|
||||
|
||||
spi_putreg(priv, STM32_SPI_CR2_OFFSET, SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN);
|
||||
#endif
|
||||
|
||||
/* Enable spi */
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* drivers/mmcsd/mmcsd_spi.c
|
||||
*
|
||||
* Copyright (C) 2008-2010, 2011-2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2008-2010, 2011-2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -409,10 +409,14 @@ static uint32_t mmcsd_sendcmd(FAR struct mmcsd_slot_s *slot,
|
|||
int ret;
|
||||
int i;
|
||||
|
||||
/* Wait until the card is not busy */
|
||||
/* Wait until the card is not busy. Some SD cards will not enter the IDLE
|
||||
* state until CMD0 is sent for the first time, switching the card to SPI
|
||||
* mode. Having a pull-up resistor on MISO may avoid this problem, but
|
||||
* this check makes it work also without the pull-up.
|
||||
*/
|
||||
|
||||
ret = mmcsd_waitready(slot);
|
||||
if (ret != OK)
|
||||
if (ret != OK && cmd != &g_cmd0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
|
|
@ -691,14 +691,16 @@ FAR struct mtd_dev_s *at25_initialize(FAR struct spi_dev_s *dev)
|
|||
kfree(priv);
|
||||
priv = NULL;
|
||||
}
|
||||
|
||||
/* Unprotect all sectors */
|
||||
else
|
||||
{
|
||||
/* Unprotect all sectors */
|
||||
|
||||
at25_writeenable(priv);
|
||||
SPI_SELECT(priv->dev, SPIDEV_FLASH, true);
|
||||
(void)SPI_SEND(priv->dev, AT25_WRSR);
|
||||
(void)SPI_SEND(priv->dev, AT25_SR_UNPROT);
|
||||
SPI_SELECT(priv->dev, SPIDEV_FLASH, false);
|
||||
at25_writeenable(priv);
|
||||
SPI_SELECT(priv->dev, SPIDEV_FLASH, true);
|
||||
(void)SPI_SEND(priv->dev, AT25_WRSR);
|
||||
(void)SPI_SEND(priv->dev, AT25_SR_UNPROT);
|
||||
SPI_SELECT(priv->dev, SPIDEV_FLASH, false);
|
||||
}
|
||||
}
|
||||
|
||||
/* Return the implementation-specific state structure as the MTD device */
|
||||
|
|
|
@ -406,7 +406,7 @@ mkfatfs_clustersearchlimits(FAR struct fat_format_s *fmt, FAR struct fat_var_s *
|
|||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: mkfatfs_try12
|
||||
* Name: mkfatfs_tryfat12
|
||||
*
|
||||
* Description:
|
||||
* Try to define a FAT12 filesystem on the device using the candidate
|
||||
|
@ -462,7 +462,7 @@ mkfatfs_tryfat12(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var,
|
|||
* FAT12 (remembering that two FAT cluster slots are reserved).
|
||||
*/
|
||||
|
||||
if (config->fc_nclusters > maxnclusters - 2)
|
||||
if (config->fc_nclusters + 2 > maxnclusters)
|
||||
{
|
||||
fvdbg("Too many clusters for FAT12\n");
|
||||
return -ENFILE;
|
||||
|
@ -472,7 +472,7 @@ mkfatfs_tryfat12(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var,
|
|||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: mkfatfs_try16
|
||||
* Name: mkfatfs_tryfat16
|
||||
*
|
||||
* Description:
|
||||
* Try to define a FAT16 filesystem on the device using the candidate
|
||||
|
@ -532,7 +532,7 @@ mkfatfs_tryfat16(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var,
|
|||
* be confused as a FAT12 at mount time.
|
||||
*/
|
||||
|
||||
if ((config->fc_nclusters > maxnclusters - 2) ||
|
||||
if ((config->fc_nclusters + 2 > maxnclusters) ||
|
||||
(config->fc_nclusters < FAT_MINCLUST16))
|
||||
{
|
||||
fvdbg("Too few or too many clusters for FAT16\n");
|
||||
|
@ -543,7 +543,7 @@ mkfatfs_tryfat16(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var,
|
|||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: mkfatfs_try32
|
||||
* Name: mkfatfs_tryfat32
|
||||
*
|
||||
* Description:
|
||||
* Try to define a FAT32 filesystem on the device using the candidate
|
||||
|
@ -587,7 +587,7 @@ mkfatfs_tryfat32(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var,
|
|||
* maxnclusters = nfatsects * sectorsize / 4 - 2
|
||||
*/
|
||||
|
||||
maxnclusters = (config->fc_nfatsects >> (var->fv_sectshift - 2));
|
||||
maxnclusters = (config->fc_nfatsects << (var->fv_sectshift - 2));
|
||||
if (maxnclusters > FAT_MAXCLUST32)
|
||||
{
|
||||
maxnclusters = FAT_MAXCLUST32;
|
||||
|
@ -599,7 +599,7 @@ mkfatfs_tryfat32(FAR struct fat_format_s *fmt, FAR struct fat_var_s *var,
|
|||
* FAT32 (remembering that two FAT cluster slots are reserved).
|
||||
*/
|
||||
|
||||
if ((config->fc_nclusters > maxnclusters - 3) ||
|
||||
if ((config->fc_nclusters + 3 > maxnclusters) ||
|
||||
(config->fc_nclusters < FAT_MINCLUST32 && fmt->ff_fattype != 32))
|
||||
{
|
||||
fvdbg("Too few or too many clusters for FAT32\n");
|
||||
|
|
|
@ -381,6 +381,7 @@ static int fat_close(FAR struct file *filep)
|
|||
{
|
||||
struct inode *inode;
|
||||
struct fat_file_s *ff;
|
||||
struct fat_mountpt_s *fs;
|
||||
int ret = OK;
|
||||
|
||||
/* Sanity checks */
|
||||
|
@ -391,6 +392,7 @@ static int fat_close(FAR struct file *filep)
|
|||
|
||||
ff = filep->f_priv;
|
||||
inode = filep->f_inode;
|
||||
fs = inode->i_private;
|
||||
|
||||
/* Do not check if the mount is healthy. We must support closing of
|
||||
* the file even when there is healthy mount.
|
||||
|
@ -408,6 +410,7 @@ static int fat_close(FAR struct file *filep)
|
|||
|
||||
if (ff->ff_buffer)
|
||||
{
|
||||
(void)fs; /* Unused if fat_io_free == free(). */
|
||||
fat_io_free(ff->ff_buffer, fs->fs_hwsectorsize);
|
||||
}
|
||||
|
||||
|
|
|
@ -106,8 +106,8 @@ static int fat_checkfsinfo(struct fat_mountpt_s *fs)
|
|||
FSI_GETSTRUCTSIG(fs->fs_buffer) == 0x61417272 &&
|
||||
FSI_GETTRAILSIG(fs->fs_buffer) == BOOT_SIGNATURE32)
|
||||
{
|
||||
fs->fs_fsinextfree = FSI_GETFREECOUNT(fs->fs_buffer);
|
||||
fs->fs_fsifreecount = FSI_GETNXTFREE(fs->fs_buffer);
|
||||
fs->fs_fsifreecount = FSI_GETFREECOUNT(fs->fs_buffer);
|
||||
fs->fs_fsinextfree = FSI_GETNXTFREE(fs->fs_buffer);
|
||||
return OK;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue