Fix readline return value; Add support for removable serial devices

git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5589 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
patacongo 2013-01-31 16:52:20 +00:00
parent 94360f3474
commit 9de6f4d501
10 changed files with 321 additions and 66 deletions

View File

@ -502,3 +502,6 @@
once when NSH starts; the .nshrc script will be executed for each session:
Once for serial, once for each USB connection, once for each Telnet
session.
* apps/system/readline: Correct realine return value. Was not
any returning special values when end-of-file or read errors
occur (it would return an empty string which is not very useful).

View File

@ -132,23 +132,34 @@ static inline int readline_rawgetc(int infd)
nread = read(infd, &buffer, 1);
/* Return EOF if the end of file (0) or error (-1) occurs. */
/* Check for end-of-file. */
if (nread < 1)
if (nread == 0)
{
/* Return zero on end-of-file */
return 0;
}
/* Check if an error occurred */
else if (nread < 0)
{
/* EINTR is not really an error; it simply means that a signal we
* received while watiing for intput.
*/
if (nread == 0 || errno != EINTR)
int errcode = errno;
if (errcode != EINTR)
{
return EOF;
return -errcode;
}
}
}
while (nread < 1);
/* On success, returnt he character that was read */
/* On success, return the character that was read */
return (int)buffer;
}
@ -275,9 +286,29 @@ ssize_t readline(FAR char *buf, int buflen, FILE *instream, FILE *outstream)
int ch = readline_rawgetc(infd);
/* Check for end-of-file or read error */
if (ch <= 0)
{
/* Did we already received some data? */
if (nch > 0)
{
/* Yes.. Terminate the line (which might be zero length)
* and return the data that was received. The end-of-file
* or error condition will be reported next time.
*/
buf[nch] = '\0';
return nch;
}
return ch;
}
/* Are we processing a VT100 escape sequence */
if (escape)
else if (escape)
{
/* Yes, is it an <esc>[, 3 byte sequence */
@ -366,16 +397,6 @@ ssize_t readline(FAR char *buf, int buflen, FILE *instream, FILE *outstream)
return nch;
}
/* Check for end-of-file */
else if (ch == EOF)
{
/* Terminate the line (which might be zero length) */
buf[nch] = '\0';
return nch;
}
/* Otherwise, check if the character is printable and, if so, put the
* character in the line buffer
*/

View File

@ -4069,4 +4069,8 @@
this.
* arch/arm/src/lm/chip/lm4f_memorymap.h: More LM4F changes from
Jose Pablo Carballo.
* drivers/serial/serial.c, include/nuttx/serial/serial.h,
drivers/usbdev/cdcacm.c, and drivers/pl2303.c: Add support for
removable serial devices (like USB serial). This support is enabled
by CONFIG_SERIAL_REMOVABLE and requires VBUS sensing support from
the board-specific logic.

View File

@ -95,9 +95,7 @@ CONFIG_BOARD_LOOPSPERMSEC=16717
#
# CONFIG_ARMV7M_TOOLCHAIN_ATOLLIC is not set
# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set
# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set
# CONFIG_ARMV7M_TOOLCHAIN_CODEREDW is not set
# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set
CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW=y
# CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM is not set
# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI is not set
@ -374,6 +372,7 @@ CONFIG_SPI_EXCHANGE=y
# CONFIG_SERCOMM_CONSOLE is not set
CONFIG_SERIAL=y
# CONFIG_DEV_LOWCONSOLE is not set
CONFIG_SERIAL_REMOVABLE=y
# CONFIG_16550_UART is not set
CONFIG_ARCH_HAVE_USART2=y
CONFIG_MCU_SERIAL=y
@ -458,6 +457,7 @@ CONFIG_CDCACM_PRODUCTSTR="CDC/ACM Serial"
#
# System Logging
#
# CONFIG_SYSLOG_ENABLE is not set
CONFIG_SYSLOG=y
CONFIG_SYSLOG_CHAR=y
CONFIG_SYSLOG_DEVPATH="/dev/ttyS0"
@ -686,6 +686,10 @@ CONFIG_NSH_NESTDEPTH=3
# CONFIG_NSH_DISABLEBG is not set
CONFIG_NSH_CONSOLE=y
# CONFIG_NSH_USBCONSOLE is not set
#
# USB Trace Support
#
# CONFIG_NSH_CONDEV is not set
CONFIG_NSH_ARCHINIT=y
@ -736,3 +740,7 @@ CONFIG_READLINE_ECHO=y
# Sysinfo
#
# CONFIG_SYSTEM_SYSINFO is not set
#
# USB Monitor
#

View File

@ -10,6 +10,9 @@ config DEV_LOWCONSOLE
---help---
Use the simple, low-level, write-only serial console driver (minimal support)
config SERIAL_REMOVABLE
bool
config 16550_UART
bool "16550 UART Chip support"
default n

View File

@ -1,7 +1,7 @@
/************************************************************************************
* drivers/serial/serial.c
*
* Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
* Copyright (C) 2007-2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@ -157,7 +157,11 @@ static void uart_pollnotify(FAR uart_dev_t *dev, pollevent_t eventset)
struct pollfd *fds = dev->fds[i];
if (fds)
{
#ifdef CONFIG_SERIAL_REMOVABLE
fds->revents |= ((fds->events | (POLLERR|POLLHUP)) & eventset);
#else
fds->revents |= (fds->events & eventset);
#endif
if (fds->revents != 0)
{
fvdbg("Report events: %02x\n", fds->revents);
@ -219,6 +223,15 @@ static int uart_putxmitchar(FAR uart_dev_t *dev, int ch)
uart_disabletxint(dev);
irqrestore(flags);
#ifdef CONFIG_SERIAL_REMOVABLE
/* Check if the removable device is no longer connected */
if (dev->disconnected)
{
return -ENOTCONN;
}
#endif
/* Check if we were awakened by signal. */
if (ret < 0)
@ -279,6 +292,15 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
ssize_t nread = buflen;
int ret;
#ifdef CONFIG_SERIAL_REMOVABLE
/* If the removable device is no longer connected, refuse to write to the device */
if (dev->disconnected)
{
return -ENOTCONN;
}
#endif
/* We may receive console writes through this path from interrupt handlers and
* from debug output in the IDLE task! In these cases, we will need to do things
* a little differently.
@ -395,6 +417,15 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
int16_t tail;
int ret;
#ifdef CONFIG_SERIAL_REMOVABLE
/* If the removable device is no longer connected, refuse to read from the device */
if (dev->disconnected)
{
return -ENOTCONN;
}
#endif
/* Only one user can access dev->recv.tail at a time */
ret = uart_takesem(&dev->recv.sem, true);
@ -525,9 +556,15 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
ret = uart_takesem(&dev->recvsem, true);
irqrestore(flags);
/* Was a signal received while waiting for data to be received? */
/* Was a signal received while waiting for data to be
* received? Was a removable device disconnected?
*/
#ifdef CONFIG_SERIAL_REMOVABLE
if (ret < 0 || dev->disconnected)
#else
if (ret < 0)
#endif
{
/* POSIX requires that we return after a signal is received.
* If some bytes were read, we need to return the number of bytes
@ -541,7 +578,11 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
* set the errno value appropriately.
*/
#ifdef CONFIG_SERIAL_REMOVABLE
recvd = dev->disconnected ? -ENOTCONN : -EINTR;
#else
recvd = -EINTR;
#endif
}
break;
@ -656,12 +697,12 @@ int uart_poll(FAR struct file *filep, FAR struct pollfd *fds, bool setup)
if (ndx != dev->xmit.tail)
{
eventset |= POLLOUT;
eventset |= (fds->events & POLLOUT);
}
uart_givesem(&dev->xmit.sem);
/* Check if the receive buffer is empty
/* Check if the receive buffer is empty.
*
* Get exclusive access to the recv buffer indices. NOTE: that we do not
* let this wait be interrupted by a signal (we probably should, but that
@ -671,11 +712,20 @@ int uart_poll(FAR struct file *filep, FAR struct pollfd *fds, bool setup)
(void)uart_takesem(&dev->recv.sem, false);
if (dev->recv.head != dev->recv.tail)
{
eventset |= POLLIN;
eventset |= (fds->events & POLLIN);
}
uart_givesem(&dev->recv.sem);
#ifdef CONFIG_SERIAL_REMOVABLE
/* Check if a removable device has been disconnected. */
if (dev->disconnected)
{
eventset |= (POLLERR|POLLHUP);
}
#endif
if (eventset)
{
uart_pollnotify(dev, eventset);
@ -796,6 +846,15 @@ static int uart_open(FAR struct file *filep)
uint8_t tmp;
int ret;
#ifdef CONFIG_SERIAL_REMOVABLE
/* If the removable device is no longer connected, refuse to open the device */
if (dev->disconnected)
{
return -ENOTCONN;
}
#endif
/* If the port is the middle of closing, wait until the close is finished.
* If a signal is received while we are waiting, then return EINTR.
*/
@ -915,10 +974,12 @@ int uart_register(FAR const char *path, FAR uart_dev_t *dev)
void uart_datareceived(FAR uart_dev_t *dev)
{
/* Awaken any awaiting read() operations */
/* Is there a thread waiting for read data? */
if (dev->recvwaiting)
{
/* Yes... wake it up */
dev->recvwaiting = false;
(void)sem_post(&dev->recvsem);
}
@ -942,8 +1003,12 @@ void uart_datareceived(FAR uart_dev_t *dev)
void uart_datasent(FAR uart_dev_t *dev)
{
/* Is there a thread waiting for space in xmit.buffer? */
if (dev->xmitwaiting)
{
/* Yes... wake it up */
dev->xmitwaiting = false;
(void)sem_post(&dev->xmitsem);
}
@ -953,4 +1018,64 @@ void uart_datasent(FAR uart_dev_t *dev)
uart_pollnotify(dev, POLLOUT);
}
/************************************************************************************
* Name: uart_connected
*
* Description:
* Serial devices (like USB serial) can be removed. In that case, the "upper
* half" serial driver must be informed that there is no longer a valid serial
* channel associated with the driver.
*
* In this case, the driver will terminate all pending transfers wint ENOTCONN and
* will refuse all further transactions while the "lower half" is disconnected.
* The driver will continue to be registered, but will be in an unusable state.
*
* Conversely, the "upper half" serial driver needs to know when the serial
* device is reconnected so that it can resume normal operations.
*
* Assumptions/Limitations:
* This function may be called from an interrupt handler.
*
************************************************************************************/
#ifdef CONFIG_SERIAL_REMOVABLE
void uart_connected(FAR uart_dev_t *dev, bool connected)
{
/* Is the device disconnected? */
dev->disconnected = !connected;
if (!connected)
{
/* Yes.. wake up all waiting threads. Each thread should detect the
* disconnection and return the ENOTCONN error.
*/
/* Is there a thread waiting for space in xmit.buffer? */
if (dev->xmitwaiting)
{
/* Yes... wake it up */
dev->xmitwaiting = false;
(void)sem_post(&dev->xmitsem);
}
/* Is there a thread waiting for read data? */
if (dev->recvwaiting)
{
/* Yes... wake it up */
dev->recvwaiting = false;
(void)sem_post(&dev->recvsem);
}
/* Notify all poll/select waiters that and hangup/error occurred */
uart_pollnotify(dev, (POLLERR|POLLHUP));
}
}
#endif

View File

@ -150,6 +150,7 @@ endif
menuconfig PL2303
bool "Prolific PL2303 serial/USB converter emulation"
default n
select SERIAL_REMOVABLE
---help---
This logic emulates the Prolific PL2303 serial/USB converter
@ -222,6 +223,7 @@ endif
menuconfig CDCACM
bool "USB Modem (CDC ACM) support"
default n
select SERIAL_REMOVABLE
---help---
Enables USB Modem (CDC ACM) support

View File

@ -570,6 +570,14 @@ static void cdcacm_resetconfig(FAR struct cdcacm_dev_s *priv)
priv->config = CDCACM_CONFIGIDNONE;
/* Inform the "upper half" driver that there is no (functional) USB
* connection.
*/
#ifdef CONFIG_SERIAL_REMOVABLE
uart_connected(&priv->serdev, false);
#endif
/* Disable endpoints. This should force completion of all pending
* transfers.
*/
@ -731,10 +739,20 @@ static int cdcacm_setconfig(FAR struct cdcacm_dev_s *priv, uint8_t config)
usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_RDSUBMIT), (uint16_t)-ret);
goto errout;
}
priv->nrdq++;
}
/* We are successfully configured */
priv->config = config;
/* Inform the "upper half" driver that we are "open for business" */
#ifdef CONFIG_SERIAL_REMOVABLE
uart_connected(&priv->serdev, true);
#endif
return OK;
errout:
@ -1575,12 +1593,20 @@ static void cdcacm_disconnect(FAR struct usbdevclass_driver_s *driver,
}
#endif
/* Reset the configuration */
/* Inform the "upper half serial driver that we have lost the USB serial
* connection.
*/
flags = irqsave();
#ifdef CONFIG_SERIAL_REMOVABLE
uart_connected(&priv->serdev, false);
#endif
/* Reset the configuration */
cdcacm_resetconfig(priv);
/* Clear out all data in the circular buffer */
/* Clear out all outgoing data in the circular buffer */
priv->serdev.xmit.head = 0;
priv->serdev.xmit.tail = 0;
@ -2045,6 +2071,11 @@ int cdcacm_classobject(int minor, FAR struct usbdevclass_driver_s **classdev)
/* Initialize the serial driver sub-structure */
/* The initial state is disconnected */
#ifdef CONFIG_SERIAL_REMOVABLE
priv->serdev.disconnected = true;
#endif
priv->serdev.recv.size = CONFIG_CDCACM_RXBUFSIZE;
priv->serdev.recv.buffer = priv->rxbuffer;
priv->serdev.xmit.size = CONFIG_CDCACM_TXBUFSIZE;

View File

@ -983,6 +983,14 @@ static void usbclass_resetconfig(FAR struct pl2303_dev_s *priv)
priv->config = PL2303_CONFIGIDNONE;
/* Inform the "upper half" driver that there is no (functional) USB
* connection.
*/
#ifdef CONFIG_SERIAL_REMOVABLE
uart_connected(&priv->serdev, false);
#endif
/* Disable endpoints. This should force completion of all pending
* transfers.
*/
@ -1112,10 +1120,20 @@ static int usbclass_setconfig(FAR struct pl2303_dev_s *priv, uint8_t config)
usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_RDSUBMIT), (uint16_t)-ret);
goto errout;
}
priv->nrdq++;
}
/* We are successfully configured */
priv->config = config;
/* Inform the "upper half" driver that we are "open for business" */
#ifdef CONFIG_SERIAL_REMOVABLE
uart_connected(&priv->serdev, true);
#endif
return OK;
errout:
@ -1844,12 +1862,20 @@ static void usbclass_disconnect(FAR struct usbdevclass_driver_s *driver,
}
#endif
/* Reset the configuration */
/* Inform the "upper half serial driver that we have lost the USB serial
* connection.
*/
flags = irqsave();
#ifdef CONFIG_SERIAL_REMOVABLE
uart_connected(&priv->serdev, false);
#endif
/* Reset the configuration */
usbclass_resetconfig(priv);
/* Clear out all data in the circular buffer */
/* Clear out all outgoing data in the circular buffer */
priv->serdev.xmit.head = 0;
priv->serdev.xmit.tail = 0;
@ -2185,6 +2211,9 @@ int usbdev_serialinitialize(int minor)
/* Initialize the serial driver sub-structure */
#ifdef CONFIG_SERIAL_REMOVABLE
priv->serdev.disconnected = true;
#endif
priv->serdev.recv.size = CONFIG_PL2303_RXBUFSIZE;
priv->serdev.recv.buffer = priv->rxbuffer;
priv->serdev.xmit.size = CONFIG_PL2303_TXBUFSIZE;

View File

@ -1,7 +1,7 @@
/************************************************************************************
* include/nuttx/serial/serial.h
*
* Copyright (C) 2007-2008, 2012 Gregory Nutt. All rights reserved.
* Copyright (C) 2007-2008, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@ -46,6 +46,7 @@
#include <stdint.h>
#include <stdbool.h>
#include <semaphore.h>
#include <nuttx/fs/fs.h>
/************************************************************************************
@ -193,6 +194,9 @@ struct uart_dev_s
uint8_t open_count; /* Number of times the device has been opened */
volatile bool xmitwaiting; /* true: User waiting for space in xmit.buffer */
volatile bool recvwaiting; /* true: User waiting for data in recv.buffer */
#ifdef CONFIG_SERIAL_REMOVABLE
volatile bool disconnected; /* true: Removable device is not connected */
#endif
bool isconsole; /* true: This is the serial console */
sem_t closesem; /* Locks out new open while close is in progress */
sem_t xmitsem; /* Wakeup user waiting for space in xmit.buffer */
@ -213,26 +217,27 @@ struct uart_dev_s
#ifndef CONFIG_DISABLE_POLL
struct pollfd *fds[CONFIG_SERIAL_NPOLLWAITERS];
#endif
};
typedef struct uart_dev_s uart_dev_t;
/************************************************************************************
* Public Data
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C" {
extern "C"
{
#else
#define EXTERN extern
#endif
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: uart_register
*
@ -241,7 +246,7 @@ extern "C" {
*
************************************************************************************/
EXTERN int uart_register(FAR const char *path, FAR uart_dev_t *dev);
int uart_register(FAR const char *path, FAR uart_dev_t *dev);
/************************************************************************************
* Name: uart_xmitchars
@ -254,7 +259,7 @@ EXTERN int uart_register(FAR const char *path, FAR uart_dev_t *dev);
*
************************************************************************************/
EXTERN void uart_xmitchars(FAR uart_dev_t *dev);
void uart_xmitchars(FAR uart_dev_t *dev);
/************************************************************************************
* Name: uart_receivechars
@ -267,7 +272,7 @@ EXTERN void uart_xmitchars(FAR uart_dev_t *dev);
*
************************************************************************************/
EXTERN void uart_recvchars(FAR uart_dev_t *dev);
void uart_recvchars(FAR uart_dev_t *dev);
/************************************************************************************
* Name: uart_datareceived
@ -279,7 +284,7 @@ EXTERN void uart_recvchars(FAR uart_dev_t *dev);
*
************************************************************************************/
EXTERN void uart_datareceived(FAR uart_dev_t *dev);
void uart_datareceived(FAR uart_dev_t *dev);
/************************************************************************************
* Name: uart_datasent
@ -292,7 +297,31 @@ EXTERN void uart_datareceived(FAR uart_dev_t *dev);
*
************************************************************************************/
EXTERN void uart_datasent(FAR uart_dev_t *dev);
void uart_datasent(FAR uart_dev_t *dev);
/************************************************************************************
* Name: uart_connected
*
* Description:
* Serial devices (like USB serial) can be removed. In that case, the "upper
* half" serial driver must be informed that there is no longer a valid serial
* channel associated with the driver.
*
* In this case, the driver will terminate all pending transfers wint ENOTCONN and
* will refuse all further transactions while the "lower half" is disconnected.
* The driver will continue to be registered, but will be in an unusable state.
*
* Conversely, the "upper half" serial driver needs to know when the serial
* device is reconnected so that it can resume normal operations.
*
* Assumptions/Limitations:
* This function may be called from an interrupt handler.
*
************************************************************************************/
#ifdef CONFIG_SERIAL_REMOVABLE
void uart_connected(FAR uart_dev_t *dev, bool connected);
#endif
#undef EXTERN
#if defined(__cplusplus)