summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-10-07 22:37:24 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-10-07 22:37:24 +0000
commit77fac8557262940319c3fa3bc473866d4bb90450 (patch)
treef6a1df9d8409cbb2e66bacb04f7aaeb344800d3a /nuttx
parent3ae6dd3bf850269d0b55c842d463d028071cd496 (diff)
downloadpx4-nuttx-77fac8557262940319c3fa3bc473866d4bb90450.tar.gz
px4-nuttx-77fac8557262940319c3fa3bc473866d4bb90450.tar.bz2
px4-nuttx-77fac8557262940319c3fa3bc473866d4bb90450.zip
SAM3U SPI debug changes
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4031 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/sam3u/sam3u_spi.c57
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_i2c.h2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_i2c.c4
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_spi.c2
-rwxr-xr-xnuttx/configs/sam3u-ek/include/board.h2
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_lcd.c2
-rw-r--r--nuttx/drivers/input/ads7843e.c12
-rw-r--r--nuttx/drivers/input/ads7843e.h6
-rw-r--r--nuttx/drivers/input/tsc2007.c2
-rw-r--r--nuttx/include/nuttx/input/ads7843e.h6
10 files changed, 61 insertions, 34 deletions
diff --git a/nuttx/arch/arm/src/sam3u/sam3u_spi.c b/nuttx/arch/arm/src/sam3u/sam3u_spi.c
index 753f02355..fb83e9312 100644
--- a/nuttx/arch/arm/src/sam3u/sam3u_spi.c
+++ b/nuttx/arch/arm/src/sam3u/sam3u_spi.c
@@ -125,7 +125,9 @@ static void spi_dumpregs(FAR const char *msg);
#else
# define spi_dumpregs(msg)
#endif
+
static inline void spi_flush(void);
+static inline uint32_t spi_cs2pcs(FAR struct sam3u_spidev_s *priv);
/* SPI methods */
@@ -222,7 +224,7 @@ static void spi_dumpregs(FAR const char *msg)
spivdbg(" CSR0:%08x CSR1:%08x CSR2:%08x CSR3:%08x\n",
getreg32(SAM3U_SPI_CSR0), getreg32(SAM3U_SPI_CSR1),
getreg32(SAM3U_SPI_CSR2), getreg32(SAM3U_SPI_CSR3));
- spivdbg(" WPCR:%08x WPSR:%08x IMR:%08x\n",
+ spivdbg(" WPCR:%08x WPSR:%08x\n",
getreg32(SAM3U_SPI_WPCR), getreg32(SAM3U_SPI_WPSR));
}
#endif
@@ -258,6 +260,37 @@ static inline void spi_flush(void)
}
/****************************************************************************
+ * Name: spi_cs2pcs
+ *
+ * Description:
+ * Map the chip select number to the bit-set PCS field used in the SPI
+ * registers. A chip select number is used for indexing and identifying
+ * chip selects. However, the chip select information is represented by
+ * a bit set in the SPI regsisters. This function maps those chip select
+ * numbers to the correct bit set:
+ *
+ * CS Returned Spec Effective
+ * No. PCS Value NPCS
+ * ---- -------- -------- --------
+ * 0 0000 xxx0 1110
+ * 1 0001 xx01 1101
+ * 2 0011 x011 1011
+ * 3 0111 0111 0111
+ *
+ * Input Parameters:
+ * priv - Device-specific state data
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static inline uint32_t spi_cs2pcs(FAR struct sam3u_spidev_s *priv)
+{
+ return ((uint32_t)1 << (priv->cs)) - 1;
+}
+
+/****************************************************************************
* Name: spi_lock
*
* Description:
@@ -346,9 +379,9 @@ static int spi_lock(FAR struct spi_dev_s *dev, bool lock)
* in order to select a slave.
*/
- regval = getreg32(SAM3U_SPI_MR);
+ regval = getreg32(SAM3U_SPI_MR);
regval &= ~SPI_MR_PCS_MASK;
- regval |= (priv->cs << SPI_MR_PCS_SHIFT);
+ regval |= (spi_cs2pcs(priv) << SPI_MR_PCS_SHIFT);
putreg32(regval, SAM3U_SPI_MR);
}
else
@@ -660,16 +693,18 @@ static void spi_exchange(FAR struct spi_dev_s *dev,
FAR const void *txbuffer, FAR void *rxbuffer,
size_t nwords)
{
-#ifdef CONFIG_SPI_VARSELECT
FAR struct sam3u_spidev_s *priv = (FAR struct sam3u_spidev_s *)dev;
- uint32_t tdr = (uint32_t)priv->cs << SPI_TDR_PCS_SHIFT;
-#endif
FAR uint8_t *rxptr = (FAR uint8_t*)rxbuffer;
FAR uint8_t *txptr = (FAR uint8_t*)txbuffer;
+ uint32_t pcs;
uint32_t data;
spivdbg("txbuffer=%p rxbuffer=%p nwords=%d\n", txbuffer, rxbuffer, nwords);
+ /* Set up PCS bits */
+
+ pcs = spi_cs2pcs(priv) << SPI_TDR_PCS_SHIFT;
+
/* Make sure that any previous transfer is flushed from the hardware */
spi_flush();
@@ -718,13 +753,13 @@ static void spi_exchange(FAR struct spi_dev_s *dev,
data = 0xffff;
}
- /* Set the chip select in the value written to the TDR */
+ /* Set the PCS field in the value written to the TDR */
-#ifdef CONFIG_SPI_VARSELECT
- data |= tdr;
+ data |= pcs;
/* Do we need to set the LASTXFER bit in the TDR value too? */
+#ifdef CONFIG_SPI_VARSELECT
if (nwords == 1)
{
data |= SPI_TDR_LASTXFER;
@@ -734,7 +769,7 @@ static void spi_exchange(FAR struct spi_dev_s *dev,
/* Wait for any previous data written to the TDR to be transferred
* to the serializer.
*/
-
+
while ((getreg32(SAM3U_SPI_SR) & SPI_INT_TDRE) == 0);
/* Write the data to transmitted to the Transmit Data Register (TDR) */
@@ -750,7 +785,7 @@ static void spi_exchange(FAR struct spi_dev_s *dev,
data = getreg32(SAM3U_SPI_RDR);
if (rxptr)
{
- *txptr++ = (uint8_t)data;
+ *rxptr++ = (uint8_t)data;
}
}
}
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_i2c.h b/nuttx/arch/arm/src/stm32/chip/stm32_i2c.h
index b637dc507..e53482b9d 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_i2c.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_i2c.h
@@ -2,7 +2,7 @@
* arch/arm/src/stm32/chip/stm32_i2c.h
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/arch/arm/src/stm32/stm32_i2c.c b/nuttx/arch/arm/src/stm32/stm32_i2c.c
index 94e9b7b88..a5aaa97b9 100644
--- a/nuttx/arch/arm/src/stm32/stm32_i2c.c
+++ b/nuttx/arch/arm/src/stm32/stm32_i2c.c
@@ -991,8 +991,8 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv)
/* \todo Finish 10-bit mode addressing */
}
- /* Was address sent, continue with ether sending or reading data */
-
+ /* Was address sent, continue with either sending or reading data */
+
else if ((priv->flags & I2C_M_READ) == 0 && (status & (I2C_SR1_ADDR | I2C_SR1_TXE)) != 0)
{
stm32_i3c_traceevent(priv, I2CEVENT_READ, priv->dcnt);
diff --git a/nuttx/arch/arm/src/stm32/stm32_spi.c b/nuttx/arch/arm/src/stm32/stm32_spi.c
index b4ba555af..abc641b49 100644
--- a/nuttx/arch/arm/src/stm32/stm32_spi.c
+++ b/nuttx/arch/arm/src/stm32/stm32_spi.c
@@ -2,7 +2,7 @@
* arm/arm/src/stm32/stm32_spi.c
*
* Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/configs/sam3u-ek/include/board.h b/nuttx/configs/sam3u-ek/include/board.h
index 7721d0f88..01817c784 100755
--- a/nuttx/configs/sam3u-ek/include/board.h
+++ b/nuttx/configs/sam3u-ek/include/board.h
@@ -3,7 +3,7 @@
* include/arch/board/board.h
*
* Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/configs/stm3210e-eval/src/up_lcd.c b/nuttx/configs/stm3210e-eval/src/up_lcd.c
index ebe478a86..9ba5e6f12 100644
--- a/nuttx/configs/stm3210e-eval/src/up_lcd.c
+++ b/nuttx/configs/stm3210e-eval/src/up_lcd.c
@@ -3,7 +3,7 @@
* arch/arm/src/board/up_lcd.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/drivers/input/ads7843e.c b/nuttx/drivers/input/ads7843e.c
index 16842f4cf..1e04de37c 100644
--- a/nuttx/drivers/input/ads7843e.c
+++ b/nuttx/drivers/input/ads7843e.c
@@ -192,9 +192,7 @@ static void ads7843e_select(FAR struct spi_dev_s *spi)
SPI_SETMODE(spi, CONFIG_ADS7843E_SPIMODE);
SPI_SETBITS(spi, 8);
-#ifdef CONFIG_ADS7843E_FREQUENCY
SPI_SETFREQUENCY(spi, CONFIG_ADS7843E_FREQUENCY);
-#endif
}
#endif
@@ -256,12 +254,8 @@ static void ads7843e_deselect(FAR struct spi_dev_s *spi)
static inline void ads7843e_configspi(FAR struct spi_dev_s *spi)
{
-#ifdef CONFIG_ADS7843E_FREQUENCY
idbg("Mode: %d Bits: 8 Frequency: %d\n",
CONFIG_ADS7843E_SPIMODE, CONFIG_ADS7843E_FREQUENCY);
-#else
- idbg("Mode: %d Bits: 8\n", CONFIG_ADS7843E_SPIMODE);
-#endif
/* Configure SPI for the P14201. But only if we own the SPI bus. Otherwise, don't
* bother because it might change.
@@ -271,9 +265,7 @@ static inline void ads7843e_configspi(FAR struct spi_dev_s *spi)
SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, true);
SPI_SETMODE(spi, CONFIG_ADS7843E_SPIMODE);
SPI_SETBITS(spi, 8);
-#ifdef CONFIG_ADS7843E_FREQUENCY
SPI_SETFREQUENCY(spi, CONFIG_ADS7843E_FREQUENCY)
-#endif
SPI_SELECT(spi, SPIDEV_TOUCHSCREEN, false);
#endif
}
@@ -1110,10 +1102,6 @@ int ads7843e_register(FAR struct spi_dev_s *dev,
sem_init(&priv->devsem, 0, 1); /* Initialize device structure semaphore */
sem_init(&priv->waitsem, 0, 0); /* Initialize pen event wait semaphore */
- /* Set the SPI frequency (saving the actual frequency) */
-
- config->frequency = SPI_SETFREQUENCY(dev, config->frequency);
-
/* Make sure that interrupts are disabled */
config->clear(config);
diff --git a/nuttx/drivers/input/ads7843e.h b/nuttx/drivers/input/ads7843e.h
index 17671aefd..edf205c61 100644
--- a/nuttx/drivers/input/ads7843e.h
+++ b/nuttx/drivers/input/ads7843e.h
@@ -2,7 +2,7 @@
* drivers/input/ads7843e.h
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* References:
* "Touch Screen Controller, ADS7843," Burr-Brown Products from Texas
@@ -60,9 +60,7 @@
* Pre-Processor Definitions
********************************************************************************************/
/* Configuration ****************************************************************************/
-/* Reference counting is partially implemented, but not needed in the
- * current design.
- */
+/* Reference counting is partially implemented, but not needed in the current design. */
#undef CONFIG_ADS7843E_REFCNT
diff --git a/nuttx/drivers/input/tsc2007.c b/nuttx/drivers/input/tsc2007.c
index 61b48fbd4..12f3dc9c3 100644
--- a/nuttx/drivers/input/tsc2007.c
+++ b/nuttx/drivers/input/tsc2007.c
@@ -445,7 +445,7 @@ static int tsc2007_transfer(FAR struct tsc2007_dev_s *priv, uint8_t cmd)
msg.addr = priv->config->address; /* 7-bit address */
msg.flags = I2C_M_READ; /* Read transaction, beginning with START */
- msg.buffer = data12; /* Transfer two this address */
+ msg.buffer = data12; /* Transfer to this address */
msg.length = 2; /* Read two bytes following the address */
ret = I2C_TRANSFER(priv->i2c, &msg, 1);
diff --git a/nuttx/include/nuttx/input/ads7843e.h b/nuttx/include/nuttx/input/ads7843e.h
index 6b8ef1f9d..09bec3d6b 100644
--- a/nuttx/include/nuttx/input/ads7843e.h
+++ b/nuttx/include/nuttx/input/ads7843e.h
@@ -54,6 +54,12 @@
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
+/* SPI Frequency. Default: 100KHz */
+
+#ifndef CONFIG_ADS7843E_FREQUENCY
+# define CONFIG_ADS7843E_FREQUENCY 100000
+#endif
+
/* Maximum number of threads than can be waiting for POLL events */
#ifndef CONFIG_ADS7843E_NPOLLWAITERS