aboutsummaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/Kconfig8
-rw-r--r--nuttx/drivers/lcd/mio283qt2.c6
-rw-r--r--nuttx/drivers/lcd/ssd1289.c6
-rw-r--r--nuttx/drivers/loop.c2
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_debug.c4
-rw-r--r--nuttx/drivers/mmcsd/mmcsd_spi.c10
-rw-r--r--nuttx/drivers/mtd/at25.c16
-rw-r--r--nuttx/drivers/net/enc28j60.c96
-rw-r--r--nuttx/drivers/serial/Kconfig3
-rw-r--r--nuttx/drivers/serial/serial.c221
-rw-r--r--nuttx/drivers/syslog/ramlog.c6
-rw-r--r--nuttx/drivers/usbdev/Kconfig44
-rw-r--r--nuttx/drivers/usbdev/cdcacm.c137
-rw-r--r--nuttx/drivers/usbdev/pl2303.c129
-rw-r--r--nuttx/drivers/usbdev/usbdev_trace.c4
-rw-r--r--nuttx/drivers/usbdev/usbmsc.h8
16 files changed, 578 insertions, 122 deletions
diff --git a/nuttx/drivers/Kconfig b/nuttx/drivers/Kconfig
index 3ced01b58..f3d2c871a 100644
--- a/nuttx/drivers/Kconfig
+++ b/nuttx/drivers/Kconfig
@@ -3,6 +3,14 @@
# see misc/tools/kconfig-language.txt.
#
+config DISABLE_POLL
+ bool "Disable driver poll interfaces"
+ default n
+ ---help---
+ The sizes of drivers can be reduced if the poll() method is not
+ supported. If you do not use poll() or select(), then you can
+ select DISABLE_POLL to reduce the code footprint by a small amount.
+
config DEV_NULL
bool "Enable /dev/null"
default y
diff --git a/nuttx/drivers/lcd/mio283qt2.c b/nuttx/drivers/lcd/mio283qt2.c
index 1758e230c..4c8835eef 100644
--- a/nuttx/drivers/lcd/mio283qt2.c
+++ b/nuttx/drivers/lcd/mio283qt2.c
@@ -495,14 +495,14 @@ static void mio283qt2_dumprun(FAR const char *msg, FAR uint16_t *run, size_t npi
{
int i, j;
- lib_rawprintf("\n%s:\n", msg);
+ syslog("\n%s:\n", msg);
for (i = 0; i < npixels; i += 16)
{
up_putc(' ');
- lib_rawprintf(" ");
+ syslog(" ");
for (j = 0; j < 16; j++)
{
- lib_rawprintf(" %04x", *run++);
+ syslog(" %04x", *run++);
}
up_putc('\n');
}
diff --git a/nuttx/drivers/lcd/ssd1289.c b/nuttx/drivers/lcd/ssd1289.c
index e42b5bded..d78688be5 100644
--- a/nuttx/drivers/lcd/ssd1289.c
+++ b/nuttx/drivers/lcd/ssd1289.c
@@ -497,14 +497,14 @@ static void ssd1289_dumprun(FAR const char *msg, FAR uint16_t *run, size_t npixe
{
int i, j;
- lib_rawprintf("\n%s:\n", msg);
+ syslog("\n%s:\n", msg);
for (i = 0; i < npixels; i += 16)
{
up_putc(' ');
- lib_rawprintf(" ");
+ syslog(" ");
for (j = 0; j < 16; j++)
{
- lib_rawprintf(" %04x", *run++);
+ syslog(" %04x", *run++);
}
up_putc('\n');
}
diff --git a/nuttx/drivers/loop.c b/nuttx/drivers/loop.c
index b5b5d82d8..4744ae0dd 100644
--- a/nuttx/drivers/loop.c
+++ b/nuttx/drivers/loop.c
@@ -268,7 +268,7 @@ static ssize_t loop_write(FAR struct inode *inode, const unsigned char *buffer,
size_t start_sector, unsigned int nsectors)
{
FAR struct loop_struct_s *dev;
- size_t nbyteswritten;
+ ssize_t nbyteswritten;
off_t offset;
int ret;
diff --git a/nuttx/drivers/mmcsd/mmcsd_debug.c b/nuttx/drivers/mmcsd/mmcsd_debug.c
index 0bd7f896e..8cb5b2a2a 100644
--- a/nuttx/drivers/mmcsd/mmcsd_debug.c
+++ b/nuttx/drivers/mmcsd/mmcsd_debug.c
@@ -56,9 +56,9 @@
/* This needs to match the logic in include/debug.h */
#ifdef CONFIG_CPP_HAVE_VARARGS
-# define message(format, arg...) lib_rawprintf(format, ##arg)
+# define message(format, arg...) syslog(format, ##arg)
#else
-# define message lib_rawprintf
+# define message syslog
#endif
/****************************************************************************
diff --git a/nuttx/drivers/mmcsd/mmcsd_spi.c b/nuttx/drivers/mmcsd/mmcsd_spi.c
index d437b7fea..3d4cf1dd1 100644
--- a/nuttx/drivers/mmcsd/mmcsd_spi.c
+++ b/nuttx/drivers/mmcsd/mmcsd_spi.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/mmcsd/mmcsd_spi.c
*
- * Copyright (C) 2008-2010, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2010, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -409,10 +409,14 @@ static uint32_t mmcsd_sendcmd(FAR struct mmcsd_slot_s *slot,
int ret;
int i;
- /* Wait until the card is not busy */
+ /* Wait until the card is not busy. Some SD cards will not enter the IDLE
+ * state until CMD0 is sent for the first time, switching the card to SPI
+ * mode. Having a pull-up resistor on MISO may avoid this problem, but
+ * this check makes it work also without the pull-up.
+ */
ret = mmcsd_waitready(slot);
- if (ret != OK)
+ if (ret != OK && cmd != &g_cmd0)
{
return ret;
}
diff --git a/nuttx/drivers/mtd/at25.c b/nuttx/drivers/mtd/at25.c
index e35b794a5..c58b16122 100644
--- a/nuttx/drivers/mtd/at25.c
+++ b/nuttx/drivers/mtd/at25.c
@@ -691,14 +691,16 @@ FAR struct mtd_dev_s *at25_initialize(FAR struct spi_dev_s *dev)
kfree(priv);
priv = NULL;
}
-
- /* Unprotect all sectors */
+ else
+ {
+ /* Unprotect all sectors */
- at25_writeenable(priv);
- SPI_SELECT(priv->dev, SPIDEV_FLASH, true);
- (void)SPI_SEND(priv->dev, AT25_WRSR);
- (void)SPI_SEND(priv->dev, AT25_SR_UNPROT);
- SPI_SELECT(priv->dev, SPIDEV_FLASH, false);
+ at25_writeenable(priv);
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, true);
+ (void)SPI_SEND(priv->dev, AT25_WRSR);
+ (void)SPI_SEND(priv->dev, AT25_SR_UNPROT);
+ SPI_SELECT(priv->dev, SPIDEV_FLASH, false);
+ }
}
/* Return the implementation-specific state structure as the MTD device */
diff --git a/nuttx/drivers/net/enc28j60.c b/nuttx/drivers/net/enc28j60.c
index 2346ee2d6..203259aeb 100644
--- a/nuttx/drivers/net/enc28j60.c
+++ b/nuttx/drivers/net/enc28j60.c
@@ -179,10 +179,10 @@
/* Debug ********************************************************************/
#ifdef CONFIG_ENC28J60_REGDEBUG
-# define enc_wrdump(a,v) lib_lowprintf("ENC28J60: %02x<-%02x\n", a, v);
-# define enc_rddump(a,v) lib_lowprintf("ENC28J60: %02x->%02x\n", a, v);
-# define enc_cmddump(c) lib_lowprintf("ENC28J60: CMD: %02x\n", c);
-# define enc_bmdump(c,b,s) lib_lowprintf("ENC28J60: CMD: %02x buffer: %p length: %d\n", c,b,s);
+# define enc_wrdump(a,v) lowsyslog("ENC28J60: %02x<-%02x\n", a, v);
+# define enc_rddump(a,v) lowsyslog("ENC28J60: %02x->%02x\n", a, v);
+# define enc_cmddump(c) lowsyslog("ENC28J60: CMD: %02x\n", c);
+# define enc_bmdump(c,b,s) lowsyslog("ENC28J60: CMD: %02x buffer: %p length: %d\n", c,b,s);
#else
# define enc_wrdump(a,v)
# define enc_rddump(a,v)
@@ -773,56 +773,56 @@ static int enc_waitbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
#if 0 /* Sometimes useful */
static void enc_rxdump(FAR struct enc_driver_s *priv)
{
- lib_lowprintf("Rx Registers:\n");
- lib_lowprintf(" EIE: %02x EIR: %02x\n",
- enc_rdgreg(priv, ENC_EIE), enc_rdgreg(priv, ENC_EIR));
- lib_lowprintf(" ESTAT: %02x ECON1: %02x ECON2: %02x\n",
- enc_rdgreg(priv, ENC_ESTAT), enc_rdgreg(priv, ENC_ECON1),
- enc_rdgreg(priv, ENC_ECON2));
- lib_lowprintf(" ERXST: %02x %02x\n",
- enc_rdbreg(priv, ENC_ERXSTH), enc_rdbreg(priv, ENC_ERXSTL));
- lib_lowprintf(" ERXND: %02x %02x\n",
- enc_rdbreg(priv, ENC_ERXNDH), enc_rdbreg(priv, ENC_ERXNDL));
- lib_lowprintf(" ERXRDPT: %02x %02x\n",
- enc_rdbreg(priv, ENC_ERXRDPTH), enc_rdbreg(priv, ENC_ERXRDPTL));
- lib_lowprintf(" ERXFCON: %02x EPKTCNT: %02x\n",
- enc_rdbreg(priv, ENC_ERXFCON), enc_rdbreg(priv, ENC_EPKTCNT));
- lib_lowprintf(" MACON1: %02x MACON3: %02x\n",
- enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3));
- lib_lowprintf(" MAMXFL: %02x %02x\n",
- enc_rdbreg(priv, ENC_MAMXFLH), enc_rdbreg(priv, ENC_MAMXFLL));
- lib_lowprintf(" MAADR: %02x:%02x:%02x:%02x:%02x:%02x\n",
- enc_rdbreg(priv, ENC_MAADR1), enc_rdbreg(priv, ENC_MAADR2),
- enc_rdbreg(priv, ENC_MAADR3), enc_rdbreg(priv, ENC_MAADR4),
- enc_rdbreg(priv, ENC_MAADR5), enc_rdbreg(priv, ENC_MAADR6));
+ lowsyslog("Rx Registers:\n");
+ lowsyslog(" EIE: %02x EIR: %02x\n",
+ enc_rdgreg(priv, ENC_EIE), enc_rdgreg(priv, ENC_EIR));
+ lowsyslog(" ESTAT: %02x ECON1: %02x ECON2: %02x\n",
+ enc_rdgreg(priv, ENC_ESTAT), enc_rdgreg(priv, ENC_ECON1),
+ enc_rdgreg(priv, ENC_ECON2));
+ lowsyslog(" ERXST: %02x %02x\n",
+ enc_rdbreg(priv, ENC_ERXSTH), enc_rdbreg(priv, ENC_ERXSTL));
+ lowsyslog(" ERXND: %02x %02x\n",
+ enc_rdbreg(priv, ENC_ERXNDH), enc_rdbreg(priv, ENC_ERXNDL));
+ lowsyslog(" ERXRDPT: %02x %02x\n",
+ enc_rdbreg(priv, ENC_ERXRDPTH), enc_rdbreg(priv, ENC_ERXRDPTL));
+ lowsyslog(" ERXFCON: %02x EPKTCNT: %02x\n",
+ enc_rdbreg(priv, ENC_ERXFCON), enc_rdbreg(priv, ENC_EPKTCNT));
+ lowsyslog(" MACON1: %02x MACON3: %02x\n",
+ enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3));
+ lowsyslog(" MAMXFL: %02x %02x\n",
+ enc_rdbreg(priv, ENC_MAMXFLH), enc_rdbreg(priv, ENC_MAMXFLL));
+ lowsyslog(" MAADR: %02x:%02x:%02x:%02x:%02x:%02x\n",
+ enc_rdbreg(priv, ENC_MAADR1), enc_rdbreg(priv, ENC_MAADR2),
+ enc_rdbreg(priv, ENC_MAADR3), enc_rdbreg(priv, ENC_MAADR4),
+ enc_rdbreg(priv, ENC_MAADR5), enc_rdbreg(priv, ENC_MAADR6));
}
#endif
#if 0 /* Sometimes useful */
static void enc_txdump(FAR struct enc_driver_s *priv)
{
- lib_lowprintf("Tx Registers:\n");
- lib_lowprintf(" EIE: %02x EIR: %02x ESTAT: %02x\n",
- enc_rdgreg(priv, ENC_EIE), enc_rdgreg(priv, ENC_EIR),);
- lib_lowprintf(" ESTAT: %02x ECON1: %02x\n",
- enc_rdgreg(priv, ENC_ESTAT), enc_rdgreg(priv, ENC_ECON1));
- lib_lowprintf(" ETXST: %02x %02x\n",
- enc_rdbreg(priv, ENC_ETXSTH), enc_rdbreg(priv, ENC_ETXSTL));
- lib_lowprintf(" ETXND: %02x %02x\n",
- enc_rdbreg(priv, ENC_ETXNDH), enc_rdbreg(priv, ENC_ETXNDL));
- lib_lowprintf(" MACON1: %02x MACON3: %02x MACON4: %02x\n",
- enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3),
- enc_rdbreg(priv, ENC_MACON4));
- lib_lowprintf(" MACON1: %02x MACON3: %02x MACON4: %02x\n",
- enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3),
- enc_rdbreg(priv, ENC_MACON4));
- lib_lowprintf(" MABBIPG: %02x MAIPG %02x %02x\n",
- enc_rdbreg(priv, ENC_MABBIPG), enc_rdbreg(priv, ENC_MAIPGH),
- enc_rdbreg(priv, ENC_MAIPGL));
- lib_lowprintf(" MACLCON1: %02x MACLCON2: %02x\n",
- enc_rdbreg(priv, ENC_MACLCON1), enc_rdbreg(priv, ENC_MACLCON2));
- lib_lowprintf(" MAMXFL: %02x %02x\n",
- enc_rdbreg(priv, ENC_MAMXFLH), enc_rdbreg(priv, ENC_MAMXFLL));
+ lowsyslog("Tx Registers:\n");
+ lowsyslog(" EIE: %02x EIR: %02x ESTAT: %02x\n",
+ enc_rdgreg(priv, ENC_EIE), enc_rdgreg(priv, ENC_EIR),);
+ lowsyslog(" ESTAT: %02x ECON1: %02x\n",
+ enc_rdgreg(priv, ENC_ESTAT), enc_rdgreg(priv, ENC_ECON1));
+ lowsyslog(" ETXST: %02x %02x\n",
+ enc_rdbreg(priv, ENC_ETXSTH), enc_rdbreg(priv, ENC_ETXSTL));
+ lowsyslog(" ETXND: %02x %02x\n",
+ enc_rdbreg(priv, ENC_ETXNDH), enc_rdbreg(priv, ENC_ETXNDL));
+ lowsyslog(" MACON1: %02x MACON3: %02x MACON4: %02x\n",
+ enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3),
+ enc_rdbreg(priv, ENC_MACON4));
+ lowsyslog(" MACON1: %02x MACON3: %02x MACON4: %02x\n",
+ enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3),
+ enc_rdbreg(priv, ENC_MACON4));
+ lowsyslog(" MABBIPG: %02x MAIPG %02x %02x\n",
+ enc_rdbreg(priv, ENC_MABBIPG), enc_rdbreg(priv, ENC_MAIPGH),
+ enc_rdbreg(priv, ENC_MAIPGL));
+ lowsyslog(" MACLCON1: %02x MACLCON2: %02x\n",
+ enc_rdbreg(priv, ENC_MACLCON1), enc_rdbreg(priv, ENC_MACLCON2));
+ lowsyslog(" MAMXFL: %02x %02x\n",
+ enc_rdbreg(priv, ENC_MAMXFLH), enc_rdbreg(priv, ENC_MAMXFLL));
}
#endif
diff --git a/nuttx/drivers/serial/Kconfig b/nuttx/drivers/serial/Kconfig
index a1e0dff49..119923a69 100644
--- a/nuttx/drivers/serial/Kconfig
+++ b/nuttx/drivers/serial/Kconfig
@@ -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
diff --git a/nuttx/drivers/serial/serial.c b/nuttx/drivers/serial/serial.c
index 8987f01b8..0fed1d6c5 100644
--- a/nuttx/drivers/serial/serial.c
+++ b/nuttx/drivers/serial/serial.c
@@ -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
@@ -158,7 +158,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);
@@ -208,18 +212,40 @@ static int uart_putxmitchar(FAR uart_dev_t *dev, int ch)
*/
flags = irqsave();
- dev->xmitwaiting = true;
+#ifdef CONFIG_SERIAL_REMOVABLE
+ /* Check if the removable device is no longer connected while we
+ * have interrupts off. We do not want the transition to occur
+ * as a race condition before we begin the wait.
+ */
+
+ if (dev->disconnected)
+ {
+ irqrestore(flags);
+ return -ENOTCONN;
+ }
+#endif
/* Wait for some characters to be sent from the buffer with the TX
* interrupt enabled. When the TX interrupt is enabled, uart_xmitchars
* should execute and remove some of the data from the TX buffer.
*/
+ dev->xmitwaiting = true;
uart_enabletxint(dev);
ret = uart_takesem(&dev->xmitsem, true);
uart_disabletxint(dev);
irqrestore(flags);
+#ifdef CONFIG_SERIAL_REMOVABLE
+ /* Check if the removable device was disconnected while we were
+ * waiting.
+ */
+
+ if (dev->disconnected)
+ {
+ return -ENOTCONN;
+ }
+#endif
/* Check if we were awakened by signal. */
if (ret < 0)
@@ -288,6 +314,17 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
if (up_interrupt_context() || getpid() == 0)
{
+#ifdef CONFIG_SERIAL_REMOVABLE
+ /* If the removable device is no longer connected, refuse to write to
+ * the device.
+ */
+
+ if (dev->disconnected)
+ {
+ return -ENOTCONN;
+ }
+#endif
+
/* up_putc() will be used to generate the output in a busy-wait loop.
* up_putc() is only available for the console device.
*/
@@ -317,6 +354,20 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
return ret;
}
+#ifdef CONFIG_SERIAL_REMOVABLE
+ /* If the removable device is no longer connected, refuse to write to the
+ * device. This check occurs after taking the xmit.sem because the
+ * disconnection event might have occurred while we were waiting for
+ * access to the transmit buffers.
+ */
+
+ if (dev->disconnected)
+ {
+ uart_givesem(&dev->xmit.sem);
+ return -ENOTCONN;
+ }
+#endif
+
/* Loop while we still have data to copy to the transmit buffer.
* we add data to the head of the buffer; uart_xmitchars takes the
* data from the end of the buffer.
@@ -392,9 +443,13 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
uart_givesem(&dev->xmit.sem);
- /* Were we interrupted by a signal? That should be the only condition that
- * uart_putxmitchar() should return an error.
- */
+ /* uart_putxmitchar() might return an error under one of two
+ * conditions: (1) The wait for buffer space might have been
+ * interrupted by a signal (ret should be -EINTR), or (2) if
+ * CONFIG_SERIAL_REMOVABLE is defined, then uart_putxmitchar()
+ * might also return if the serial device was disconnected
+ * (wtih -ENOTCONN).
+ */
if (ret < 0)
{
@@ -413,11 +468,11 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
}
else
{
- /* No data was transferred. Return -EINTR. The VFS layer will
- * set the errno value appropriately).
+ /* No data was transferred. Return the negated error. The VFS layer
+ * will set the errno value appropriately).
*/
- nread = -EINTR;
+ nread = -ret;
}
}
@@ -458,6 +513,22 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
while (recvd < buflen)
{
+#ifdef CONFIG_SERIAL_REMOVABLE
+ /* If the removable device is no longer connected, refuse to read any
+ * further from the device.
+ */
+
+ if (dev->disconnected)
+ {
+ if (recvd == 0)
+ {
+ recvd = -ENOTCONN;
+ }
+
+ break;
+ }
+#endif
+
/* Check if there is more data to return in the circular buffer.
* NOTE: Rx interrupt handling logic may aynchronously increment
* the head index but must not modify the tail index. The tail
@@ -548,6 +619,7 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
{
recvd = -EAGAIN;
}
+
break;
}
#else
@@ -599,20 +671,41 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
*/
flags = irqsave();
- dev->recvwaiting = true;
- uart_enablerxint(dev);
+#ifdef CONFIG_SERIAL_REMOVABLE
+ /* Check if the removable device is no longer connected while
+ * we have interrupts off. We do not want the transition to
+ * occur as a race condition before we begin the wait.
+ */
+
+ if (dev->disconnected)
+ {
+ uart_enablerxint(dev);
+ irqrestore(flags);
+ ret = -ENOTCONN;
+ break;
+ }
+#endif
/* Now wait with the Rx interrupt re-enabled. NuttX will
* automatically re-enable global interrupts when this thread
* goes to sleep.
*/
+ dev->recvwaiting = true;
+ uart_enablerxint(dev);
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 while
+ * we were waiting?
+ */
+#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
@@ -626,7 +719,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;
@@ -852,12 +949,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
@@ -867,11 +964,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);
@@ -971,6 +1077,7 @@ static int uart_close(FAR struct file *filep)
{
uart_shutdown(dev); /* Disable the UART */
}
+
irqrestore(flags);
uart_givesem(&dev->closesem);
@@ -1004,6 +1111,19 @@ static int uart_open(FAR struct file *filep)
return ret;
}
+#ifdef CONFIG_SERIAL_REMOVABLE
+ /* If the removable device is no longer connected, refuse to open the
+ * device. We check this after obtaining the close semaphore because
+ * we might have been waiting when the device was disconnected.
+ */
+
+ if (dev->disconnected)
+ {
+ ret = -ENOTCONN;
+ goto errout_with_sem;
+ }
+#endif
+
/* Start up serial port */
/* Increment the count of references to the device. */
@@ -1145,10 +1265,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);
}
@@ -1172,8 +1294,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);
}
@@ -1183,4 +1309,69 @@ 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)
+{
+ irqstate_t flags;
+
+ /* Is the device disconnected? */
+
+ flags = irqsave();
+ 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 occurred */
+
+ uart_pollnotify(dev, (POLLERR|POLLHUP));
+ }
+
+ irqrestore(flags);
+}
+#endif
+
+
diff --git a/nuttx/drivers/syslog/ramlog.c b/nuttx/drivers/syslog/ramlog.c
index b3a2ad0f5..08bbbfb59 100644
--- a/nuttx/drivers/syslog/ramlog.c
+++ b/nuttx/drivers/syslog/ramlog.c
@@ -726,10 +726,10 @@ int ramlog_sysloginit(void)
*
* Description:
* This is the low-level system logging interface. The debugging/syslogging
- * interfaces are lib_rawprintf() and lib_lowprinf(). The difference is
- * the lib_rawprintf() writes to fd=1 (stdout) and lib_lowprintf() uses
+ * interfaces are syslog() and lowsyslog(). The difference is that
+ * the syslog() internface writes to fd=1 (stdout) whereas lowsyslog() uses
* a lower level interface that works from interrupt handlers. This
- * function is a a low-level interface used to implement lib_lowprintf()
+ * function is a a low-level interface used to implement lowsyslog()
* when CONFIG_RAMLOG_SYSLOG=y and CONFIG_SYSLOG=y
*
****************************************************************************/
diff --git a/nuttx/drivers/usbdev/Kconfig b/nuttx/drivers/usbdev/Kconfig
index 70c7a04f0..0752bb791 100644
--- a/nuttx/drivers/usbdev/Kconfig
+++ b/nuttx/drivers/usbdev/Kconfig
@@ -148,12 +148,21 @@ config COMPOSITE_VERSIONNO
endif
menuconfig PL2303
- bool "Emulates the Prolific PL2303 serial/USB converter"
+ bool "Prolific PL2303 serial/USB converter emulation"
default n
+ select SERIAL_REMOVABLE
---help---
This logic emulates the Prolific PL2303 serial/USB converter
if PL2303
+
+config PL2303_CONSOLE
+ bool "PL2303 console device"
+ default n
+ ---help---
+ Register the USB device as /dev/console so that is will be used
+ as the console device.
+
config PL2303_EPINTIN
int "Logical endpoint numbers"
default 1
@@ -208,18 +217,27 @@ config PL2303_VENDORSTR
config PL2303_PRODUCTSTR
string "Product string"
- default "USBdev Serial"
+ default "PL2303 Emulation"
endif
menuconfig CDCACM
bool "USB Modem (CDC ACM) support"
default n
+ select SERIAL_REMOVABLE
---help---
Enables USB Modem (CDC ACM) support
if CDCACM
+
+config CDCACM_CONSOLE
+ bool "CDC/ACM console device"
+ default n
+ ---help---
+ Register the USB device as /dev/console so that is will be used
+ as the console device.
+
config CDCACM_COMPOSITE
- bool "CDCACM composite support"
+ bool "CDC/ACM composite support"
default n
depends on USBDEV_COMPOSITE
---help---
@@ -256,10 +274,10 @@ config CDCACM_EP0MAXPACKET
config CDCACM_EPINTIN
int "Hardware endpoint that supports interrupt IN operation"
- default 2
+ default 1
---help---
The logical 7-bit address of a hardware endpoint that supports
- interrupt IN operation. Default 2.
+ interrupt IN operation. Default 1.
config CDCACM_EPINTIN_FSSIZE
int "Endpoint in full speed size"
@@ -277,10 +295,10 @@ config CDCACM_EPINTIN_HSSIZE
config CDCACM_EPBULKOUT
int "Endpoint bulk out"
- default 0
+ default 3
---help---
The logical 7-bit address of a hardware endpoint that supports
- bulk OUT operation
+ bulk OUT operation. Default: 3
config CDCACM_EPBULKOUT_FSSIZE
int "Endpoint bulk out full speed size"
@@ -298,10 +316,10 @@ config CDCACM_EPBULKOUT_HSSIZE
config CDCACM_EPBULKIN
int "Endpoint bulk in"
- default 0
+ default 2
---help---
The logical 7-bit address of a hardware endpoint that supports
- bulk IN operation
+ bulk IN operation. Default: 2
config CDCACM_EPBULKIN_FSSIZE
int "Endpoint bulk in full speed size"
@@ -336,7 +354,7 @@ config CDCACM_RXBUFSIZE
Size of the serial receive/transmit buffers
config CDCACM_TXBUFSIZE
- bool "Transmit buffer size"
+ int "Transmit buffer size"
default 256
---help---
Size of the serial receive/transmit buffers
@@ -364,7 +382,7 @@ config CDCACM_VENDORSTR
config CDCACM_PRODUCTSTR
string "Product string"
- default "USBdev Serial"
+ default "CDC/ACM Serial"
endif
menuconfig USBMSC
@@ -479,8 +497,8 @@ config USBMSC_PRODUCTID
default 0x00
config USBMSC_PRODUCTSTR
- string "Mass stroage product string"
- default "Mass stroage"
+ string "Mass storage product string"
+ default "Mass Storage"
config USBMSC_VERSIONNO
hex "USB MSC Version Number"
diff --git a/nuttx/drivers/usbdev/cdcacm.c b/nuttx/drivers/usbdev/cdcacm.c
index 97c9d7c77..cb8679976 100644
--- a/nuttx/drivers/usbdev/cdcacm.c
+++ b/nuttx/drivers/usbdev/cdcacm.c
@@ -1,7 +1,7 @@
/****************************************************************************
* drivers/usbdev/cdcacm.c
*
- * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -188,6 +188,12 @@ static int cdcacm_setup(FAR struct usbdevclass_driver_s *driver,
size_t outlen);
static void cdcacm_disconnect(FAR struct usbdevclass_driver_s *driver,
FAR struct usbdev_s *dev);
+#ifdef CONFIG_SERIAL_REMOVABLE
+static void cdcacm_suspend(FAR struct usbdevclass_driver_s *driver,
+ FAR struct usbdev_s *dev);
+static void cdcacm_resume(FAR struct usbdevclass_driver_s *driver,
+ FAR struct usbdev_s *dev);
+#endif
/* UART Operations **********************************************************/
@@ -211,8 +217,13 @@ static const struct usbdevclass_driverops_s g_driverops =
cdcacm_unbind, /* unbind */
cdcacm_setup, /* setup */
cdcacm_disconnect, /* disconnect */
+#ifdef CONFIG_SERIAL_REMOVABLE
+ cdcacm_suspend, /* suspend */
+ cdcacm_resume, /* resume */
+#else
NULL, /* suspend */
NULL, /* resume */
+#endif
};
/* Serial port **************************************************************/
@@ -570,6 +581,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 +750,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:
@@ -823,6 +852,7 @@ static void cdcacm_rdcomplete(FAR struct usbdev_ep_s *ep,
{
usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_RDSUBMIT), (uint16_t)-req->result);
}
+
irqrestore(flags);
}
@@ -932,6 +962,7 @@ static int cdcacm_bind(FAR struct usbdevclass_driver_s *driver,
ret = -ENOMEM;
goto errout;
}
+
priv->ctrlreq->callback = cdcacm_ep0incomplete;
/* Pre-allocate all endpoints... the endpoints will not be functional
@@ -1575,12 +1606,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;
@@ -1596,6 +1635,79 @@ static void cdcacm_disconnect(FAR struct usbdevclass_driver_s *driver,
}
/****************************************************************************
+ * Name: cdcacm_suspend
+ *
+ * Description:
+ * Handle the USB suspend event.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SERIAL_REMOVABLE
+static void cdcacm_suspend(FAR struct usbdevclass_driver_s *driver,
+ FAR struct usbdev_s *dev)
+{
+ FAR struct cdcacm_dev_s *priv;
+
+ usbtrace(TRACE_CLASSSUSPEND, 0);
+
+#ifdef CONFIG_DEBUG
+ if (!driver || !dev)
+ {
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_INVALIDARG), 0);
+ return;
+ }
+#endif
+
+ /* Extract reference to private data */
+
+ priv = ((FAR struct cdcacm_driver_s*)driver)->dev;
+
+ /* And let the "upper half" driver now that we are suspended */
+
+ uart_connected(&priv->serdev, false);
+}
+#endif
+
+/****************************************************************************
+ * Name: cdcacm_resume
+ *
+ * Description:
+ * Handle the USB resume event.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SERIAL_REMOVABLE
+static void cdcacm_resume(FAR struct usbdevclass_driver_s *driver,
+ FAR struct usbdev_s *dev)
+{
+ FAR struct cdcacm_dev_s *priv;
+
+ usbtrace(TRACE_CLASSRESUME, 0);
+
+#ifdef CONFIG_DEBUG
+ if (!driver || !dev)
+ {
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_INVALIDARG), 0);
+ return;
+ }
+#endif
+
+ /* Extract reference to private data */
+
+ priv = ((FAR struct cdcacm_driver_s*)driver)->dev;
+
+ /* Are we still configured? */
+
+ if (priv->config != CDCACM_CONFIGIDNONE)
+ {
+ /* Yes.. let the "upper half" know that have resumed */
+
+ uart_connected(&priv->serdev, true);
+ }
+}
+#endif
+
+/****************************************************************************
* Serial Device Methods
****************************************************************************/
@@ -2045,12 +2157,17 @@ int cdcacm_classobject(int minor, FAR struct usbdevclass_driver_s **classdev)
/* Initialize the serial driver sub-structure */
- priv->serdev.recv.size = CONFIG_CDCACM_RXBUFSIZE;
- priv->serdev.recv.buffer = priv->rxbuffer;
- priv->serdev.xmit.size = CONFIG_CDCACM_TXBUFSIZE;
- priv->serdev.xmit.buffer = priv->txbuffer;
- priv->serdev.ops = &g_uartops;
- priv->serdev.priv = priv;
+ /* 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;
+ priv->serdev.xmit.buffer = priv->txbuffer;
+ priv->serdev.ops = &g_uartops;
+ priv->serdev.priv = priv;
/* Initialize the USB class driver structure */
@@ -2148,7 +2265,7 @@ int cdcacm_initialize(int minor, FAR void **handle)
*
* Description:
* Un-initialize the USB storage class driver. This function is used
- * internally by the USB composite driver to unitialized the CDC/ACM
+ * internally by the USB composite driver to unitialize the CDC/ACM
* driver. This same interface is available (with an untyped input
* parameter) when the CDC/ACM driver is used standalone.
*
diff --git a/nuttx/drivers/usbdev/pl2303.c b/nuttx/drivers/usbdev/pl2303.c
index d10539fa7..7b07a9cba 100644
--- a/nuttx/drivers/usbdev/pl2303.c
+++ b/nuttx/drivers/usbdev/pl2303.c
@@ -343,6 +343,12 @@ static int usbclass_setup(FAR struct usbdevclass_driver_s *driver,
size_t outlen);
static void usbclass_disconnect(FAR struct usbdevclass_driver_s *driver,
FAR struct usbdev_s *dev);
+#ifdef CONFIG_SERIAL_REMOVABLE
+static void usbclass_suspend(FAR struct usbdevclass_driver_s *driver,
+ FAR struct usbdev_s *dev);
+static void usbclass_resume(FAR struct usbdevclass_driver_s *driver,
+ FAR struct usbdev_s *dev);
+#endif
/* Serial port *************************************************************/
@@ -366,8 +372,13 @@ static const struct usbdevclass_driverops_s g_driverops =
usbclass_unbind, /* unbind */
usbclass_setup, /* setup */
usbclass_disconnect, /* disconnect */
+#ifdef CONFIG_SERIAL_REMOVABLE
+ usbclass_suspend, /* suspend */
+ usbclass_resume, /* resume */
+#else
NULL, /* suspend */
NULL, /* resume */
+#endif
};
/* Serial port *************************************************************/
@@ -983,6 +994,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 +1131,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 +1873,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;
@@ -1863,6 +1900,79 @@ static void usbclass_disconnect(FAR struct usbdevclass_driver_s *driver,
}
/****************************************************************************
+ * Name: usbclass_suspend
+ *
+ * Description:
+ * Handle the USB suspend event.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SERIAL_REMOVABLE
+static void usbclass_suspend(FAR struct usbdevclass_driver_s *driver,
+ FAR struct usbdev_s *dev)
+{
+ FAR struct cdcacm_dev_s *priv;
+
+ usbtrace(TRACE_CLASSSUSPEND, 0);
+
+#ifdef CONFIG_DEBUG
+ if (!driver || !dev)
+ {
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_INVALIDARG), 0);
+ return;
+ }
+#endif
+
+ /* Extract reference to private data */
+
+ priv = ((FAR struct cdcacm_driver_s*)driver)->dev;
+
+ /* And let the "upper half" driver now that we are suspended */
+
+ uart_connected(&priv->serdev, false);
+}
+#endif
+
+/****************************************************************************
+ * Name: usbclass_resume
+ *
+ * Description:
+ * Handle the USB resume event.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SERIAL_REMOVABLE
+static void usbclass_resume(FAR struct usbdevclass_driver_s *driver,
+ FAR struct usbdev_s *dev)
+{
+ FAR struct cdcacm_dev_s *priv;
+
+ usbtrace(TRACE_CLASSRESUME, 0);
+
+#ifdef CONFIG_DEBUG
+ if (!driver || !dev)
+ {
+ usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_INVALIDARG), 0);
+ return;
+ }
+#endif
+
+ /* Extract reference to private data */
+
+ priv = ((FAR struct cdcacm_driver_s*)driver)->dev;
+
+ /* Are we still configured? */
+
+ if (priv->config != PL2303_CONFIGIDNONE)
+ {
+ /* Yes.. let the "upper half" know that have resumed */
+
+ uart_connected(&priv->serdev, true);
+ }
+}
+#endif
+
+/****************************************************************************
* Serial Device Methods
****************************************************************************/
@@ -2185,12 +2295,15 @@ int usbdev_serialinitialize(int minor)
/* Initialize the serial driver sub-structure */
- priv->serdev.recv.size = CONFIG_PL2303_RXBUFSIZE;
- priv->serdev.recv.buffer = priv->rxbuffer;
- priv->serdev.xmit.size = CONFIG_PL2303_TXBUFSIZE;
- priv->serdev.xmit.buffer = priv->txbuffer;
- priv->serdev.ops = &g_uartops;
- priv->serdev.priv = priv;
+#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;
+ priv->serdev.xmit.buffer = priv->txbuffer;
+ priv->serdev.ops = &g_uartops;
+ priv->serdev.priv = priv;
/* Initialize the USB class driver structure */
diff --git a/nuttx/drivers/usbdev/usbdev_trace.c b/nuttx/drivers/usbdev/usbdev_trace.c
index c8cc09292..c332c1358 100644
--- a/nuttx/drivers/usbdev/usbdev_trace.c
+++ b/nuttx/drivers/usbdev/usbdev_trace.c
@@ -168,9 +168,9 @@ void usbtrace(uint16_t event, uint16_t value)
}
}
#else
- /* Just print the data using lib_lowprintf */
+ /* Just print the data using lowsyslog */
- usbtrace_trprintf((trprintf_t)lib_lowprintf, event, value);
+ usbtrace_trprintf((trprintf_t)lowsyslog, event, value);
#endif
}
irqrestore(flags);
diff --git a/nuttx/drivers/usbdev/usbmsc.h b/nuttx/drivers/usbdev/usbmsc.h
index 883a49951..da35ae923 100644
--- a/nuttx/drivers/usbdev/usbmsc.h
+++ b/nuttx/drivers/usbdev/usbmsc.h
@@ -199,9 +199,9 @@
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
# ifdef CONFIG_ARCH_LOWPUTC
-# define dbgprintf(format, arg...) lib_lowprintf(format, ##arg)
+# define dbgprintf(format, arg...) lowsyslog(format, ##arg)
# else
-# define dbgprintf(format, arg...) lib_rawprintf(format, ##arg)
+# define dbgprintf(format, arg...) syslog(format, ##arg)
# endif
# else
# define dbgprintf(x...)
@@ -209,9 +209,9 @@
#else
# ifdef CONFIG_DEBUG
# ifdef CONFIG_ARCH_LOWPUTC
-# define dbgprintf lib_lowprintf
+# define dbgprintf lowsyslog
# else
-# define dbgprintf lib_rawprintf
+# define dbgprintf syslog
# endif
# else
# define dbgprintf (void)