summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--apps/system/nxplayer/nxplayer.c23
-rw-r--r--nuttx/drivers/audio/audio_null.c16
-rw-r--r--nuttx/drivers/audio/vs1053.c124
-rw-r--r--nuttx/drivers/audio/wm8904.c70
-rw-r--r--nuttx/include/nuttx/audio/audio.h7
-rw-r--r--nuttx/libc/audio/lib_buffer.c22
6 files changed, 174 insertions, 88 deletions
diff --git a/apps/system/nxplayer/nxplayer.c b/apps/system/nxplayer/nxplayer.c
index d3c2366a3..49d015de6 100644
--- a/apps/system/nxplayer/nxplayer.c
+++ b/apps/system/nxplayer/nxplayer.c
@@ -489,7 +489,7 @@ static int nxplayer_mediasearch(FAR struct nxplayer_s *pPlayer,
****************************************************************************/
static int nxplayer_enqueuebuffer(FAR struct nxplayer_s *pPlayer,
- FAR struct ap_buffer_s* pBuf)
+ FAR struct ap_buffer_s* apb)
{
struct audio_buf_desc_s bufdesc;
int ret;
@@ -510,10 +510,11 @@ static int nxplayer_enqueuebuffer(FAR struct nxplayer_s *pPlayer,
/* Read data into the buffer. */
- pBuf->nbytes = fread(&pBuf->samp, 1, pBuf->nmaxbytes, pPlayer->fileFd);
- pBuf->curbyte = 0;
+ apb->nbytes = fread(&apb->samp, 1, apb->nmaxbytes, pPlayer->fileFd);
+ apb->curbyte = 0;
+ apb->flags = 0;
- if (pBuf->nbytes < pBuf->nmaxbytes)
+ if (apb->nbytes < apb->nmaxbytes)
{
int errcode = errno;
int readerror = ferror(pPlayer->fileFd);
@@ -523,14 +524,18 @@ static int nxplayer_enqueuebuffer(FAR struct nxplayer_s *pPlayer,
*/
audvdbg("Closing audio file, nbytes=%d readerr=%d\n",
- pBuf->nbytes, readerror);
+ apb->nbytes, readerror);
fclose(pPlayer->fileFd);
pPlayer->fileFd = NULL;
+ /* Set a flag to indicate that this is the final buffer in the stream */
+
+ apb->flags |= AUDIO_APB_FINAL;
+
/* Was this a file read error */
- if (pBuf->nbytes == 0 && readerror)
+ if (apb->nbytes == 0 && readerror)
{
DEBUGASSERT(errcode > 0);
@@ -541,7 +546,7 @@ static int nxplayer_enqueuebuffer(FAR struct nxplayer_s *pPlayer,
/* Do nothing more if this was the end-of-file with nothing read */
- if (pBuf->nbytes > 0)
+ if (apb->nbytes > 0)
{
/* Now enqueue the buffer with the audio device. If the number of
* bytes in the file happens to be an exact multiple of the audio
@@ -553,8 +558,8 @@ static int nxplayer_enqueuebuffer(FAR struct nxplayer_s *pPlayer,
#ifdef CONFIG_AUDIO_MULTI_SESSION
bufdesc.session = pPlayer->session;
#endif
- bufdesc.numbytes = pBuf->nbytes;
- bufdesc.u.pBuffer = pBuf;
+ bufdesc.numbytes = apb->nbytes;
+ bufdesc.u.pBuffer = apb;
ret = ioctl(pPlayer->devFd, AUDIOIOC_ENQUEUEBUFFER,
(unsigned long)&bufdesc);
diff --git a/nuttx/drivers/audio/audio_null.c b/nuttx/drivers/audio/audio_null.c
index e753f5171..4ebb0042f 100644
--- a/nuttx/drivers/audio/audio_null.c
+++ b/nuttx/drivers/audio/audio_null.c
@@ -650,6 +650,7 @@ static int null_enqueuebuffer(FAR struct audio_lowerhalf_s *dev,
FAR struct ap_buffer_s *apb)
{
FAR struct null_dev_s *priv = (FAR struct null_dev_s *)dev;
+ bool final;
audvdbg("apb=%p curbyte=%d nbytes=%d\n", apb, apb->curbyte, apb->nbytes);
@@ -657,6 +658,10 @@ static int null_enqueuebuffer(FAR struct audio_lowerhalf_s *dev,
apb->curbyte = apb->nbytes;
+ /* Check if this was the last buffer in the stream */
+
+ done = ((apb->flags & AUDIO_APB_FINAL) != 0);
+
/* And return the buffer to the upper level */
DEBUGASSERT(priv && apb && priv->dev.upper);
@@ -671,6 +676,17 @@ static int null_enqueuebuffer(FAR struct audio_lowerhalf_s *dev,
priv->dev.upper(priv->dev.priv, AUDIO_CALLBACK_DEQUEUE, apb, OK);
#endif
+ /* Say we are done playing if this was the last buffer in the stream */
+
+ if (done)
+ {
+#ifdef CONFIG_AUDIO_MULTI_SESSION
+ priv->dev.upper(priv->dev.priv, AUDIO_CALLBACK_COMPLETE, NULL, OK, NULL);
+#else
+ priv->dev.upper(priv->dev.priv, AUDIO_CALLBACK_COMPLETE, NULL, OK);
+#endif
+ }
+
audvdbg("Return OK\n");
return OK;
}
diff --git a/nuttx/drivers/audio/vs1053.c b/nuttx/drivers/audio/vs1053.c
index 734c884ae..102fa4e65 100644
--- a/nuttx/drivers/audio/vs1053.c
+++ b/nuttx/drivers/audio/vs1053.c
@@ -43,7 +43,9 @@
#include <sys/types.h>
#include <sys/ioctl.h>
+
#include <stdint.h>
+#include <stdbool.h>
#include <stdio.h>
#include <fcntl.h>
#include <string.h>
@@ -111,7 +113,7 @@ struct vs1053_struct_s
const FAR struct vs1053_lower_s *hw_lower;/* Pointer to the hardware lower functions */
FAR struct spi_dev_s *spi; /* Pointer to the SPI bus */
- FAR struct ap_buffer_s *pBuf; /* Pointer to the buffer we are processing */
+ FAR struct ap_buffer_s *apb; /* Pointer to the buffer we are processing */
struct dq_queue_s apbq; /* Our queue for enqueued buffers */
unsigned long spi_freq; /* Frequency to run the SPI bus at. */
unsigned long chip_freq; /* Current chip frequency */
@@ -131,13 +133,13 @@ struct vs1053_struct_s
#endif
uint16_t endfillbytes;
uint8_t endfillchar; /* Fill char to send when no more data */
- uint8_t running;
- uint8_t paused;
- uint8_t endmode;
+ bool running;
+ bool paused;
+ bool endmode;
#ifndef CONFIG_AUDIO_EXCLUDE_STOP
- uint8_t cancelmode;
+ bool cancelmode;
#endif
- uint8_t busy; /* Set true when device reserved */
+ bool busy; /* Set true when device reserved */
};
/****************************************************************************
@@ -511,7 +513,7 @@ static void vs1053_setvolume(FAR struct vs1053_struct_s *dev)
leftreg = vs1053_logapprox(leftlevel / 10);
rightreg = vs1053_logapprox(rightlevel / 10);
- /* Lock the SPI bus to get exclsive access to the chip. */
+ /* Lock the SPI bus to get exclusive access to the chip. */
vs1053_spi_lock(spi, dev->spi_freq);
vs1053_writereg(dev, VS1053_SCI_VOL, (leftreg << 8) | rightreg);
@@ -941,7 +943,7 @@ static void vs1053_feeddata(FAR struct vs1053_struct_s *dev)
int ret;
uint8_t *pSamp = NULL;
uint16_t reg;
- struct ap_buffer_s *pBuf;
+ struct ap_buffer_s *apb;
FAR struct spi_dev_s *spi = dev->spi;
/* Check for false interrupt caused by an SCI transaction */
@@ -960,14 +962,14 @@ static void vs1053_feeddata(FAR struct vs1053_struct_s *dev)
/* Local stack copy of our active buffer */
- pBuf = dev->pBuf;
- //auddbg("Entry pBuf=%p, Bytes left=%d\n", pBuf, pBuf->nbytes - pBuf->curbyte);
+ apb = dev->apb;
+ //auddbg("Entry apb=%p, Bytes left=%d\n", apb, apb->nbytes - apb->curbyte);
/* Setup pointer to the next sample in the buffer */
- if (pBuf)
+ if (apb)
{
- pSamp = &pBuf->samp[pBuf->curbyte];
+ pSamp = &apb->samp[apb->curbyte];
}
else if (!dev->endmode)
{
@@ -1018,14 +1020,14 @@ static void vs1053_feeddata(FAR struct vs1053_struct_s *dev)
/* Do a hard reset and terminate */
vs1053_hardreset(dev);
- dev->running = FALSE;
- dev->endmode = FALSE;
+ dev->running = false;
+ dev->endmode = false;
break;
}
else if (dev->endfillbytes > 32*65)
{
/* After each 32 byte of endfillchar, check the status
- * register to see if SM_CANCEL has been cleard. If
+ * register to see if SM_CANCEL has been cleared. If
* it has been cleared, then we're done.
*/
@@ -1041,8 +1043,9 @@ static void vs1053_feeddata(FAR struct vs1053_struct_s *dev)
auddbg("EndFillChar: 0x%0X\n", dev->endfillchar);
reg = vs1053_readreg(dev, VS1053_SCI_MODE);
vs1053_writereg(dev, VS1053_SCI_MODE, reg | VS1053_SM_RESET);
- dev->running = FALSE;
- dev->endmode = FALSE;
+
+ dev->running = false;
+ dev->endmode = false;
break;
}
}
@@ -1055,7 +1058,7 @@ static void vs1053_feeddata(FAR struct vs1053_struct_s *dev)
* will recheck the DREQ line again.
*/
- bytecount = pBuf->nbytes - pBuf->curbyte;
+ bytecount = apb->nbytes - apb->curbyte;
if (bytecount > 32)
{
bytecount = 32;
@@ -1073,7 +1076,7 @@ static void vs1053_feeddata(FAR struct vs1053_struct_s *dev)
pSamp++;
}
#endif
- pBuf->curbyte += bytecount;
+ apb->curbyte += bytecount;
/* Test if we are in cancel mode. If we are, then we need
* to continue sending file data and check for the SM_CANCEL
@@ -1097,16 +1100,19 @@ static void vs1053_feeddata(FAR struct vs1053_struct_s *dev)
{
/* Cancel has begun. Switch to endmode */
- pBuf->curbyte = pBuf->nbytes = 0;
+ apb->nbytes = 0;
+ apb->curbyte = 0;
}
}
#endif /* CONFIG_AUDIO_EXCLUDE_STOP */
/* Test if we are at the end of the buffer */
- if (pBuf->curbyte >= pBuf->nbytes)
+ if (apb->curbyte >= apb->nbytes)
{
- if (pBuf->nbytes != pBuf->nmaxbytes)
+ /* Check if this was the final buffer in stream */
+
+ if ((apb->flags & AUDIO_APB_FINAL) != 0)
{
/* This is the final buffer. Get the VS1053 endfillchar */
@@ -1119,7 +1125,8 @@ static void vs1053_feeddata(FAR struct vs1053_struct_s *dev)
/* Mark the device as endmode */
- dev->endmode = TRUE;
+ dev->endmode = true;
+
#ifndef CONFIG_AUDIO_EXCLUDE_STOP
if (dev->cancelmode)
{
@@ -1140,13 +1147,13 @@ static void vs1053_feeddata(FAR struct vs1053_struct_s *dev)
/* We referenced the buffer so we must free it */
- apb_free(pBuf);
+ apb_free(apb);
#ifdef CONFIG_AUDIO_MULTI_SESSION
dev->lower.upper(dev->lower.priv, AUDIO_CALLBACK_DEQUEUE,
- pBuf, OK, NULL);
+ apb, OK, NULL);
#else
dev->lower.upper(dev->lower.priv, AUDIO_CALLBACK_DEQUEUE,
- pBuf, OK);
+ apb, OK);
#endif
/* Lock the buffer queue to pop the next buffer */
@@ -1167,18 +1174,18 @@ static void vs1053_feeddata(FAR struct vs1053_struct_s *dev)
/* Pop the next entry */
- pBuf = (struct ap_buffer_s *) dq_remfirst(&dev->apbq);
- dev->pBuf = pBuf;
+ apb = (struct ap_buffer_s *) dq_remfirst(&dev->apbq);
+ dev->apb = apb;
- //auddbg("Next Buffer = %p, bytes = %d\n", pBuf, pBuf ? pBuf->nbytes : 0);
- if (pBuf == NULL)
+ //auddbg("Next Buffer = %p, bytes = %d\n", apb, apb ? apb->nbytes : 0);
+ if (apb == NULL)
{
sem_post(&dev->apbq_sem);
break;
}
- pSamp = &pBuf->samp[pBuf->curbyte];
- apb_reference(pBuf); /* Add our buffer reference */
+ pSamp = &apb->samp[apb->curbyte];
+ apb_reference(apb); /* Add our buffer reference */
sem_post(&dev->apbq_sem);
}
}
@@ -1254,7 +1261,7 @@ static void *vs1053_workerthread(pthread_addr_t pvarg)
{
FAR struct vs1053_struct_s *dev = (struct vs1053_struct_s *) pvarg;
struct audio_msg_s msg;
- FAR struct ap_buffer_s *pBuf;
+ FAR struct ap_buffer_s *apb;
int size;
int prio;
#ifndef CONFIG_AUDIO_EXCLUDE_STOP
@@ -1265,9 +1272,10 @@ static void *vs1053_workerthread(pthread_addr_t pvarg)
auddbg("Entry\n");
#ifndef CONFIG_AUDIO_EXCLUDE_STOP
- dev->cancelmode = 0;
+ dev->cancelmode = false;
#endif
- dev->endmode = dev->endfillbytes = 0;
+ dev->endmode = false;
+ dev->endfillbytes = 0;
/* Fill the VS1053 FIFO with initial data. */
@@ -1284,7 +1292,7 @@ static void *vs1053_workerthread(pthread_addr_t pvarg)
/* Loop as long as we are supposed to be running */
- dev->running = TRUE;
+ dev->running = true;
dev->hw_lower->enable(dev->hw_lower); /* Enable the DREQ interrupt */
while (dev->running || dev->endmode)
{
@@ -1303,7 +1311,7 @@ static void *vs1053_workerthread(pthread_addr_t pvarg)
{
/* Should we just stop running? */
- dev->running = FALSE;
+ dev->running = false;
break;
}
@@ -1338,7 +1346,7 @@ static void *vs1053_workerthread(pthread_addr_t pvarg)
/* Set cancelmode */
- dev->cancelmode = TRUE;
+ dev->cancelmode = true;
break;
#endif
@@ -1363,7 +1371,7 @@ static void *vs1053_workerthread(pthread_addr_t pvarg)
{
/* Get the next buffer from the queue */
- while ((pBuf = (FAR struct ap_buffer_s *) dq_remfirst(&dev->apbq)) != NULL)
+ while ((apb = (FAR struct ap_buffer_s *) dq_remfirst(&dev->apbq)) != NULL)
;
}
@@ -1371,10 +1379,10 @@ static void *vs1053_workerthread(pthread_addr_t pvarg)
/* Free the active buffer */
- if (dev->pBuf != NULL)
+ if (dev->apb != NULL)
{
- apb_free(dev->pBuf);
- dev->pBuf = NULL;
+ apb_free(dev->apb);
+ dev->apb = NULL;
}
/* Close the message queue */
@@ -1458,8 +1466,8 @@ static int vs1053_start(FAR struct audio_lowerhalf_s *lower)
if ((ret = sem_wait(&dev->apbq_sem)) == OK)
{
- dev->pBuf = (FAR struct ap_buffer_s *) dq_remfirst(&dev->apbq);
- apb_reference(dev->pBuf); /* Add our buffer reference */
+ dev->apb = (FAR struct ap_buffer_s *) dq_remfirst(&dev->apbq);
+ apb_reference(dev->apb); /* Add our buffer reference */
sem_post(&dev->apbq_sem);
}
else
@@ -1560,11 +1568,13 @@ static int vs1053_pause(FAR struct audio_lowerhalf_s *lower)
FAR struct vs1053_struct_s *dev = (struct vs1053_struct_s *) lower;
if (!dev->running)
- return OK;
+ {
+ return OK;
+ }
- /* Disable interrupts to prevent us from suppling any more data */
+ /* Disable interrupts to prevent us from supplying any more data */
- dev->paused = TRUE;
+ dev->paused = true;
dev->hw_lower->disable(dev->hw_lower); /* Disable the DREQ interrupt */
return OK;
}
@@ -1587,11 +1597,13 @@ static int vs1053_resume(FAR struct audio_lowerhalf_s *lower)
FAR struct vs1053_struct_s *dev = (struct vs1053_struct_s *) lower;
if (!dev->running)
- return OK;
+ {
+ return OK;
+ }
/* Enable interrupts to allow suppling data */
- dev->paused = FALSE;
+ dev->paused = false;
vs1053_feeddata(dev);
dev->hw_lower->enable(dev->hw_lower); /* Enable the DREQ interrupt */
return OK;
@@ -1621,7 +1633,7 @@ static int vs1053_enqueuebuffer(FAR struct audio_lowerhalf_s *lower,
/* We can now safely add the buffer to the queue */
apb->curbyte = 0;
- apb->flags = AUDIO_APB_OUTPUT_ENQUEUED;
+ apb->flags |= AUDIO_APB_OUTPUT_ENQUEUED;
dq_addlast(&apb->dq_entry, &dev->apbq);
sem_post(&dev->apbq_sem);
@@ -1730,9 +1742,9 @@ static int vs1053_reserve(FAR struct audio_lowerhalf_s *lower)
#ifdef CONFIG_AUDIO_MULTI_SESSION
*psession = NULL;
#endif
- dev->busy = TRUE;
- dev->running = FALSE;
- dev->paused = FALSE;
+ dev->busy = true;
+ dev->running = false;
+ dev->paused = false;
}
sem_post(&dev->apbq_sem);
@@ -1774,7 +1786,7 @@ static int vs1053_release(FAR struct audio_lowerhalf_s *lower)
/* Really we should free any queued buffers here */
- dev->busy = 0;
+ dev->busy = false;
sem_post(&dev->apbq_sem);
return OK;
@@ -1825,9 +1837,9 @@ struct audio_lowerhalf_s *vs1053_initialize(FAR struct spi_dev_s *spi,
dev->spi_freq = CONFIG_VS1053_XTALI / 7;
dev->spi = spi;
dev->mq = NULL;
- dev->busy = FALSE;
+ dev->busy = false;
dev->threadid = 0;
- dev->running = 0;
+ dev->running = false;
#ifndef CONFIG_AUDIO_EXCLUDE_VOLUME
dev->volume = 250; /* 25% volume as default */
diff --git a/nuttx/drivers/audio/wm8904.c b/nuttx/drivers/audio/wm8904.c
index 02f83f375..1120aa2da 100644
--- a/nuttx/drivers/audio/wm8904.c
+++ b/nuttx/drivers/audio/wm8904.c
@@ -451,6 +451,8 @@ static void wm8904_setvolume(FAR struct wm8904_dev_s *priv, uint16_t volume,
uint32_t rightlevel;
uint16_t regval;
+ audvdbg("volume=%u mute=%u\n", volume, mute);
+
#ifndef CONFIG_AUDIO_EXCLUDE_BALANCE
/* Calculate the left channel volume level {0..1000} */
@@ -524,6 +526,7 @@ static void wm8904_setvolume(FAR struct wm8904_dev_s *priv, uint16_t volume,
#ifndef CONFIG_AUDIO_EXCLUDE_TONE
static void wm8904_setbass(FAR struct wm8904_dev_s *priv, uint8_t bass)
{
+ audvdbg("bass=%u\n", bass);
#warning Missing logic
}
#endif /* CONFIG_AUDIO_EXCLUDE_TONE */
@@ -541,6 +544,7 @@ static void wm8904_setbass(FAR struct wm8904_dev_s *priv, uint8_t bass)
#ifndef CONFIG_AUDIO_EXCLUDE_TONE
static void wm8904_settreble(FAR struct wm8904_dev_s *priv, uint8_t treble)
{
+ audvdbg("treble=%u\n", treble);
#warning Missing logic
}
#endif /* CONFIG_AUDIO_EXCLUDE_TONE */
@@ -555,11 +559,10 @@ static void wm8904_settreble(FAR struct wm8904_dev_s *priv, uint8_t treble)
static int wm8904_getcaps(FAR struct audio_lowerhalf_s *dev, int type,
FAR struct audio_caps_s *caps)
{
- audvdbg("Entry\n");
-
/* Validate the structure */
- DEBUGASSERT(caps->ac_len >= sizeof(struct audio_caps_s));
+ DEBUGASSERT(caps && caps->ac_len >= sizeof(struct audio_caps_s));
+ audvdbg("type=%d ac_type=%d\n", type, caps->ac_type);
/* Fill in the caller's structure based on requested info */
@@ -726,6 +729,7 @@ static int wm8904_configure(FAR struct audio_lowerhalf_s *dev,
#endif
int ret = OK;
+ DEBUGASSERT(priv && caps);
audvdbg("ac_type: %d\n", caps->ac_type);
/* Process the configure operation */
@@ -858,6 +862,7 @@ static int wm8904_shutdown(FAR struct audio_lowerhalf_s *dev)
{
FAR struct wm8904_dev_s *priv = (FAR struct wm8904_dev_s *)dev;
+ DEBUGASSERT(priv);
wm8904_reset(priv);
return OK;
}
@@ -881,6 +886,7 @@ static void wm8904_senddone(FAR struct i2s_dev_s *i2s,
int ret;
DEBUGASSERT(i2s && priv && priv->running && apb);
+ audvdbg("apb=%p inflight=%d\n", apb, priv->inflight);
/* We do not place any restriction on the context in which this function
* is called. It may be called from an interrupt handler. Therefore, the
@@ -933,7 +939,7 @@ static void wm8904_senddone(FAR struct i2s_dev_s *i2s,
static void wm8904_returnbuffers(FAR struct wm8904_dev_s *priv)
{
FAR struct ap_buffer_s *apb;
- irqstate_t flags;
+ irqstate_t flags;
/* The doneq and in-flight values might be accessed from the interrupt
* level in some implementations. Not the best design. But we will
@@ -943,14 +949,43 @@ static void wm8904_returnbuffers(FAR struct wm8904_dev_s *priv)
flags = irqsave();
while (dq_peek(&priv->doneq) != NULL)
{
- /* Take next buffer from the queue of completed transfers */
+ /* Take the next buffer from the queue of completed transfers */
apb = (FAR struct ap_buffer_s *)dq_remfirst(&priv->doneq);
irqrestore(flags);
+ audvdbg("Returning apb=%p flags=%04x\n", apb, apb->flags);
+
+ /* Are we returning the final buffer in the stream? */
+
+ if ((apb->flags & AUDIO_APB_FINAL) != 0)
+ {
+ /* Both the pending and the done queues should be empty and there
+ * should be no buffers in-flight.
+ */
+
+ DEBUGASSERT(dq_empty(&priv->doneq) && dq_empty(&priv->pendq) &&
+ priv->inflight == 0);
+
+ /* Set the terminating flag. This will, eventually, cause the
+ * worker thread to exit (if it is not already terminating).
+ */
+
+ audvdbg("Terminating\n");
+ priv->terminating = true;
+ }
+
/* Release our reference to the audio buffer */
apb_free(apb);
+
+ /* Send the buffer back up to the previous level. */
+
+#ifdef CONFIG_AUDIO_MULTI_SESSION
+ priv->dev.upper(priv->dev.priv, AUDIO_CALLBACK_DEQUEUE, apb, OK, NULL);
+#else
+ priv->dev.upper(priv->dev.priv, AUDIO_CALLBACK_DEQUEUE, apb, OK);
+#endif
flags = irqsave();
}
@@ -993,7 +1028,8 @@ static int wm8904_sendbuffer(FAR struct wm8904_dev_s *priv)
/* Take next buffer from the queue of pending transfers */
apb = (FAR struct ap_buffer_s *)dq_remfirst(&priv->pendq);
- audvdbg("Sending apb=%p, size=%d\n", apb, apb->nbytes);
+ audvdbg("Sending apb=%p, size=%d inflight=%d\n",
+ apb, apb->nbytes, priv->inflight);
/* Increment the number of buffers in-flight before sending in order
* to avoid a possible race condition.
@@ -1082,7 +1118,9 @@ static void *wm8904_workerthread(pthread_addr_t pvarg)
WM8904_ENABLE(priv->lower);
wm8904_setvolume(priv, priv->volume, false);
- /* Loop as long as we are supposed to be running */
+ /* Loop as long as we are supposed to be running and as long as we have
+ * buffers in-flight.
+ */
while (priv->running || priv->inflight > 0)
{
@@ -1125,7 +1163,7 @@ static void *wm8904_workerthread(pthread_addr_t pvarg)
*/
case AUDIO_MSG_DATA_REQUEST:
- /* REVISIT this */
+ audvdbg("AUDIO_MSG_DATA_REQUEST\n");
break;
/* Stop the playback */
@@ -1134,6 +1172,7 @@ static void *wm8904_workerthread(pthread_addr_t pvarg)
case AUDIO_MSG_STOP:
/* Indicate that we are terminating */
+ audvdbg("AUDIO_MSG_STOP: Terminating\n");
priv->terminating = true;
break;
#endif
@@ -1143,11 +1182,13 @@ static void *wm8904_workerthread(pthread_addr_t pvarg)
*/
case AUDIO_MSG_ENQUEUE:
+ audvdbg("AUDIO_MSG_ENQUEUE\n");
break;
/* We will wake up from the I2S callback with this message */
case AUDIO_MSG_COMPLETE:
+ audvdbg("AUDIO_MSG_COMPLETE\n");
wm8904_returnbuffers(priv);
break;
@@ -1170,6 +1211,14 @@ static void *wm8904_workerthread(pthread_addr_t pvarg)
/* Release our reference to the buffer */
apb_free(apb);
+
+ /* Send the buffer back up to the previous level. */
+
+#ifdef CONFIG_AUDIO_MULTI_SESSION
+ priv->dev.upper(priv->dev.priv, AUDIO_CALLBACK_DEQUEUE, apb, OK, NULL);
+#else
+ priv->dev.upper(priv->dev.priv, AUDIO_CALLBACK_DEQUEUE, apb, OK);
+#endif
}
wm8904_givesem(&priv->pendsem);
@@ -1386,7 +1435,7 @@ static int wm8904_enqueuebuffer(FAR struct audio_lowerhalf_s *dev,
struct audio_msg_s term_msg;
int ret = -EAGAIN;
- audvdbg("Entry\n");
+ audvdbg("apb=%p\n", apb);
/* Take a reference on the new audio buffer */
@@ -1395,7 +1444,7 @@ static int wm8904_enqueuebuffer(FAR struct audio_lowerhalf_s *dev,
/* Add the new buffer to the tail of pending audio buffers */
wm8904_takesem(&priv->pendsem);
- apb->flags = AUDIO_APB_OUTPUT_ENQUEUED;
+ apb->flags |= AUDIO_APB_OUTPUT_ENQUEUED;
dq_addlast(&apb->dq_entry, &priv->pendq);
wm8904_givesem(&priv->pendsem);
@@ -1434,6 +1483,7 @@ static int wm8904_enqueuebuffer(FAR struct audio_lowerhalf_s *dev,
static int wm8904_cancelbuffer(FAR struct audio_lowerhalf_s *dev,
FAR struct ap_buffer_s *apb)
{
+ audvdbg("apb=%p\n", apb);
return OK;
}
diff --git a/nuttx/include/nuttx/audio/audio.h b/nuttx/include/nuttx/audio/audio.h
index 351e9ec54..78fc1944e 100644
--- a/nuttx/include/nuttx/audio/audio.h
+++ b/nuttx/include/nuttx/audio/audio.h
@@ -289,9 +289,10 @@
/* Audio Pipeline Buffer flags */
-#define AUDIO_APB_OUTPUT_ENQUEUED 0x0001;
-#define AUDIO_APB_OUTPUT_PROCESS 0x0002;
-#define AUDIO_APB_DEQUEUED 0x0004;
+#define AUDIO_APB_OUTPUT_ENQUEUED (1 << 0)
+#define AUDIO_APB_OUTPUT_PROCESS (1 << 1)
+#define AUDIO_APB_DEQUEUED (1 << 2)
+#define AUDIO_APB_FINAL (1 << 3) /* Last buffer in the stream */
/****************************************************************************
* Public Types
diff --git a/nuttx/libc/audio/lib_buffer.c b/nuttx/libc/audio/lib_buffer.c
index cf518de16..50c504b46 100644
--- a/nuttx/libc/audio/lib_buffer.c
+++ b/nuttx/libc/audio/lib_buffer.c
@@ -118,15 +118,15 @@ int apb_alloc(FAR struct audio_buf_desc_s *bufdesc)
{
uint32_t bufsize;
int ret;
- struct ap_buffer_s *pBuf;
+ struct ap_buffer_s *apb;
DEBUGASSERT(bufdesc->u.ppBuffer != NULL);
/* Perform a user mode allocation */
bufsize = sizeof(struct ap_buffer_s) + bufdesc->numbytes;
- pBuf = lib_umalloc(bufsize);
- *bufdesc->u.ppBuffer = pBuf;
+ apb = lib_umalloc(bufsize);
+ *bufdesc->u.ppBuffer = apb;
/* Test if the allocation was successful or not */
@@ -138,15 +138,17 @@ int apb_alloc(FAR struct audio_buf_desc_s *bufdesc)
{
/* Populate the buffer contents */
- memset(pBuf, 0, bufsize);
- pBuf->i.channels = 1;
- pBuf->crefs = 1;
- pBuf->nmaxbytes = bufdesc->numbytes;
- pBuf->nbytes = 0;
+ memset(apb, 0, bufsize);
+ apb->i.channels = 1;
+ apb->crefs = 1;
+ apb->nmaxbytes = bufdesc->numbytes;
+ apb->nbytes = 0;
+ apb->flags = 0;
#ifdef CONFIG_AUDIO_MULTI_SESSION
- pBuf->session = bufdesc->session;
+ apb->session = bufdesc->session;
#endif
- sem_init(&pBuf->sem, 0, 1);
+
+ sem_init(&apb->sem, 0, 1);
ret = sizeof(struct audio_buf_desc_s);
}