summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-11-10 14:51:33 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-11-10 14:51:33 -0600
commit42fc9811e106b09913d3f8a269b88fa1abf657b5 (patch)
tree975428989407fa3c36e0ec247c8a4638e2389df9
parent09adf63b2a9d364123bff73902472a974dc1b0b2 (diff)
downloadpx4-nuttx-42fc9811e106b09913d3f8a269b88fa1abf657b5.tar.gz
px4-nuttx-42fc9811e106b09913d3f8a269b88fa1abf657b5.tar.bz2
px4-nuttx-42fc9811e106b09913d3f8a269b88fa1abf657b5.zip
I2S simplifed audio buffer queuing
-rw-r--r--nuttx/ChangeLog4
-rw-r--r--nuttx/arch/arm/src/sama5/sam_ssc.c123
-rw-r--r--nuttx/drivers/audio/i2schar.c117
-rw-r--r--nuttx/include/nuttx/audio/i2s.h35
4 files changed, 116 insertions, 163 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index fca89d458..bcb6668f3 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -6027,4 +6027,6 @@
NuttX Kernel build (2013-11-10).
* arch/arm/src/sama5/sam_ssc.c and Kconfig: Add configurable support
for SSC loopback mode (2013-11-10).
-
+ * include/nuttx/audio/i2s.h, arch/arm/src/sama5/sam_ssc.c, and
+ drivers/audio/i2schar.c: Improvied I2S interface design: Simplified
+ audio buffer queuing (2013-11-10).
diff --git a/nuttx/arch/arm/src/sama5/sam_ssc.c b/nuttx/arch/arm/src/sama5/sam_ssc.c
index d244a75f9..9490e7c15 100644
--- a/nuttx/arch/arm/src/sama5/sam_ssc.c
+++ b/nuttx/arch/arm/src/sama5/sam_ssc.c
@@ -242,11 +242,10 @@
struct sam_buffer_s
{
struct sam_buffer_s *flink; /* Supports a singly linked list */
- void *callback; /* Function to call when the transfer completes */
+ i2s_callback_t callback; /* Function to call when the transfer completes */
uint32_t timeout; /* The timeout value to use with DMA transfers */
void *arg; /* The argument to be returned with the callback */
- void *buffer; /* I/O buffer */
- size_t nbytes; /* Number of valid bytes in the buffer */
+ struct ap_buffer_s *apb; /* The audio buffer */
int result; /* The result of the transfer */
};
@@ -399,13 +398,12 @@ static void ssc_txdma_callback(DMA_HANDLE handle, void *arg, int result);
static uint32_t ssc_rxsamplerate(struct i2s_dev_s *dev, uint32_t rate);
static uint32_t ssc_rxdatawidth(struct i2s_dev_s *dev, int bits);
-static int ssc_receive(struct i2s_dev_s *dev, void *buffer,
- size_t nbytes, i2s_rxcallback_t callback, void *arg,
- uint32_t timeout);
+static int ssc_receive(struct i2s_dev_s *dev, struct ap_buffer_s *apb,
+ i2s_callback_t callback, void *arg, uint32_t timeout);
static uint32_t ssc_txsamplerate(struct i2s_dev_s *dev, uint32_t rate);
static uint32_t ssc_txdatawidth(struct i2s_dev_s *dev, int bits);
-static int ssc_send(struct i2s_dev_s *dev, const void *buffer,
- size_t nbytes, i2s_txcallback_t callback, void *arg,
+static int ssc_send(struct i2s_dev_s *dev, struct ap_buffer_s *apb,
+ i2s_callback_t callback, void *arg,
uint32_t timeout);
/* Initialization */
@@ -1013,6 +1011,7 @@ static void ssc_rxdma_timeout(int argc, uint32_t arg)
static int ssc_rxdma_setup(struct sam_ssc_s *priv)
{
struct sam_buffer_s *bfcontainer;
+ struct ap_buffer_s *apb;
uintptr_t paddr;
uintptr_t maddr;
uint32_t timeout;
@@ -1049,17 +1048,21 @@ static int ssc_rxdma_setup(struct sam_ssc_s *priv)
/* Remove the pending RX transfer at the head of the RX pending queue. */
bfcontainer = (struct sam_buffer_s *)sq_remfirst(&priv->rxpend);
+ DEBUGASSERT(bfcontainer && bfcontainer->apb);
+
+ apb = bfcontainer->apb;
+ DEBUGASSERT(((uintptr_t)apb->samp & 3) == 0);
/* Physical address of the SSC RHR register and of the buffer location
* in RAM.
*/
paddr = ssc_physregaddr(priv, SAM_SSC_RHR_OFFSET);
- maddr = sam_physramaddr((uintptr_t)bfcontainer->buffer);
+ maddr = sam_physramaddr((uintptr_t)apb->samp);
/* Configure the RX DMA */
- sam_dmarxsetup(priv->rxdma, paddr, maddr, bfcontainer->nbytes);
+ sam_dmarxsetup(priv->rxdma, paddr, maddr, apb->nmaxbytes);
/* Increment the DMA timeout */
@@ -1075,6 +1078,14 @@ static int ssc_rxdma_setup(struct sam_ssc_s *priv)
/* Add the container to the list of active DMAs */
sq_addlast((sq_entry_t *)bfcontainer, &priv->rxact);
+
+ /* Invalidate the data cache so that nothing gets flush into the
+ * DMA buffer after starting the DMA transfer.
+ */
+
+ cp15_invalidate_dcache((uintptr_t)apb->samp,
+ (uintptr_t)apb->samp + apb->nmaxbytes);
+
}
while (!sq_empty(&priv->rxpend));
@@ -1082,13 +1093,6 @@ static int ssc_rxdma_setup(struct sam_ssc_s *priv)
ssc_rxdma_sample(priv, DMA_AFTER_SETUP);
- /* Invalidate the data cache so that nothing gets flush into the
- * DMA buffer after starting the DMA transfer.
- */
-
- cp15_invalidate_dcache((uintptr_t)bfcontainer->buffer,
- (uintptr_t)bfcontainer->buffer + bfcontainer->nbytes);
-
/* Start the DMA, saving the container as the current active transfer */
sam_dmastart(priv->rxdma, ssc_rxdma_callback, priv);
@@ -1140,7 +1144,6 @@ static void ssc_rx_worker(void *arg)
{
struct sam_ssc_s *priv = (struct sam_ssc_s *)arg;
struct sam_buffer_s *bfcontainer;
- i2s_rxcallback_t callback;
irqstate_t flags;
DEBUGASSERT(priv);
@@ -1203,10 +1206,12 @@ static void ssc_rx_worker(void *arg)
/* Perform the TX transfer done callback */
DEBUGASSERT(bfcontainer && bfcontainer->callback);
+ bfcontainer->callback(&priv->dev, bfcontainer->apb,
+ bfcontainer->arg, bfcontainer->result);
+
+ /* Release our reference on the audio buffer */
- callback = (i2s_rxcallback_t)bfcontainer->callback;
- callback(&priv->dev, bfcontainer->buffer, bfcontainer->nbytes,
- bfcontainer->arg, bfcontainer->result);
+ apb_free(bfcontainer->apb);
/* And release the buffer container */
@@ -1381,6 +1386,7 @@ static void ssc_txdma_timeout(int argc, uint32_t arg)
static int ssc_txdma_setup(struct sam_ssc_s *priv)
{
struct sam_buffer_s *bfcontainer;
+ struct ap_buffer_s *apb;
uintptr_t paddr;
uintptr_t maddr;
uint32_t timeout;
@@ -1417,6 +1423,10 @@ static int ssc_txdma_setup(struct sam_ssc_s *priv)
/* Remove the pending TX transfer at the head of the TX pending queue. */
bfcontainer = (struct sam_buffer_s *)sq_remfirst(&priv->txpend);
+ DEBUGASSERT(bfcontainer && bfcontainer->apb);
+
+ apb = bfcontainer->apb;
+ DEBUGASSERT(((uintptr_t)apb->samp & 3) == 0);
/* Physical address of the SSC THR register and of the buffer location
* in
@@ -1424,11 +1434,11 @@ static int ssc_txdma_setup(struct sam_ssc_s *priv)
*/
paddr = ssc_physregaddr(priv, SAM_SSC_THR_OFFSET);
- maddr = sam_physramaddr((uintptr_t)bfcontainer->buffer);
+ maddr = sam_physramaddr((uintptr_t)apb->samp);
/* Configure the TX DMA */
- sam_dmatxsetup(priv->txdma, paddr, maddr, bfcontainer->nbytes);
+ sam_dmatxsetup(priv->txdma, paddr, maddr, apb->nbytes);
/* Increment the DMA timeout */
@@ -1444,6 +1454,14 @@ static int ssc_txdma_setup(struct sam_ssc_s *priv)
/* Add the container to the list of active DMAs */
sq_addlast((sq_entry_t *)bfcontainer, &priv->txact);
+
+ /* Flush the data cache so that everything is in the physical memory
+ * before starting the DMA.
+ */
+
+ cp15_clean_dcache((uintptr_t)apb->samp,
+ (uintptr_t)apb->samp + apb->nbytes);
+
}
while (!sq_empty(&priv->txpend));
@@ -1451,13 +1469,6 @@ static int ssc_txdma_setup(struct sam_ssc_s *priv)
ssc_txdma_sample(priv, DMA_AFTER_SETUP);
- /* Flush the data cache so that everything is in the physical memory
- * before starting the DMA.
- */
-
- cp15_clean_dcache((uintptr_t)bfcontainer->buffer,
- (uintptr_t)bfcontainer->buffer + bfcontainer->nbytes);
-
/* Start the DMA, saving the container as the current active transfer */
sam_dmastart(priv->txdma, ssc_txdma_callback, priv);
@@ -1509,7 +1520,6 @@ static void ssc_tx_worker(void *arg)
{
struct sam_ssc_s *priv = (struct sam_ssc_s *)arg;
struct sam_buffer_s *bfcontainer;
- i2s_txcallback_t callback;
irqstate_t flags;
DEBUGASSERT(priv);
@@ -1572,10 +1582,12 @@ static void ssc_tx_worker(void *arg)
/* Perform the TX transfer done callback */
DEBUGASSERT(bfcontainer && bfcontainer->callback);
+ bfcontainer->callback(&priv->dev, bfcontainer->apb,
+ bfcontainer->arg, bfcontainer->result);
+
+ /* Release our reference on the audio buffer */
- callback = (i2s_txcallback_t)bfcontainer->callback;
- callback(&priv->dev, bfcontainer->buffer, bfcontainer->nbytes,
- bfcontainer->arg, bfcontainer->result);
+ apb_free(bfcontainer->apb);
/* And release the buffer container */
@@ -1780,9 +1792,7 @@ static uint32_t ssc_rxdatawidth(struct i2s_dev_s *dev, int bits)
*
* Input Parameters:
* dev - Device-specific state data
- * buffer - A pointer to the buffer in which to recieve data
- * nbytes - The length of data that can be received in the buffer in number
- * of bytes.
+ * apb - A pointer to the audio buffer in which to recieve data
* callback - A user provided callback function that will be called at
* the completion of the transfer. The callback will be
* performed in the context of the worker thread.
@@ -1804,18 +1814,17 @@ static uint32_t ssc_rxdatawidth(struct i2s_dev_s *dev, int bits)
*
****************************************************************************/
-static int ssc_receive(struct i2s_dev_s *dev, void *buffer,
- size_t nbytes, i2s_rxcallback_t callback,
- void *arg, uint32_t timeout)
+static int ssc_receive(struct i2s_dev_s *dev, struct ap_buffer_s *apb,
+ i2s_callback_t callback, void *arg, uint32_t timeout)
{
struct sam_ssc_s *priv = (struct sam_ssc_s *)dev;
struct sam_buffer_s *bfcontainer;
irqstate_t flags;
int ret;
- i2svdbg("buffer=%p nbytes=%d\n", buffer, (int)nbytes);
- DEBUGASSERT(priv && buffer && ((uintptr_t)buffer & 3) == 0);
-
+ DEBUGASSERT(priv && apb && ((uintptr_t)apb->samp & 3) == 0);
+ i2svdbg("apb=%p nmaxbytes=%d\n", apb, apb->nmaxbytes);
+
#ifdef SSC_HAVE_RX
/* Allocate a buffer container in advance */
@@ -1835,13 +1844,16 @@ static int ssc_receive(struct i2s_dev_s *dev, void *buffer,
goto errout_with_exclsem;
}
+ /* Add a reference to the audio buffer */
+
+ apb_reference(apb);
+
/* Initialize the buffer container structure */
bfcontainer->callback = (void *)callback;
bfcontainer->timeout = timeout;
bfcontainer->arg = arg;
- bfcontainer->buffer = buffer;
- bfcontainer->nbytes = nbytes;
+ bfcontainer->apb = apb;
bfcontainer->result = -EBUSY;
/* Add the buffer container to the end of the RX pending queue */
@@ -1957,9 +1969,8 @@ static uint32_t ssc_txdatawidth(struct i2s_dev_s *dev, int bits)
* Send a block of data on I2S.
*
* Input Parameters:
- * dev - Device-specific state data
- * buffer - A pointer to the buffer of data to be sent
- * nbytes - the length of data to send from the buffer in number of bytes.
+ * dev - Device-specific state data
+ * apb - A pointer to the audio buffer from which to send data
* callback - A user provided callback function that will be called at
* the completion of the transfer. The callback will be
* performed in the context of the worker thread.
@@ -1981,17 +1992,16 @@ static uint32_t ssc_txdatawidth(struct i2s_dev_s *dev, int bits)
*
****************************************************************************/
-static int ssc_send(struct i2s_dev_s *dev, const void *buffer,
- size_t nbytes, i2s_txcallback_t callback,
- void *arg, uint32_t timeout)
+static int ssc_send(struct i2s_dev_s *dev, struct ap_buffer_s *apb,
+ i2s_callback_t callback, void *arg, uint32_t timeout)
{
struct sam_ssc_s *priv = (struct sam_ssc_s *)dev;
struct sam_buffer_s *bfcontainer;
irqstate_t flags;
int ret;
- i2svdbg("buffer=%p nbytes=%d\n", buffer, (int)nbytes);
- DEBUGASSERT(priv && buffer && ((uintptr_t)buffer & 3) == 0);
+ DEBUGASSERT(priv && apb && ((uintptr_t)apb->samp & 3) == 0);
+ i2svdbg("apb=%p nbytes=%d\n", apb, apb->nbytes);
#ifdef SSC_HAVE_TX
/* Allocate a buffer container in advance */
@@ -2012,13 +2022,16 @@ static int ssc_send(struct i2s_dev_s *dev, const void *buffer,
goto errout_with_exclsem;
}
+ /* Add a reference to the audio buffer */
+
+ apb_reference(apb);
+
/* Initialize the buffer container structure */
bfcontainer->callback = (void *)callback;
bfcontainer->timeout = timeout;
bfcontainer->arg = arg;
- bfcontainer->buffer = (void *)buffer;
- bfcontainer->nbytes = nbytes;
+ bfcontainer->apb = apb;
bfcontainer->result = -EBUSY;
/* Add the buffer container to the end of the TX pending queue */
diff --git a/nuttx/drivers/audio/i2schar.c b/nuttx/drivers/audio/i2schar.c
index 52e945d5b..f7f251d7f 100644
--- a/nuttx/drivers/audio/i2schar.c
+++ b/nuttx/drivers/audio/i2schar.c
@@ -52,7 +52,6 @@
#include <string.h>
#include <debug.h>
#include <errno.h>
-#include <queue.h>
#include <nuttx/kmalloc.h>
#include <nuttx/fs/fs.h>
@@ -100,8 +99,6 @@ struct i2schar_dev_s
{
FAR struct i2s_dev_s *i2s; /* The lower half i2s driver */
sem_t exclsem; /* Assures mutually exclusive access */
- dq_queue_t rxq; /* RX audio buffers awaiting transfer */
- dq_queue_t txq; /* TX audio buffers awaiting transfer */
};
/****************************************************************************
@@ -110,9 +107,9 @@ struct i2schar_dev_s
/* I2S callback function */
static void i2schar_rxcallback(FAR struct i2s_dev_s *dev,
- FAR void *buffer, size_t nbytes, FAR void *arg, int result);
+ FAR struct ap_buffer_s *apb, FAR void *arg, int result);
static void i2schar_txcallback(FAR struct i2s_dev_s *dev,
- FAR const void *buffer, size_t nbytes, FAR void *arg,
+ FAR struct ap_buffer_s *apb, FAR void *arg,
int result);
/* Character driver methods */
@@ -161,47 +158,25 @@ static const struct file_operations i2schar_fops =
****************************************************************************/
static void i2schar_rxcallback(FAR struct i2s_dev_s *dev,
- FAR void *buffer, size_t nbytes,
+ FAR struct ap_buffer_s *apb,
FAR void *arg, int result)
{
FAR struct i2schar_dev_s *priv = (FAR struct i2schar_dev_s *)arg;
- FAR struct ap_buffer_s *apb;
- i2svdbg("buffer=%p nbytes=%d result=%d\n", buffer, (int)nbytes, result);
- DEBUGASSERT(dev && buffer && priv);
+ DEBUGASSERT(priv && apb);
+ i2svdbg("apb=%p nbytes=%d result=%d\n", apb, apb->nbytes, result);
- /* The returned buffer should match the buffer at the head of the RX audio
- * buffer queue.
+ /* REVISIT: If you want this to actually do something other than
+ * test I2S data transfer, then this is the point where you would
+ * want to pass the received I2S to some application.
*/
- apb = (FAR struct ap_buffer_s *)dq_peek(&priv->rxq);
- if ((FAR const void *)apb->samp != buffer)
- {
- i2sdbg("ERROR: apb=%p apb->samp=%p buffer=%p\n",
- apb, apb->samp, buffer);
- }
- else
- {
- if (apb->nmaxbytes != nbytes)
- {
- i2sdbg("ERROR: apb->nmaxbytes=%d nbytes=%d\n",
- (int)apb->nmaxbytes, (int)nbytes);
- }
-
- /* REVISIT: If you want this to actually do something other than
- * test I2S data transfer, then this is the point where you would
- * want to pass the received I2S to some application.
- */
-
- /* Remove the buffer from the beginning of the RX queue and release
- * our reference to it. Hopefully it will be freed now.
- */
-
- (void)dq_remfirst(&priv->rxq);
+ /* Release our reference to the audio buffer. Hopefully it will be freed
+ * now.
+ */
- i2svdbg("Freeing apb=%p crefs=%d\n", apb, apb->crefs);
- apb_free(apb);
- }
+ i2svdbg("Freeing apb=%p crefs=%d\n", apb, apb->crefs);
+ apb_free(apb);
}
/****************************************************************************
@@ -218,47 +193,25 @@ static void i2schar_rxcallback(FAR struct i2s_dev_s *dev,
****************************************************************************/
static void i2schar_txcallback(FAR struct i2s_dev_s *dev,
- FAR const void *buffer, size_t nbytes,
+ FAR struct ap_buffer_s *apb,
FAR void *arg, int result)
{
FAR struct i2schar_dev_s *priv = (FAR struct i2schar_dev_s *)arg;
- FAR struct ap_buffer_s *apb;
- i2svdbg("buffer=%p nbytes=%d result=%d\n", buffer, (int)nbytes, result);
- DEBUGASSERT(dev && buffer && priv);
+ DEBUGASSERT(priv && apb);
+ i2svdbg("apb=%p nbytes=%d result=%d\n", apb, apb->nbytes, result);
- /* The returned buffer should match the buffer at the head of the RX audio
- * buffer queue.
+ /* REVISIT: If you want this to actually do something other than
+ * test I2S data transfer, then this is the point where you would
+ * want to let some application know that the transfer has complete.
*/
- apb = (FAR struct ap_buffer_s *)dq_peek(&priv->txq);
- if ((FAR const void *)apb->samp != buffer)
- {
- i2sdbg("ERROR: apb=%p apb->samp=%p buffer=%p\n",
- apb, apb->samp, buffer);
- }
- else
- {
- if (apb->nmaxbytes != nbytes)
- {
- i2sdbg("ERROR: apb->nmaxbytes=%d nbytes=%d\n",
- (int)apb->nmaxbytes, (int)nbytes);
- }
-
- /* REVISIT: If you want this to actually do something other than
- * test I2S data transfer, then this is the point where you would
- * want to pass the received I2S to some application.
- */
-
- /* Remove the buffer from the beginning of the RX queue and release
- * our reference to it. Hopefully it will be freed now.
- */
-
- (void)dq_remfirst(&priv->txq);
+ /* Release our reference to the audio buffer. Hopefully it will be freed
+ * now.
+ */
- i2svdbg("Freeing apb=%p crefs=%d\n", apb, apb->crefs);
- apb_free(apb);
- }
+ i2svdbg("Freeing apb=%p crefs=%d\n", apb, apb->crefs);
+ apb_free(apb);
}
/****************************************************************************
@@ -298,7 +251,7 @@ static ssize_t i2schar_read(FAR struct file *filep, FAR char *buffer,
nbytes = apb->nmaxbytes;
DEBUGASSERT(buflen >= (sizeof(struct ap_buffer_s) + nbytes));
- /* Add our buffer reference */
+ /* Add a reference to the audio buffer */
apb_reference(apb);
@@ -313,13 +266,9 @@ static ssize_t i2schar_read(FAR struct file *filep, FAR char *buffer,
goto errout_with_reference;
}
- /* Add the audio buffer to the I2S receiver queue */
-
- dq_addlast(&apb->dq_entry, &priv->rxq);
-
- /* And give the buffer to the I2S driver */
+ /* Give the buffer to the I2S driver */
- ret = I2S_RECEIVE(priv->i2s, apb->samp, nbytes, i2schar_rxcallback, priv, 0);
+ ret = I2S_RECEIVE(priv->i2s, apb, i2schar_rxcallback, priv, 0);
if (ret < 0)
{
i2sdbg("ERROR: I2S_RECEIVE returned: %d\n", ret);
@@ -376,7 +325,7 @@ static ssize_t i2schar_write(FAR struct file *filep, FAR const char *buffer,
nbytes = apb->nmaxbytes;
DEBUGASSERT(buflen >= (sizeof(struct ap_buffer_s) + nbytes));
- /* Add our buffer reference */
+ /* Add a reference to the audio buffer */
apb_reference(apb);
@@ -391,13 +340,9 @@ static ssize_t i2schar_write(FAR struct file *filep, FAR const char *buffer,
goto errout_with_reference;
}
- /* Add the audio buffer to the I2S transmitter queue */
-
- dq_addlast(&apb->dq_entry, &priv->txq);
-
- /* And give the buffer to the I2S driver */
+ /* Give the audio buffer to the I2S driver */
- ret = I2S_SEND(priv->i2s, apb->samp, nbytes, i2schar_txcallback, priv, 0);
+ ret = I2S_SEND(priv->i2s, apb, i2schar_txcallback, priv, 0);
if (ret < 0)
{
i2sdbg("ERROR: I2S_SEND returned: %d\n", ret);
@@ -457,8 +402,6 @@ int i2schar_register(FAR struct i2s_dev_s *i2s, int minor)
priv->i2s = i2s;
sem_init(&priv->exclsem, 0, 1);
- dq_init(&priv->rxq);
- dq_init(&priv->txq);
/* Create the character device name */
diff --git a/nuttx/include/nuttx/audio/i2s.h b/nuttx/include/nuttx/audio/i2s.h
index 6318be005..e9addf784 100644
--- a/nuttx/include/nuttx/audio/i2s.h
+++ b/nuttx/include/nuttx/audio/i2s.h
@@ -46,6 +46,8 @@
#include <stdint.h>
#include <stdbool.h>
+#include <nuttx/audio/audio.h>
+
#ifdef CONFIG_I2S
/****************************************************************************
@@ -99,9 +101,7 @@
*
* Input Parameters:
* dev - Device-specific state data
- * buffer - A pointer to the buffer in which to recieve data
- * nbytes - The length of data that can be received in the buffer in number
- * of bytes.
+ * apb - A pointer to the audio buffer in which to recieve data
* callback - A user provided callback function that will be called at
* the completion of the transfer. The callback will be
* performed in the context of the worker thread.
@@ -123,7 +123,7 @@
*
****************************************************************************/
-#define I2S_RECEIVE(d,b,n,c,a,t) ((d)->ops->i2s_receive(d,b,n,c,a,t))
+#define I2S_RECEIVE(d,b,c,a,t) ((d)->ops->i2s_receive(d,b,c,a,t))
/****************************************************************************
* Name: I2S_TXSAMPLERATE
@@ -170,9 +170,8 @@
* Send a block of data on I2S.
*
* Input Parameters:
- * dev - Device-specific state data
- * buffer - A pointer to the buffer of data to be sent
- * nbytes - the length of data to send from the buffer in number of bytes.
+ * dev - Device-specific state data
+ * apb - A pointer to the audio buffer from which to send data
* callback - A user provided callback function that will be called at
* the completion of the transfer. The callback will be
* performed in the context of the worker thread.
@@ -194,7 +193,7 @@
*
****************************************************************************/
-#define I2S_SEND(d,b,n,c,a,t) ((d)->ops->i2s_send(d,b,n,c,a,t))
+#define I2S_SEND(d,b,c,a,t) ((d)->ops->i2s_send(d,b,c,a,t))
/****************************************************************************
* Public Types
@@ -202,12 +201,8 @@
/* Transfer complete callbacks */
struct i2s_dev_s;
-typedef CODE void (*i2s_rxcallback_t)(FAR struct i2s_dev_s *dev,
- FAR void *buffer, size_t nbytes, FAR void *arg,
- int result);
-typedef CODE void (*i2s_txcallback_t)(FAR struct i2s_dev_s *dev,
- FAR const void *buffer, size_t nbytes, FAR void *arg,
- int result);
+typedef CODE void (*i2s_callback_t)(FAR struct i2s_dev_s *dev,
+ FAR struct ap_buffer_s *apb, FAR void *arg, int result);
/* The I2S vtable */
@@ -217,17 +212,17 @@ struct i2s_ops_s
CODE uint32_t (*i2s_rxsamplerate)(FAR struct i2s_dev_s *dev, uint32_t rate);
CODE uint32_t (*i2s_rxdatawidth)(FAR struct i2s_dev_s *dev, int bits);
- CODE int (*i2s_receive)(FAR struct i2s_dev_s *dev, FAR void *buffer,
- size_t nbytes, i2s_rxcallback_t callback, FAR void *arg,
- uint32_t timeout);
+ CODE int (*i2s_receive)(FAR struct i2s_dev_s *dev,
+ FAR struct ap_buffer_s *apb, i2s_callback_t callback,
+ FAR void *arg, uint32_t timeout);
/* Transmitter methods */
CODE uint32_t (*i2s_txsamplerate)(FAR struct i2s_dev_s *dev, uint32_t rate);
CODE uint32_t (*i2s_txdatawidth)(FAR struct i2s_dev_s *dev, int bits);
- CODE int (*i2s_send)(FAR struct i2s_dev_s *dev, FAR const void *buffer,
- size_t nbytes, i2s_txcallback_t callback, FAR void *arg,
- uint32_t timeout);
+ CODE int (*i2s_send)(FAR struct i2s_dev_s *dev,
+ FAR struct ap_buffer_s *apb, i2s_callback_t callback,
+ FAR void *arg, uint32_t timeout);
};
/* I2S private data. This structure only defines the initial fields of the