summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-08 15:28:07 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-08 15:28:07 +0000
commitb6abad5fbf5877bf9c26269bff418726f26e4b9d (patch)
tree945b66a02dfe50fed4a55a500a96f11d81d7d9e3 /nuttx
parent1442e62637fa138626671be49b51d5329c6536c3 (diff)
downloadpx4-nuttx-b6abad5fbf5877bf9c26269bff418726f26e4b9d.tar.gz
px4-nuttx-b6abad5fbf5877bf9c26269bff418726f26e4b9d.tar.bz2
px4-nuttx-b6abad5fbf5877bf9c26269bff418726f26e4b9d.zip
Several patches from Petteri Aimonen
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5625 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog15
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_spi.c6
-rw-r--r--nuttx/drivers/input/max11802.c28
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_spi.c71
-rw-r--r--nuttx/graphics/nxfonts/nxfonts_sans17x22.h4
-rw-r--r--nuttx/mm/mm_mallinfo.c10
6 files changed, 102 insertions, 32 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 5b8730f3c..c1766a609 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -4161,4 +4161,17 @@
* arch/arm/src/lpc17xx: Add support for the Cortex-M4 FPU and
Mikes "common vector" logic. The LPC1788 is going to need
these things.
-
+ * arch/arm/src/stm32/stm32_spi.c: Fix SPI DMA logic that does
+ not work if sem_wait() is interrupt by a signal. From Petteri
+ Aimonen.
+ * drivers/input/max11802.c: MAX11802: Fix a timing bug that
+ corrupted coordinates. From Petteri Aimonen.
+ * drivers/mmcsd/mmcsd_spi.c: Use SPI locking so that MMC/SD can
+ exist on the same bus as other SPI devices. From Petteri
+ Aimonen.
+ * graphics/nxfonts/nxfonts_sans17x22.h: Small mod to hyphen in
+ sans17x22 font. The hyphen did not have any space on its sides.
+ This caused it to run together with other characters so that for
+ example "+-" would look weird. From Petteri Aimonen.
+ * mm/mm_mallinfo.c: Take MM semaphore in mm_mallinfo. From Petteri
+ Aimonen.
diff --git a/nuttx/arch/arm/src/stm32/stm32_spi.c b/nuttx/arch/arm/src/stm32/stm32_spi.c
index b4a4f36ab..7119247f7 100644
--- a/nuttx/arch/arm/src/stm32/stm32_spi.c
+++ b/nuttx/arch/arm/src/stm32/stm32_spi.c
@@ -511,7 +511,7 @@ static void spi_dmarxwait(FAR struct stm32_spidev_s *priv)
* must not really have completed???
*/
- while (sem_wait(&priv->rxsem) != 0 && priv->rxresult == 0)
+ while (sem_wait(&priv->rxsem) != 0 || priv->rxresult == 0)
{
/* The only case that an error should occur here is if the wait was awakened
* by a signal.
@@ -537,7 +537,7 @@ static void spi_dmatxwait(FAR struct stm32_spidev_s *priv)
* must not really have completed???
*/
- while (sem_wait(&priv->txsem) != 0 && priv->txresult == 0)
+ while (sem_wait(&priv->txsem) != 0 || priv->txresult == 0)
{
/* The only case that an error should occur here is if the wait was awakened
* by a signal.
@@ -731,6 +731,7 @@ static void spi_dmatxsetup(FAR struct stm32_spidev_s *priv, FAR const void *txbu
#ifdef CONFIG_STM32_SPI_DMA
static inline void spi_dmarxstart(FAR struct stm32_spidev_s *priv)
{
+ priv->rxresult = 0;
stm32_dmastart(priv->rxdma, spi_dmarxcallback, priv, false);
}
#endif
@@ -746,6 +747,7 @@ static inline void spi_dmarxstart(FAR struct stm32_spidev_s *priv)
#ifdef CONFIG_STM32_SPI_DMA
static inline void spi_dmatxstart(FAR struct stm32_spidev_s *priv)
{
+ priv->txresult = 0;
stm32_dmastart(priv->txdma, spi_dmatxcallback, priv, false);
}
#endif
diff --git a/nuttx/drivers/input/max11802.c b/nuttx/drivers/input/max11802.c
index ea3883cd0..9cb8dee0e 100644
--- a/nuttx/drivers/input/max11802.c
+++ b/nuttx/drivers/input/max11802.c
@@ -188,11 +188,9 @@ static void max11802_lock(FAR struct spi_dev_s *spi)
* unlocked)
*/
- SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true);
SPI_SETMODE(spi, CONFIG_MAX11802_SPIMODE);
SPI_SETBITS(spi, 8);
SPI_SETFREQUENCY(spi, CONFIG_MAX11802_FREQUENCY);
- SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false);
}
#endif
@@ -249,11 +247,9 @@ static inline void max11802_configspi(FAR struct spi_dev_s *spi)
* bother because it might change.
*/
- SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true);
SPI_SETMODE(spi, CONFIG_MAX11802_SPIMODE);
SPI_SETBITS(spi, 8);
SPI_SETFREQUENCY(spi, CONFIG_MAX11802_FREQUENCY);
- SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false);
}
#endif
@@ -629,10 +625,20 @@ static void max11802_worker(FAR void *arg)
}
else
{
- /* Wait for data ready */
- do {
- /* Handle pen down events. First, sample positional values. */
+ /* Wait for data ready
+ * Note: MAX11802 signals the readiness of the results using
+ * the lowest 4 bits of the result. However these are the
+ * last bits to be read out of the device. It appears that
+ * the hardware value can change in the middle of the readout,
+ * causing the upper bits to be still invalid even though lower
+ * bits indicate valid result.
+ *
+ * We work around this by reading the registers once more after
+ * the tags indicate they are ready.
+ */
+ int readycount = 0;
+ do {
#ifdef CONFIG_MAX11802_SWAPXY
x = max11802_sendcmd(priv, MAX11802_CMD_YPOSITION, &tags);
y = max11802_sendcmd(priv, MAX11802_CMD_XPOSITION, &tags2);
@@ -640,8 +646,12 @@ static void max11802_worker(FAR void *arg)
x = max11802_sendcmd(priv, MAX11802_CMD_XPOSITION, &tags);
y = max11802_sendcmd(priv, MAX11802_CMD_YPOSITION, &tags2);
#endif
- } while (tags == 0xF || tags2 == 0xF);
-
+ if (tags != 0xF && tags2 != 0xF)
+ {
+ readycount++;
+ }
+ } while (readycount < 2);
+
/* Continue to sample the position while the pen is down */
wd_start(priv->wdog, MAX11802_WDOG_DELAY, max11802_wdog, 1, (uint32_t)priv);
diff --git a/nuttx/drivers/mmcsd/mmcsd_spi.c b/nuttx/drivers/mmcsd/mmcsd_spi.c
index 3d4cf1dd1..9939fa9de 100644
--- a/nuttx/drivers/mmcsd/mmcsd_spi.c
+++ b/nuttx/drivers/mmcsd/mmcsd_spi.c
@@ -169,7 +169,8 @@ struct mmcsd_cmdinfo_s
/* Misc *********************************************************************/
-static void mmcsd_semtake(sem_t *sem);
+static void mmcsd_semtake(sem_t *sem, FAR struct spi_dev_s *spi);
+static void mmcsd_semgive(sem_t *sem, FAR struct spi_dev_s *spi);
/* Card SPI interface *******************************************************/
@@ -339,8 +340,18 @@ static const struct mmcsd_cmdinfo_s g_acmd41 = {ACMD41, MMCSD_CMDRESP_R1, 0xff};
* Name: mmcsd_semtake
****************************************************************************/
-static void mmcsd_semtake(sem_t *sem)
+static void mmcsd_semtake(sem_t *sem, FAR struct spi_dev_s *spi)
{
+ /* Get exclusive access to the SPI bus (if necessary) */
+
+#ifndef CONFIG_SPI_OWNBUS
+ (void)SPI_LOCK(spi, true);
+#endif
+
+ /* Get exclusive access to the MMC/SD device (prossibly un-necessary if
+ * SPI_LOCK is also implemented as a semaphore.
+ */
+
while (sem_wait(sem) != 0)
{
/* The only case that an error should occur here is if the wait was
@@ -351,8 +362,19 @@ static void mmcsd_semtake(sem_t *sem)
}
}
-#define mmcsd_semgive(sem) sem_post(sem)
+static void mmcsd_semgive(sem_t *sem, FAR struct spi_dev_s *spi)
+{
+ /* Relinquish the lock on the MMC/SD device */
+
+ sem_post(sem);
+ /* Relinquish the lock on the SPI bus */
+
+#ifndef CONFIG_SPI_OWNBUS
+ (void)SPI_LOCK(spi, false);
+#endif
+}
+
/****************************************************************************
* Name: mmcsd_waitready
*
@@ -1005,7 +1027,7 @@ static int mmcsd_open(FAR struct inode *inode)
/* Verify that an MMC/SD card has been inserted */
ret = -ENODEV;
- mmcsd_semtake(&slot->sem);
+ mmcsd_semtake(&slot->sem, spi);
if ((SPI_STATUS(spi, SPIDEV_MMCSD) & SPI_STATUS_PRESENT) != 0)
{
/* Yes.. a card is present. Has it been initialized? */
@@ -1030,7 +1052,7 @@ static int mmcsd_open(FAR struct inode *inode)
}
errout_with_sem:
- mmcsd_semgive(&slot->sem);
+ mmcsd_semgive(&slot->sem, spi);
return ret;
}
@@ -1124,7 +1146,7 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer,
/* Select the slave */
- mmcsd_semtake(&slot->sem);
+ mmcsd_semtake(&slot->sem, spi);
SPI_SELECT(spi, SPIDEV_MMCSD, true);
/* Single or multiple block read? */
@@ -1172,6 +1194,7 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer,
fdbg("Failed: to receive the block\n");
goto errout_with_eio;
}
+
buffer += SECTORSIZE(slot);
}
@@ -1184,7 +1207,7 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer,
SPI_SELECT(spi, SPIDEV_MMCSD, false);
SPI_SEND(spi, 0xff);
- mmcsd_semgive(&slot->sem);
+ mmcsd_semgive(&slot->sem, spi);
fvdbg("Read %d bytes:\n", nbytes);
mmcsd_dumpbuffer("Read buffer", buffer, nbytes);
@@ -1192,7 +1215,7 @@ static ssize_t mmcsd_read(FAR struct inode *inode, unsigned char *buffer,
errout_with_eio:
SPI_SELECT(spi, SPIDEV_MMCSD, false);
- mmcsd_semgive(&slot->sem);
+ mmcsd_semgive(&slot->sem, spi);
return -EIO;
}
@@ -1281,11 +1304,12 @@ static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer,
offset = start_sector * SECTORSIZE(slot);
fvdbg("nbytes=%d byte offset=%d\n", nbytes, offset);
}
+
mmcsd_dumpbuffer("Write buffer", buffer, nbytes);
/* Select the slave */
- mmcsd_semtake(&slot->sem);
+ mmcsd_semtake(&slot->sem, spi);
SPI_SELECT(spi, SPIDEV_MMCSD, true);
/* Single or multiple block transfer? */
@@ -1356,7 +1380,7 @@ static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer,
ret = mmcsd_waitready(slot);
SPI_SELECT(spi, SPIDEV_MMCSD, false);
SPI_SEND(spi, 0xff);
- mmcsd_semgive(&slot->sem);
+ mmcsd_semgive(&slot->sem, spi);
/* The success return value is the number of sectors written */
@@ -1364,7 +1388,7 @@ static ssize_t mmcsd_write(FAR struct inode *inode, const unsigned char *buffer,
errout_with_sem:
SPI_SELECT(spi, SPIDEV_MMCSD, false);
- mmcsd_semgive(&slot->sem);
+ mmcsd_semgive(&slot->sem, spi);
return -EIO;
}
#endif
@@ -1413,14 +1437,14 @@ static int mmcsd_geometry(FAR struct inode *inode, struct geometry *geometry)
/* Re-sample the CSD */
- mmcsd_semtake(&slot->sem);
+ mmcsd_semtake(&slot->sem, spi);
SPI_SELECT(spi, SPIDEV_MMCSD, true);
ret = mmcsd_getcsd(slot, csd);
SPI_SELECT(spi, SPIDEV_MMCSD, false);
if (ret < 0)
{
- mmcsd_semgive(&slot->sem);
+ mmcsd_semgive(&slot->sem, spi);
fdbg("mmcsd_getcsd returned %d\n", ret);
return ret;
}
@@ -1449,7 +1473,7 @@ static int mmcsd_geometry(FAR struct inode *inode, struct geometry *geometry)
*/
slot->state &= ~MMCSD_SLOTSTATUS_MEDIACHGD;
- mmcsd_semgive(&slot->sem);
+ mmcsd_semgive(&slot->sem, spi);
fvdbg("geo_available: %d\n", geometry->geo_available);
fvdbg("geo_mediachanged: %d\n", geometry->geo_mediachanged);
@@ -1470,6 +1494,8 @@ static int mmcsd_geometry(FAR struct inode *inode, struct geometry *geometry)
* Description:
* Detect media and initialize
*
+ * Precondition:
+ * Semaphore has been taken.
****************************************************************************/
static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot)
@@ -1479,7 +1505,8 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot)
uint32_t result = MMCSD_SPIR1_IDLESTATE;
uint32_t start;
uint32_t elapsed;
- int i, j;
+ int i;
+ int j;
/* Assume that the card is not ready (we'll clear this on successful card
* initialization.
@@ -1551,6 +1578,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot)
{
fdbg("Send CMD0 failed: R1=%02x\n", result);
SPI_SELECT(spi, SPIDEV_MMCSD, false);
+ mmcsd_semgive(&slot->sem, spi);
return -EIO;
}
@@ -1585,6 +1613,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot)
break;
}
}
+
elapsed = ELAPSED_TIME(start);
}
while (elapsed < MMCSD_DELAY_1SEC);
@@ -1594,6 +1623,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot)
if (elapsed < MMCSD_DELAY_1SEC)
{
fvdbg("Send CMD58\n");
+
SPI_SEND(spi, 0xff);
result = mmcsd_sendcmd(slot, &g_cmd58, 0);
if (result == MMCSD_SPIR1_OK)
@@ -1664,6 +1694,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot)
break;
}
}
+
elapsed = ELAPSED_TIME(start);
}
while (elapsed < MMCSD_DELAY_1SEC);
@@ -1672,6 +1703,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot)
{
fdbg("Failed to exit IDLE state\n");
SPI_SELECT(spi, SPIDEV_MMCSD, false);
+ mmcsd_semgive(&slot->sem, spi);
return -EIO;
}
}
@@ -1680,6 +1712,7 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot)
{
fdbg("Failed to identify card\n");
SPI_SELECT(spi, SPIDEV_MMCSD, false);
+ mmcsd_semgive(&slot->sem, spi);
return -EIO;
}
@@ -1691,8 +1724,10 @@ static int mmcsd_mediainitialize(FAR struct mmcsd_slot_s *slot)
{
fdbg("mmcsd_getcsd(CMD9) failed: %d\n", result);
SPI_SELECT(spi, SPIDEV_MMCSD, false);
+ mmcsd_semgive(&slot->sem, spi);
return -EIO;
}
+
mmcsd_dmpcsd(csd, slot->type);
/* CSD data and set block size */
@@ -1762,7 +1797,7 @@ static void mmcsd_mediachanged(void *arg)
/* Save the current slot state and reassess the new state */
- mmcsd_semtake(&slot->sem);
+ mmcsd_semtake(&slot->sem, spi);
oldstate = slot->state;
/* Check if media was removed or inserted */
@@ -1798,6 +1833,8 @@ static void mmcsd_mediachanged(void *arg)
slot->state |= MMCSD_SLOTSTATUS_MEDIACHGD;
}
}
+
+ mmcsd_semgive(&slot->sem, spi);
}
/****************************************************************************
@@ -1855,7 +1892,9 @@ int mmcsd_spislotinitialize(int minor, int slotno, FAR struct spi_dev_s *spi)
/* Ininitialize for the media in the slot (if any) */
+ mmcsd_semtake(&slot->sem, spi);
ret = mmcsd_mediainitialize(slot);
+ mmcsd_semgive(&slot->sem, spi);
if (ret == 0)
{
fvdbg("mmcsd_mediainitialize returned OK\n");
diff --git a/nuttx/graphics/nxfonts/nxfonts_sans17x22.h b/nuttx/graphics/nxfonts/nxfonts_sans17x22.h
index cea027447..12eeb8fc9 100644
--- a/nuttx/graphics/nxfonts/nxfonts_sans17x22.h
+++ b/nuttx/graphics/nxfonts/nxfonts_sans17x22.h
@@ -114,8 +114,8 @@
#define NXFONT_BITMAP_44 {0x40, 0x40, 0x40, 0x80}
/* hyphen (45) */
-#define NXFONT_METRICS_45 {1, 3, 1, 0, 12, 0}
-#define NXFONT_BITMAP_45 {0xe0}
+#define NXFONT_METRICS_45 {1, 5, 1, 0, 12, 0}
+#define NXFONT_BITMAP_45 {0x70}
/* period (46) */
#define NXFONT_METRICS_46 {1, 1, 2, 1, 15, 0}
diff --git a/nuttx/mm/mm_mallinfo.c b/nuttx/mm/mm_mallinfo.c
index b725535d1..30c1028fd 100644
--- a/nuttx/mm/mm_mallinfo.c
+++ b/nuttx/mm/mm_mallinfo.c
@@ -98,13 +98,17 @@ int mallinfo(struct mallinfo *info)
for (region = 0; region < g_nregions; region++)
#endif
{
- /* Visit each node in the region */
+ /* Visit each node in the region
+ * Retake the semaphore for each region to reduce latencies
+ */
+
+ mm_takesemaphore();
for (node = g_heapstart[region];
node < g_heapend[region];
node = (struct mm_allocnode_s *)((char*)node + node->size))
{
- mvdbg("region=%d node=%p preceding=%p\n", region, node, node->preceding);
+ mvdbg("region=%d node=%p size=%p preceding=%p\n", region, node, node->size, node->preceding);
if (node->preceding & MM_ALLOC_BIT)
{
uordblks += node->size;
@@ -120,6 +124,8 @@ int mallinfo(struct mallinfo *info)
}
}
+ mm_givesemaphore();
+
mvdbg("region=%d node=%p g_heapend=%p\n", region, node, g_heapend[region]);
DEBUGASSERT(node == g_heapend[region]);
uordblks += SIZEOF_MM_ALLOCNODE; /* account for the tail node */