summaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-11-17 23:22:27 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-11-17 23:22:27 +0000
commit09f70284f5e1d190519661166422909e69b2331b (patch)
treeb968095164f6f6417386d02feda27ea7e7d434ca /nuttx/drivers
parent5c3162da749c8c8c1609c1ab1c85ab1961dbabde (diff)
downloadpx4-nuttx-09f70284f5e1d190519661166422909e69b2331b.tar.gz
px4-nuttx-09f70284f5e1d190519661166422909e69b2331b.tar.bz2
px4-nuttx-09f70284f5e1d190519661166422909e69b2331b.zip
Add poll method to serial drivers
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1268 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/serial.c184
-rw-r--r--nuttx/drivers/serialirq.c41
-rw-r--r--nuttx/drivers/usbdev/usbdev_serial.c59
3 files changed, 229 insertions, 55 deletions
diff --git a/nuttx/drivers/serial.c b/nuttx/drivers/serial.c
index 366c7a208..2939bf61f 100644
--- a/nuttx/drivers/serial.c
+++ b/nuttx/drivers/serial.c
@@ -44,6 +44,7 @@
#include <semaphore.h>
#include <string.h>
#include <fcntl.h>
+#include <poll.h>
#include <errno.h>
#include <debug.h>
@@ -77,6 +78,9 @@ static int uart_close(FAR struct file *filep);
static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen);
static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t buflen);
static int uart_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
+#ifndef CONFIG_DISABLE_POLL
+static int uart_poll(FAR struct file *filep, FAR struct pollfd *fds);
+#endif
/************************************************************************************
* Private Variables
@@ -89,8 +93,10 @@ struct file_operations g_serialops =
uart_read, /* read */
uart_write, /* write */
0, /* seek */
- uart_ioctl, /* ioctl */
- 0 /* poll */
+ uart_ioctl /* ioctl */
+#ifndef CONFIG_DISABLE_POLL
+ , uart_poll /* poll */
+#endif
};
/************************************************************************************
@@ -119,6 +125,33 @@ static void uart_takesem(FAR sem_t *sem)
#define uart_givesem(sem) (void)sem_post(sem)
+/****************************************************************************
+ * Name: uart_pollnotify
+ ****************************************************************************/
+
+#ifndef CONFIG_DISABLE_POLL
+static void uart_pollnotify(FAR uart_dev_t *dev, pollevent_t eventset)
+{
+ int i;
+
+ for (i = 0; i < CONFIG_DEV_CONSOLE_NPOLLWAITERS; i++)
+ {
+ struct pollfd *fds = dev->fds[i];
+ if (fds)
+ {
+ fds->revents |= (fds->events & eventset);
+ if (fds->revents != 0)
+ {
+ fvdbg("Report events: %02x\n", fds->revents);
+ sem_post(fds->sem);
+ }
+ }
+ }
+}
+#else
+# define uart_pollnotify(dev,event)
+#endif
+
/************************************************************************************
* Name: uart_putxmitchar
************************************************************************************/
@@ -340,6 +373,98 @@ static int uart_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
return dev->ops->ioctl(filep, cmd, arg);
}
+/****************************************************************************
+ * Name: uart_poll
+ ****************************************************************************/
+
+#ifndef CONFIG_DISABLE_POLL
+int uart_poll(FAR struct file *filep, FAR struct pollfd *fds)
+{
+ FAR struct inode *inode = filep->f_inode;
+ FAR uart_dev_t *dev = inode->i_private;
+ pollevent_t eventset;
+ int ndx;
+ int i;
+
+ /* Some sanity checking */
+#if CONFIG_DEBUG
+ if (!dev)
+ {
+ return -ENODEV;
+ }
+#endif
+
+ /* Find an available slot for the poll structure reference */
+
+ uart_takesem(&dev->pollsem);
+ for (i = 0; i < CONFIG_DEV_CONSOLE_NPOLLWAITERS; i++)
+ {
+ /* Find the slot with the value equal to filep->f_priv. If there
+ * is not previously installed poll structure, then f_priv will
+ * be NULL and we will find the first unused slot. If f_priv is
+ * is non-NULL, then we will find the slot that was used for the
+ * previous setup.
+ */
+
+ if (dev->fds[i] == filep->f_priv)
+ {
+ dev->fds[i] = fds;
+ break;
+ }
+ }
+
+ if (i >= CONFIG_DEV_CONSOLE_NPOLLWAITERS)
+ {
+ DEBUGASSERT(fds == NULL);
+ return -EBUSY;
+ }
+
+ /* Set or clear the poll event structure reference in the 'struct file'
+ * private data.
+ */
+
+ filep->f_priv = fds;
+
+ /* Check if we should immediately notify on any of the requested events */
+
+ if (fds)
+ {
+ /* Check if the xmit buffer is full. */
+
+ eventset = 0;
+
+ uart_takesem(&dev->xmit.sem);
+ ndx = dev->xmit.head + 1;
+ if (ndx >= dev->xmit.size)
+ {
+ ndx = 0;
+ }
+ if (ndx != dev->xmit.tail)
+ {
+ eventset |= POLLOUT;
+ }
+ uart_givesem(&dev->xmit.sem);
+
+ /* Check if the receive buffer is empty */
+
+ uart_takesem(&dev->recv.sem);
+ if (dev->recv.head != dev->recv.tail)
+ {
+ eventset |= POLLIN;
+ }
+ uart_givesem(&dev->recv.sem);
+
+ if (eventset)
+ {
+ uart_pollnotify(dev, eventset);
+ }
+ }
+
+ uart_givesem(&dev->pollsem);
+ return OK;
+}
+#endif
+
/************************************************************************************
* Name: uart_close
*
@@ -513,7 +638,62 @@ int uart_register(FAR const char *path, FAR uart_dev_t *dev)
sem_init(&dev->closesem, 0, 1);
sem_init(&dev->xmitsem, 0, 0);
sem_init(&dev->recvsem, 0, 0);
+#ifndef CONFIG_DISABLE_POLL
+ sem_init(&dev->pollsem, 0, 1);
+#endif
dbg("Registering %s\n", path);
return register_driver(path, &g_serialops, 0666, dev);
}
+
+/************************************************************************************
+ * Name: uart_datareceived
+ *
+ * Description:
+ * This function is called from uart_recvchars when new serial data is place in
+ * the driver's circular buffer. This function will wake-up any stalled read()
+ * operations that are waiting for incoming data.
+ *
+ ************************************************************************************/
+
+void uart_datareceived(FAR uart_dev_t *dev)
+{
+ /* Awaken any awaiting read() operations */
+
+ if (dev->recvwaiting)
+ {
+ dev->recvwaiting = FALSE;
+ (void)sem_post(&dev->recvsem);
+ }
+
+ /* Notify all poll/select waiters that they can read from the recv buffer */
+
+ uart_pollnotify(dev, POLLIN);
+
+}
+
+/************************************************************************************
+ * Name: uart_datasent
+ *
+ * Description:
+ * This function is called from uart_xmitchars after serial data has been sent,
+ * freeing up some space in the driver's circular buffer. This function will
+ * wake-up any stalled write() operations that was waiting for space to buffer
+ * outgoing data.
+ *
+ ************************************************************************************/
+
+void uart_datasent(FAR uart_dev_t *dev)
+{
+ if (dev->xmitwaiting)
+ {
+ dev->xmitwaiting = FALSE;
+ (void)sem_post(&dev->xmitsem);
+ }
+
+ /* Notify all poll/select waiters that they can write to xmit buffer */
+
+ uart_pollnotify(dev, POLLOUT);
+}
+
+
diff --git a/nuttx/drivers/serialirq.c b/nuttx/drivers/serialirq.c
index f7503e4cc..d1a18b257 100644
--- a/nuttx/drivers/serialirq.c
+++ b/nuttx/drivers/serialirq.c
@@ -80,6 +80,8 @@
void uart_xmitchars(FAR uart_dev_t *dev)
{
+ uint16 nbytes = 0;
+
/* Send while we still have data & room in the fifo */
while (dev->xmit.head != dev->xmit.tail && uart_txready(dev))
@@ -87,6 +89,7 @@ void uart_xmitchars(FAR uart_dev_t *dev)
/* Send the next byte */
uart_send(dev, dev->xmit.buffer[dev->xmit.tail]);
+ nbytes++;
/* Increment the tail index */
@@ -94,16 +97,6 @@ void uart_xmitchars(FAR uart_dev_t *dev)
{
dev->xmit.tail = 0;
}
-
- /* A byte was removed from the buffer. Inform any waiters
- * there there is space available.
- */
-
- if (dev->xmitwaiting)
- {
- dev->xmitwaiting = FALSE;
- (void)sem_post(&dev->xmitsem);
- }
}
/* When all of the characters have been sent from the buffer
@@ -114,6 +107,15 @@ void uart_xmitchars(FAR uart_dev_t *dev)
{
uart_disabletxint(dev);
}
+
+ /* If any bytes were removed from the buffer, inform any waiters
+ * there there is space available.
+ */
+
+ if (nbytes)
+ {
+ uart_datasent(dev);
+ }
}
/************************************************************************************
@@ -131,6 +133,7 @@ void uart_recvchars(FAR uart_dev_t *dev)
{
unsigned int status;
int nexthead = dev->recv.head + 1;
+ uint16 nbytes = 0;
if (nexthead >= dev->recv.size)
{
@@ -146,6 +149,7 @@ void uart_recvchars(FAR uart_dev_t *dev)
/* Add the character to the buffer */
dev->recv.buffer[dev->recv.head] = uart_receive(dev, &status);
+ nbytes++;
/* Increment the head index */
@@ -154,18 +158,15 @@ void uart_recvchars(FAR uart_dev_t *dev)
{
nexthead = 0;
}
+ }
- /* A character was added... if there is a thread waiting for more data, then
- * post the recvsem semaphore to wake it up. NOTE: There is a logic error in
- * the above looping logic: If nexthead == dev->recv.tail on entry and
- * recvwaiting is true, the recvsem will never get posted!
- */
+ /* If any bytes were added to the buffer, inform any waiters
+ * there there is new incoming data available.
+ */
- if (dev->recvwaiting)
- {
- dev->recvwaiting = FALSE;
- (void)sem_post(&dev->recvsem);
- }
+ if (nbytes)
+ {
+ uart_datareceived(dev);
}
}
diff --git a/nuttx/drivers/usbdev/usbdev_serial.c b/nuttx/drivers/usbdev/usbdev_serial.c
index 4b32ac052..116accc57 100644
--- a/nuttx/drivers/usbdev/usbdev_serial.c
+++ b/nuttx/drivers/usbdev/usbdev_serial.c
@@ -526,14 +526,6 @@ static uint16 usbclass_fillrequest(FAR struct usbser_dev_s *priv, char *reqbuf,
{
xmit->tail = 0;
}
-
- /* Check if we have to wake up the serial driver */
-
- if (serdev->xmitwaiting)
- {
- serdev->xmitwaiting = FALSE;
- sem_post(&serdev->xmitsem);
- }
}
/* When all of the characters have been sent from the buffer
@@ -545,6 +537,15 @@ static uint16 usbclass_fillrequest(FAR struct usbser_dev_s *priv, char *reqbuf,
uart_disabletxint(serdev);
}
+ /* If any bytes were removed from the buffer, inform any waiters
+ * there there is space available.
+ */
+
+ if (nbytes)
+ {
+ uart_datasent(serdev);
+ }
+
irqrestore(flags);
return nbytes;
}
@@ -651,6 +652,7 @@ static inline int usbclass_recvpacket(FAR struct usbser_dev_s *priv,
FAR struct uart_buffer_s *recv = &serdev->recv;
uint16 currhead;
uint16 nexthead;
+ uint16 nbytes = 0;
/* Get the next head index. During the time that RX interrupts are disabled, the
* the serial driver will be extracting data from the circular buffer and modifying
@@ -684,7 +686,7 @@ static inline int usbclass_recvpacket(FAR struct usbser_dev_s *priv,
* then we have overrun the serial driver and data will be lost.
*/
- while (nexthead != recv->tail && reqlen > 0)
+ while (nexthead != recv->tail && nbytes < reqlen)
{
/* Copy one byte to the head of the circular RX buffer */
@@ -693,21 +695,7 @@ static inline int usbclass_recvpacket(FAR struct usbser_dev_s *priv,
/* Update counts and indices */
currhead = nexthead;
- reqlen--;
-
- /* Wake up the serial driver if it is waiting for incoming data. If we
- * are running in an interrupt handler, then the serial driver will
- * not run until the interrupt handler returns. But we will exercise
- * care in the following just in case the serial driver does run.
- */
-
- if (priv->rxenabled && serdev->recvwaiting)
- {
- recv->head = currhead;
- serdev->recvwaiting = FALSE;
- sem_post(&serdev->recvsem);
- currhead = recv->head;
- }
+ nbytes++;
/* Increment the head index and check for wrap around */
@@ -731,9 +719,20 @@ static inline int usbclass_recvpacket(FAR struct usbser_dev_s *priv,
priv->rxhead = currhead;
}
+ /* If data was added to the incoming serial buffer, then wake up any
+ * threads is waiting for incoming data. If we are running in an interrupt
+ * handler, then the serial driver will not run until the interrupt handler
+ * returns.
+ */
+
+ if (priv->rxenabled && nbytes > 0)
+ {
+ uart_datareceived(serdev);
+ }
+
/* Return an error if the entire packet could not be transferred */
- if (reqlen > 0)
+ if (nbytes < reqlen)
{
usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_RXOVERRUN), 0);
return -ENOSPC;
@@ -2017,15 +2016,9 @@ static void usbser_rxint(FAR struct uart_dev_s *dev, boolean enable)
{
serdev->recv.head = priv->rxhead;
- /* Is the serial driver waiting for more data? */
+ /* Yes... signal the availability of new data */
- if (serdev->recvwaiting)
- {
- /* Yes... signal the availability of new data */
-
- sem_post(&serdev->recvsem);
- serdev->recvwaiting = FALSE;
- }
+ uart_datareceived(serdev);
}
/* RX "interrupts are no longer disabled */