summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-11-11 15:18:57 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-11-11 15:18:57 -0600
commitb83fdc6a4c19a6e99c0ce10b98db5374519d5e79 (patch)
tree8e907ba687465a76995465aaea5b420973b16734 /nuttx
parent35805fc983f9cd16b745f4326582e2f936e74cc5 (diff)
downloadpx4-nuttx-b83fdc6a4c19a6e99c0ce10b98db5374519d5e79.tar.gz
px4-nuttx-b83fdc6a4c19a6e99c0ce10b98db5374519d5e79.tar.bz2
px4-nuttx-b83fdc6a4c19a6e99c0ce10b98db5374519d5e79.zip
Various fixes from initial attempts to integrate the SAMA5 SSC/I2C driver with the I2C character driver loopback test
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog3
-rw-r--r--nuttx/arch/arm/src/sama5/sam_ssc.c52
-rw-r--r--nuttx/drivers/audio/i2schar.c12
-rw-r--r--nuttx/include/nuttx/audio/i2s.h25
4 files changed, 63 insertions, 29 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 67a06cb00..f7f35ca71 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -6036,3 +6036,6 @@
(2013-11-11).
* arch/arm/src/stm32: Added header files and driver framework for the
STM32F429 LTDC framebuffer driver. From Ken Pettit (2013-11-11).
+ * configs/sama5d3x-ek/src/sam_i2schar.c: Add support for the
+ apps/examples/i2schar test (2011-11-11).
+
diff --git a/nuttx/arch/arm/src/sama5/sam_ssc.c b/nuttx/arch/arm/src/sama5/sam_ssc.c
index 9d40f0558..77e4fe63c 100644
--- a/nuttx/arch/arm/src/sama5/sam_ssc.c
+++ b/nuttx/arch/arm/src/sama5/sam_ssc.c
@@ -254,7 +254,7 @@ struct sam_buffer_s
struct sam_ssc_s
{
struct i2s_dev_s dev; /* Externally visible I2S interface */
- uint32_t base; /* SSC controller register base address */
+ uintptr_t base; /* SSC controller register base address */
sem_t exclsem; /* Assures mutually exclusive acess to SSC */
uint16_t master:1; /* True: Master mode transfers */
uint16_t rx:1; /* True: RX transfers supported */
@@ -319,15 +319,15 @@ struct sam_ssc_s
/* Register helpers */
#ifdef CONFIG_SAMA5_SSC_REGDEBUG
-static bool ssc_checkreg(struct sam_ssc_s *priv, bool wr, uint32_t value,
- uint32_t address);
+static bool ssc_checkreg(struct sam_ssc_s *priv, bool wr, uint32_t regval,
+ uint32_t regaddr);
#else
-# define ssc_checkreg(priv,wr,value,address) (false)
+# define ssc_checkreg(priv,wr,regval,regaddr) (false)
#endif
static inline uint32_t ssc_getreg(struct sam_ssc_s *priv, unsigned int offset);
-static inline void ssc_putreg(struct sam_ssc_s *priv, uint32_t value,
- unsigned int offset);
+static inline void ssc_putreg(struct sam_ssc_s *priv, unsigned int offset,
+ uint32_t regval);
static inline uintptr_t ssc_physregaddr(struct sam_ssc_s *priv,
unsigned int offset);
@@ -459,8 +459,8 @@ static const struct i2s_ops_s g_sscops =
* Check if the current register access is a duplicate of the preceding.
*
* Input Parameters:
- * value - The value to be written
- * address - The address of the register to write to
+ * regval - The value to be written
+ * regaddr - The address of the register to write to
*
* Returned Value:
* true: This is the first register access of this type.
@@ -469,12 +469,12 @@ static const struct i2s_ops_s g_sscops =
****************************************************************************/
#ifdef CONFIG_SAMA5_SSC_REGDEBUG
-static bool ssc_checkreg(struct sam_ssc_s *priv, bool wr, uint32_t value,
- uint32_t address)
+static bool ssc_checkreg(struct sam_ssc_s *priv, bool wr, uint32_t regval,
+ uint32_t regaddr)
{
if (wr == priv->wr && /* Same kind of access? */
- value == priv->regval && /* Same value? */
- address == priv->regaddr) /* Same address? */
+ regval == priv->regval && /* Same value? */
+ regaddr == priv->regaddr) /* Same address? */
{
/* Yes, then just keep a count of the number of times we did this. */
@@ -495,9 +495,9 @@ static bool ssc_checkreg(struct sam_ssc_s *priv, bool wr, uint32_t value,
/* Save information about the new access */
priv->wr = wr;
- priv->regval = value;
- priv->regaddr = address;
- priv->count = 0;
+ priv->regval = regval;
+ priv->regaddr = regaddr;
+ priv->count = 0;
}
/* Return true if this is the first time that we have done this operation */
@@ -517,17 +517,17 @@ static bool ssc_checkreg(struct sam_ssc_s *priv, bool wr, uint32_t value,
static inline uint32_t ssc_getreg(struct sam_ssc_s *priv,
unsigned int offset)
{
- uint32_t address = priv->base + offset;
- uint32_t value = getreg32(address);
+ uint32_t regaddr = priv->base + offset;
+ uint32_t regval = getreg32(regaddr);
#ifdef CONFIG_SAMA5_SSC_REGDEBUG
- if (ssc_checkreg(priv, false, value, address))
+ if (ssc_checkreg(priv, false, regval, regaddr))
{
- lldbg("%08x->%08x\n", address, value);
+ lldbg("%08x->%08x\n", regaddr, regval);
}
#endif
- return value;
+ return regval;
}
/****************************************************************************
@@ -538,19 +538,19 @@ static inline uint32_t ssc_getreg(struct sam_ssc_s *priv,
*
****************************************************************************/
-static inline void ssc_putreg(struct sam_ssc_s *priv, uint32_t value,
- unsigned int offset)
+static inline void ssc_putreg(struct sam_ssc_s *priv, unsigned int offset,
+ uint32_t regval)
{
- uint32_t address = priv->base + offset;
+ uint32_t regaddr = priv->base + offset;
#ifdef CONFIG_SAMA5_SSC_REGDEBUG
- if (ssc_checkreg(priv, true, value, address))
+ if (ssc_checkreg(priv, true, regval, regaddr))
{
- lldbg("%08x<-%08x\n", address, value);
+ lldbg("%08x<-%08x\n", regaddr, regval);
}
#endif
- putreg32(value, address);
+ putreg32(regval, regaddr);
}
/****************************************************************************
diff --git a/nuttx/drivers/audio/i2schar.c b/nuttx/drivers/audio/i2schar.c
index f7f251d7f..e3f6986b1 100644
--- a/nuttx/drivers/audio/i2schar.c
+++ b/nuttx/drivers/audio/i2schar.c
@@ -280,7 +280,7 @@ static ssize_t i2schar_read(FAR struct file *filep, FAR char *buffer,
*/
sem_post(&priv->exclsem);
- return nbytes;
+ return sizeof(struct ap_buffer_s) + nbytes;
errout_with_reference:
apb_free(apb);
@@ -354,7 +354,7 @@ static ssize_t i2schar_write(FAR struct file *filep, FAR const char *buffer,
*/
sem_post(&priv->exclsem);
- return nbytes;
+ return sizeof(struct ap_buffer_s) + nbytes;
errout_with_reference:
apb_free(apb);
@@ -370,7 +370,13 @@ errout_with_reference:
* Name: i2schar_register
*
* Description:
- * Create and register the i2s character driver.
+ * Create and register the I2S character driver.
+ *
+ * The I2S character driver is a simple character driver that supports I2S
+ * transfers via a read() and write(). The intent of this driver is to
+ * support I2S testing. It is not an audio driver but does conform to some
+ * of the buffer management heuristics of an audio driver. It is not
+ * suitable for use in any real driver application in its current form.
*
* Input Parameters:
* i2s - An instance of the lower half I2S driver
diff --git a/nuttx/include/nuttx/audio/i2s.h b/nuttx/include/nuttx/audio/i2s.h
index e9addf784..ecf42f199 100644
--- a/nuttx/include/nuttx/audio/i2s.h
+++ b/nuttx/include/nuttx/audio/i2s.h
@@ -252,6 +252,31 @@ extern "C"
* Public Functions
****************************************************************************/
+/****************************************************************************
+ * Name: i2schar_register
+ *
+ * Description:
+ * Create and register the I2S character driver.
+ *
+ * The I2S character driver is a simple character driver that supports I2S
+ * transfers via a read() and write(). The intent of this driver is to
+ * support I2S testing. It is not an audio driver but does conform to some
+ * of the buffer management heuristics of an audio driver. It is not
+ * suitable for use in any real driver application in its current form.
+ *
+ * Input Parameters:
+ * i2s - An instance of the lower half I2S driver
+ * minor - The device minor number. The I2S character device will be
+ * registers as /dev/i2scharN where N is the minor number
+ *
+ * Returned Value:
+ * OK if the driver was successfully register; A negated errno value is
+ * returned on any failure.
+ *
+ ****************************************************************************/
+
+int i2schar_register(FAR struct i2s_dev_s *i2s, int minor);
+
#undef EXTERN
#if defined(__cplusplus)
}