aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--Makefile15
-rw-r--r--apps/drivers/px4io/px4io.cpp1
-rw-r--r--apps/drivers/px4io/uploader.cpp6
-rw-r--r--apps/px4io/dsm.c26
-rw-r--r--apps/px4io/mixer.c25
-rw-r--r--apps/px4io/px4io.c2
-rw-r--r--apps/px4io/px4io.h5
-rw-r--r--apps/px4io/sbus.c30
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_serial.c200
-rw-r--r--nuttx/drivers/serial/serial.c287
-rw-r--r--nuttx/include/nuttx/fs/ioctl.h4
-rw-r--r--nuttx/include/nuttx/serial/serial.h11
-rw-r--r--nuttx/include/termios.h30
13 files changed, 469 insertions, 173 deletions
diff --git a/Makefile b/Makefile
index 801256cfe..d9469bb49 100644
--- a/Makefile
+++ b/Makefile
@@ -114,10 +114,21 @@ endif
upload: $(FIRMWARE_BUNDLE) $(UPLOADER)
@python -u $(UPLOADER) --port $(SERIAL_PORTS) $(FIRMWARE_BUNDLE)
-
+
+#
+# JTAG firmware uploading with OpenOCD
+#
+ifeq ($(JTAGCONFIG),)
+JTAGCONFIG=interface/olimex-jtag-tiny.cfg
+endif
+
upload-jtag-px4fmu:
@echo Attempting to flash PX4FMU board via JTAG
- @openocd -f interface/olimex-jtag-tiny.cfg -f ../Bootloader/stm32f4x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4fmu_bl.elf" -c "reset run" -c shutdown
+ @openocd -f $(JTAGCONFIG) -f ../Bootloader/stm32f4x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4fmu_bl.elf" -c "reset run" -c shutdown
+
+upload-jtag-px4io: all
+ @echo Attempting to flash PX4IO board via JTAG
+ @openocd -f $(JTAGCONFIG) -f ../Bootloader/stm32f1x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4io_bl.elf" -c "reset run" -c shutdown
#
# Hacks and fixups
diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp
index 07a39c881..49ad80943 100644
--- a/apps/drivers/px4io/px4io.cpp
+++ b/apps/drivers/px4io/px4io.cpp
@@ -338,7 +338,6 @@ PX4IO::task_main()
/* this would be bad... */
if (ret < 0) {
log("poll error %d", errno);
- usleep(1000000);
continue;
}
diff --git a/apps/drivers/px4io/uploader.cpp b/apps/drivers/px4io/uploader.cpp
index 5669aeb01..8b354ff60 100644
--- a/apps/drivers/px4io/uploader.cpp
+++ b/apps/drivers/px4io/uploader.cpp
@@ -189,8 +189,10 @@ PX4IO_Uploader::drain()
int ret;
do {
- ret = recv(c, 10);
- //log("discard 0x%02x", c);
+ ret = recv(c, 250);
+ if (ret == OK) {
+ //log("discard 0x%02x", c);
+ }
} while (ret == OK);
}
diff --git a/apps/px4io/dsm.c b/apps/px4io/dsm.c
index 2c2e09905..744dac3d6 100644
--- a/apps/px4io/dsm.c
+++ b/apps/px4io/dsm.c
@@ -278,6 +278,7 @@ dsm_decode(hrt_abstime frame_time)
last_frame_time = frame_time;
if (channel_shift == 0) {
dsm_guess_format(false);
+ system_state.dsm_input_ok = false;
return;
}
@@ -292,6 +293,10 @@ dsm_decode(hrt_abstime frame_time)
* seven channels are being transmitted.
*/
+ const unsigned dsm_chancount = (DSM_FRAME_CHANNELS < PX4IO_INPUT_CHANNELS) ? DSM_FRAME_CHANNELS : PX4IO_INPUT_CHANNELS;
+
+ uint16_t dsm_channels[dsm_chancount];
+
for (unsigned i = 0; i < DSM_FRAME_CHANNELS; i++) {
uint8_t *dp = &frame[2 + (2 * i)];
@@ -314,10 +319,23 @@ dsm_decode(hrt_abstime frame_time)
value /= 2;
/* stuff the decoded channel into the PPM input buffer */
- ppm_buffer[channel] = 988 + value;
+ dsm_channels[channel] = 988 + value;
}
- /* and note that we have received data from the R/C controller */
- /* XXX failsafe will cause problems here - need a strategy for detecting it */
- ppm_last_valid_decode = frame_time;
+ /* DSM input is valid */
+ system_state.dsm_input_ok = true;
+
+ /* check if no S.BUS data is available */
+ if (!system_state.sbus_input_ok) {
+
+ for (unsigned i = 0; i < dsm_chancount; i++) {
+ system_state.rc_channel_data[i] = dsm_channels[i];
+ }
+
+ /* and note that we have received data from the R/C controller */
+ /* XXX failsafe will cause problems here - need a strategy for detecting it */
+ system_state.rc_channels_timestamp = frame_time;
+ system_state.rc_channels = dsm_chancount;
+ system_state.fmu_report_due = true;
+ }
}
diff --git a/apps/px4io/mixer.c b/apps/px4io/mixer.c
index fb553bc6e..483e9fe4d 100644
--- a/apps/px4io/mixer.c
+++ b/apps/px4io/mixer.c
@@ -170,17 +170,26 @@ mixer_update(int mixer, uint16_t *inputs, int input_count)
static void
mixer_get_rc_input(void)
{
-
/* if we haven't seen any new data in 200ms, assume we have lost input and tell FMU */
if ((hrt_absolute_time() - ppm_last_valid_decode) > 200000) {
- system_state.rc_channels = 0;
- system_state.fmu_report_due = true;
+
+ /* input was ok and timed out, mark as update */
+ if (system_state.ppm_input_ok) {
+ system_state.ppm_input_ok = false;
+ system_state.fmu_report_due = true;
+ }
return;
}
- /* otherwise, copy channel data */
- system_state.rc_channels = ppm_decoded_channels;
- for (unsigned i = 0; i < ppm_decoded_channels; i++)
- system_state.rc_channel_data[i] = ppm_buffer[i];
- system_state.fmu_report_due = true;
+ /* mark PPM as valid */
+ system_state.ppm_input_ok = true;
+
+ /* check if no DSM and S.BUS data is available */
+ if (!system_state.sbus_input_ok && !system_state.dsm_input_ok) {
+ /* otherwise, copy channel data */
+ system_state.rc_channels = ppm_decoded_channels;
+ for (unsigned i = 0; i < ppm_decoded_channels; i++)
+ system_state.rc_channel_data[i] = ppm_buffer[i];
+ system_state.fmu_report_due = true;
+ }
}
diff --git a/apps/px4io/px4io.c b/apps/px4io/px4io.c
index bba236322..77524797f 100644
--- a/apps/px4io/px4io.c
+++ b/apps/px4io/px4io.c
@@ -58,6 +58,8 @@ struct sys_state_s system_state;
int user_start(int argc, char *argv[])
{
+ /* reset all to zero */
+ memset(&system_state, 0, sizeof(system_state));
/* configure the high-resolution time/callout interface */
hrt_init();
diff --git a/apps/px4io/px4io.h b/apps/px4io/px4io.h
index 21c1482be..483b9bcc8 100644
--- a/apps/px4io/px4io.h
+++ b/apps/px4io/px4io.h
@@ -72,11 +72,16 @@ struct sys_state_s
bool armed; /* IO armed */
bool arm_ok; /* FMU says OK to arm */
+ bool ppm_input_ok; /* valid PPM input data */
+ bool dsm_input_ok; /* valid Spektrum DSM data */
+ bool sbus_input_ok; /* valid Futaba S.Bus data */
+
/*
* Data from the remote control input(s)
*/
int rc_channels;
uint16_t rc_channel_data[PX4IO_INPUT_CHANNELS];
+ uint64_t rc_channels_timestamp;
/*
* Control signals from FMU.
diff --git a/apps/px4io/sbus.c b/apps/px4io/sbus.c
index 39d2c4939..c3949f2b0 100644
--- a/apps/px4io/sbus.c
+++ b/apps/px4io/sbus.c
@@ -50,6 +50,7 @@
#define DEBUG
#include "px4io.h"
#include "protocol.h"
+#include "debug.h"
#define SBUS_FRAME_SIZE 25
#define SBUS_INPUT_CHANNELS 16
@@ -192,21 +193,22 @@ static void
sbus_decode(hrt_abstime frame_time)
{
/* check frame boundary markers to avoid out-of-sync cases */
- if ((frame[0] != 0xf0) || (frame[24] != 0x00)) {
+ if ((frame[0] != 0x0f) || (frame[24] != 0x00)) {
sbus_frame_drops++;
+ system_state.sbus_input_ok = false;
return;
}
/* if the failsafe bit is set, we consider that a loss of RX signal */
- if (frame[23] & (1 << 4))
+ if (frame[23] & (1 << 4)) {
+ system_state.sbus_input_ok = false;
return;
+ }
- /* use the decoder matrix to extract channel data */
- for (unsigned channel = 0; channel < SBUS_INPUT_CHANNELS; channel++) {
-
- if (channel >= PX4IO_INPUT_CHANNELS)
- break;
+ unsigned chancount = (PX4IO_INPUT_CHANNELS > 16) ? 16 : PX4IO_INPUT_CHANNELS;
+ /* use the decoder matrix to extract channel data */
+ for (unsigned channel = 0; channel < chancount; channel++) {
unsigned value = 0;
for (unsigned pick = 0; pick < 3; pick++) {
@@ -222,8 +224,18 @@ sbus_decode(hrt_abstime frame_time)
}
}
/* convert 0-2048 values to 1000-2000 ppm encoding in a very sloppy fashion */
- ppm_buffer[channel] = (value / 2) + 998;
+ system_state.rc_channel_data[channel] = (value / 2) + 998;
}
+
+ if (PX4IO_INPUT_CHANNELS >= 18) {
+ /* decode two switch channels */
+ chancount = 18;
+ }
+
+ system_state.rc_channels = chancount;
+ system_state.sbus_input_ok = true;
+ system_state.fmu_report_due = true;
+
/* and note that we have received data from the R/C controller */
- ppm_last_valid_decode = frame_time;
+ system_state.rc_channels_timestamp = frame_time;
}
diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c
index ff18d208b..0868c3cd3 100644
--- a/nuttx/arch/arm/src/stm32/stm32_serial.c
+++ b/nuttx/arch/arm/src/stm32/stm32_serial.c
@@ -185,11 +185,15 @@ struct up_dev_s
uint8_t parity; /* 0=none, 1=odd, 2=even */
uint8_t bits; /* Number of bits (7 or 8) */
bool stopbits2; /* True: Configure with 2 stop bits instead of 1 */
+ bool iflow; /* input flow control (RTS) enabled */
+ bool oflow; /* output flow control (CTS) enabled */
uint32_t baud; /* Configured baud */
#else
const uint8_t parity; /* 0=none, 1=odd, 2=even */
const uint8_t bits; /* Number of bits (7 or 8) */
const bool stopbits2; /* True: Configure with 2 stop bits instead of 1 */
+ const bool iflow; /* input flow control (RTS) enabled */
+ const bool oflow; /* output flow control (CTS) enabled */
const uint32_t baud; /* Configured baud */
#endif
@@ -221,7 +225,7 @@ struct up_dev_s
* Private Function Prototypes
****************************************************************************/
-static void up_setspeed(struct uart_dev_s *dev);
+static void up_set_format(struct uart_dev_s *dev);
static int up_setup(struct uart_dev_s *dev);
static void up_shutdown(struct uart_dev_s *dev);
static int up_attach(struct uart_dev_s *dev);
@@ -393,6 +397,8 @@ static struct up_dev_s g_usart1priv =
.parity = CONFIG_USART1_PARITY,
.bits = CONFIG_USART1_BITS,
.stopbits2 = CONFIG_USART1_2STOP,
+ .iflow = false,
+ .oflow = false,
.baud = CONFIG_USART1_BAUD,
.apbclock = STM32_PCLK2_FREQUENCY,
.usartbase = STM32_USART1_BASE,
@@ -444,6 +450,8 @@ static struct up_dev_s g_usart2priv =
.parity = CONFIG_USART2_PARITY,
.bits = CONFIG_USART2_BITS,
.stopbits2 = CONFIG_USART2_2STOP,
+ .iflow = false,
+ .oflow = false,
.baud = CONFIG_USART2_BAUD,
.apbclock = STM32_PCLK1_FREQUENCY,
.usartbase = STM32_USART2_BASE,
@@ -495,6 +503,8 @@ static struct up_dev_s g_usart3priv =
.parity = CONFIG_USART3_PARITY,
.bits = CONFIG_USART3_BITS,
.stopbits2 = CONFIG_USART3_2STOP,
+ .iflow = false,
+ .oflow = false,
.baud = CONFIG_USART3_BAUD,
.apbclock = STM32_PCLK1_FREQUENCY,
.usartbase = STM32_USART3_BASE,
@@ -546,17 +556,15 @@ static struct up_dev_s g_uart4priv =
.parity = CONFIG_UART4_PARITY,
.bits = CONFIG_UART4_BITS,
.stopbits2 = CONFIG_UART4_2STOP,
+ .iflow = false,
+ .oflow = false,
.baud = CONFIG_UART4_BAUD,
.apbclock = STM32_PCLK1_FREQUENCY,
.usartbase = STM32_UART4_BASE,
.tx_gpio = GPIO_UART4_TX,
.rx_gpio = GPIO_UART4_RX,
-#ifdef GPIO_UART4_CTS
- .cts_gpio = GPIO_UART4_CTS,
-#endif
-#ifdef GPIO_UART4_RTS
- .rts_gpio = GPIO_UART4_RTS,
-#endif
+ .cts_gpio = 0, /* flow control not supported on this port */
+ .rts_gpio = 0, /* flow control not supported on this port */
#ifdef CONFIG_UART4_RXDMA
.rxdma_channel = DMAMAP_UART4_RX,
.rxfifo = g_uart4rxfifo,
@@ -597,17 +605,15 @@ static struct up_dev_s g_uart5priv =
.parity = CONFIG_UART5_PARITY,
.bits = CONFIG_UART5_BITS,
.stopbits2 = CONFIG_UART5_2STOP,
+ .iflow = false,
+ .oflow = false,
.baud = CONFIG_UART5_BAUD,
.apbclock = STM32_PCLK1_FREQUENCY,
.usartbase = STM32_UART5_BASE,
.tx_gpio = GPIO_UART5_TX,
.rx_gpio = GPIO_UART5_RX,
-#ifdef GPIO_UART5_CTS
- .cts_gpio = GPIO_UART5_CTS,
-#endif
-#ifdef GPIO_UART5_RTS
- .rts_gpio = GPIO_UART5_RTS,
-#endif
+ .cts_gpio = 0, /* flow control not supported on this port */
+ .rts_gpio = 0, /* flow control not supported on this port */
#ifdef CONFIG_UART5_RXDMA
.rxdma_channel = DMAMAP_UART5_RX,
.rxfifo = g_uart5rxfifo,
@@ -648,6 +654,8 @@ static struct up_dev_s g_usart6priv =
.parity = CONFIG_USART6_PARITY,
.bits = CONFIG_USART6_BITS,
.stopbits2 = CONFIG_USART6_2STOP,
+ .iflow = false,
+ .oflow = false,
.baud = CONFIG_USART6_BAUD,
.apbclock = STM32_PCLK2_FREQUENCY,
.usartbase = STM32_USART6_BASE,
@@ -812,21 +820,22 @@ static int up_dma_nextrx(struct up_dev_s *priv)
#endif
/****************************************************************************
- * Name: up_setspeed
+ * Name: up_set_format
*
* Description:
- * Set the serial line speed.
+ * Set the serial line format and speed.
*
****************************************************************************/
#ifndef CONFIG_SUPPRESS_UART_CONFIG
-static void up_setspeed(struct uart_dev_s *dev)
+static void up_set_format(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
uint32_t usartdiv32;
uint32_t mantissa;
uint32_t fraction;
uint32_t brr;
+ uint32_t regval;
/* Configure the USART Baud Rate. The baud rate for the receiver and
* transmitter (Rx and Tx) are both set to the same value as programmed
@@ -844,20 +853,64 @@ static void up_setspeed(struct uart_dev_s *dev)
* usartdiv32 = 32 * usartdiv = fCK / (baud/2)
*/
- usartdiv32 = priv->apbclock / (priv->baud >> 1);
+ usartdiv32 = priv->apbclock / (priv->baud >> 1);
+
+ /* The mantissa part is then */
+
+ mantissa = usartdiv32 >> 5;
+ brr = mantissa << USART_BRR_MANT_SHIFT;
+
+ /* The fractional remainder (with rounding) */
+
+ fraction = (usartdiv32 - (mantissa << 5) + 1) >> 1;
+ brr |= fraction << USART_BRR_FRAC_SHIFT;
+ up_serialout(priv, STM32_USART_BRR_OFFSET, brr);
+
+ /* Configure parity mode */
- /* The mantissa part is then */
+ regval = up_serialin(priv, STM32_USART_CR1_OFFSET);
+ regval &= ~(USART_CR1_PCE|USART_CR1_PS);
- mantissa = usartdiv32 >> 5;
- brr = mantissa << USART_BRR_MANT_SHIFT;
+ if (priv->parity == 1) /* Odd parity */
+ {
+ regval |= (USART_CR1_PCE|USART_CR1_PS);
+ }
+ else if (priv->parity == 2) /* Even parity */
+ {
+ regval |= USART_CR1_PCE;
+ }
- /* The fractional remainder (with rounding) */
+ up_serialout(priv, STM32_USART_CR1_OFFSET, regval);
+
+ /* Configure STOP bits */
+
+ regval = up_serialin(priv, STM32_USART_CR2_OFFSET);
+ regval &= ~(USART_CR2_STOP_MASK);
+
+ if (priv->stopbits2)
+ {
+ regval |= USART_CR2_STOP2;
+ }
+ up_serialout(priv, STM32_USART_CR2_OFFSET, regval);
+
+ /* Configure hardware flow control */
+
+ regval = up_serialin(priv, STM32_USART_CR3_OFFSET);
+ regval &= ~(USART_CR3_CTSE|USART_CR3_RTSE);
+
+ if (priv->iflow && (priv->rts_gpio != 0))
+ {
+ regval |= USART_CR3_RTSE;
+ }
+ if (priv->oflow && (priv->cts_gpio != 0))
+ {
+ regval |= USART_CR3_CTSE;
+ }
+
+ up_serialout(priv, STM32_USART_CR3_OFFSET, regval);
- fraction = (usartdiv32 - (mantissa << 5) + 1) >> 1;
- brr |= fraction << USART_BRR_FRAC_SHIFT;
- up_serialout(priv, STM32_USART_BRR_OFFSET, brr);
}
-#endif
+#endif /* CONFIG_SUPPRESS_UART_CONFIG */
/****************************************************************************
* Name: up_setup
@@ -894,43 +947,28 @@ static int up_setup(struct uart_dev_s *dev)
}
/* Configure CR2 */
- /* Clear STOP, CLKEN, CPOL, CPHA, LBCL, and interrupt enable bits */
+ /* Clear CLKEN, CPOL, CPHA, LBCL, and interrupt enable bits */
regval = up_serialin(priv, STM32_USART_CR2_OFFSET);
- regval &= ~(USART_CR2_STOP_MASK|USART_CR2_CLKEN|USART_CR2_CPOL|
+ regval &= ~(USART_CR2_CLKEN|USART_CR2_CPOL|
USART_CR2_CPHA|USART_CR2_LBCL|USART_CR2_LBDIE);
- /* Configure STOP bits */
-
- if (priv->stopbits2)
- {
- regval |= USART_CR2_STOP2;
- }
up_serialout(priv, STM32_USART_CR2_OFFSET, regval);
/* Configure CR1 */
- /* Clear M, PCE, PS, TE, REm and all interrupt enable bits */
+ /* Clear M, TE, REm and all interrupt enable bits */
regval = up_serialin(priv, STM32_USART_CR1_OFFSET);
- regval &= ~(USART_CR1_M|USART_CR1_PCE|USART_CR1_PS|USART_CR1_TE|
+ regval &= ~(USART_CR1_M|USART_CR1_TE|
USART_CR1_RE|USART_CR1_ALLINTS);
- /* Configure word length and parity mode */
+ /* Configure word length */
if (priv->bits == 9) /* Default: 1 start, 8 data, n stop */
{
regval |= USART_CR1_M; /* 1 start, 9 data, n stop */
}
- if (priv->parity == 1) /* Odd parity */
- {
- regval |= (USART_CR1_PCE|USART_CR1_PS);
- }
- else if (priv->parity == 2) /* Even parity */
- {
- regval |= USART_CR1_PCE;
- }
-
up_serialout(priv, STM32_USART_CR1_OFFSET, regval);
/* Configure CR3 */
@@ -943,16 +981,17 @@ static int up_setup(struct uart_dev_s *dev)
up_serialout(priv, STM32_USART_CR3_OFFSET, regval);
- /* Configure the USART Baud Rate. */
+ /* Configure the USART line format and speed. */
- up_setspeed(dev);
+ up_set_format(dev);
/* Enable Rx, Tx, and the USART */
regval = up_serialin(priv, STM32_USART_CR1_OFFSET);
regval |= (USART_CR1_UE|USART_CR1_TE|USART_CR1_RE);
up_serialout(priv, STM32_USART_CR1_OFFSET, regval);
-#endif
+
+#endif /* CONFIG_SUPPRESS_UART_CONFIG */
/* Set up the cached interrupt enables value */
@@ -1279,12 +1318,21 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
break;
}
- /* TODO: Other termios fields are not yet returned.
- * Note that only cfsetospeed is not necessary because we have
- * knowledge that only one speed is supported.
+ cfsetispeed(termiosp, priv->baud);
+
+ /* Note that since we only support 8/9 bit modes and
+ * there is no way to report 9-bit mode, we always claim 8.
*/
- cfsetispeed(termiosp, priv->baud);
+ termiosp->c_cflag =
+ ((priv->parity != 0) ? PARENB : 0) |
+ ((priv->parity == 1) ? PARODD : 0) |
+ ((priv->stopbits2) ? CSTOPB : 0) |
+ ((priv->oflow) ? CCTS_OFLOW : 0) |
+ ((priv->iflow) ? CRTS_IFLOW : 0) |
+ CS8;
+
+ /* TODO: CCTS_IFLOW, CCTS_OFLOW */
}
break;
@@ -1298,16 +1346,48 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
break;
}
- /* TODO: Handle other termios settings.
- * Note that only cfgetispeed is used besued we have knowledge
+ /* Perform some sanity checks before accepting any changes */
+
+ if (((termiosp->c_cflag & CSIZE) != CS8) ||
+ ((termiosp->c_cflag & CCTS_OFLOW) && (priv->cts_gpio == 0)) ||
+ ((termiosp->c_cflag & CRTS_IFLOW) && (priv->rts_gpio == 0)))
+ {
+ ret = -EINVAL;
+ break;
+ }
+
+ if (termiosp->c_cflag & PARENB)
+ {
+ priv->parity = (termiosp->c_cflag & PARODD) ? 1 : 2;
+ }
+ else
+ {
+ priv->parity = 0;
+ }
+
+ priv->stopbits2 = (termiosp->c_cflag & CSTOPB) != 0;
+ priv->oflow = (termiosp->c_cflag & CCTS_OFLOW) != 0;
+ priv->iflow = (termiosp->c_cflag & CRTS_IFLOW) != 0;
+
+ /* Note that since there is no way to request 9-bit mode
+ * and no way to support 5/6/7-bit modes, we ignore them
+ * all here.
+ */
+
+ /* Note that only cfgetispeed is used because we have knowledge
* that only one speed is supported.
*/
priv->baud = cfgetispeed(termiosp);
- up_setspeed(dev);
+
+ /* effect the changes immediately - note that we do not implement
+ * TCSADRAIN / TCSAFLUSH
+ */
+
+ up_set_format(dev);
}
break;
-#endif
+#endif /* CONFIG_SERIAL_TERMIOS */
#ifdef CONFIG_USART_BREAKS
case TIOCSBRK: /* BSD compatibility: Turn break on, unconditionally */
@@ -1945,10 +2025,10 @@ void stm32_serial_dma_poll(void)
int up_putc(int ch)
{
#if CONSOLE_UART > 0
-// struct up_dev_s *priv = uart_devs[CONSOLE_UART - 1];
-// uint16_t ie;
+ struct up_dev_s *priv = uart_devs[CONSOLE_UART - 1];
+ uint16_t ie;
-// up_disableusartint(priv, &ie);
+ up_disableusartint(priv, &ie);
/* Check for LF */
@@ -1960,7 +2040,7 @@ int up_putc(int ch)
}
up_lowputc(ch);
-// up_restoreusartint(priv, ie);
+ up_restoreusartint(priv, ie);
#endif
return ch;
}
diff --git a/nuttx/drivers/serial/serial.c b/nuttx/drivers/serial/serial.c
index 40011199b..c650da5db 100644
--- a/nuttx/drivers/serial/serial.c
+++ b/nuttx/drivers/serial/serial.c
@@ -252,7 +252,7 @@ static inline ssize_t uart_irqwrite(FAR uart_dev_t *dev, FAR const char *buffer,
{
int ch = *buffer++;
- /* If this is the console, then we should replace LF with CR-LF */
+ /* assume that this is console text output and always do \n -> \r\n conversion */
if (ch == '\n')
{
@@ -277,6 +277,7 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
FAR uart_dev_t *dev = inode->i_private;
ssize_t nread = buflen;
int ret;
+ char ch;
/* 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
@@ -308,8 +309,7 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
if (ret < 0)
{
/* A signal received while waiting for access to the xmit.head will
- * abort the transfer. After the transfer has started, we are committed
- * and signals will be ignored.
+ * abort the transfer.
*/
return ret;
@@ -323,53 +323,64 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
uart_disabletxint(dev);
for (; buflen; buflen--)
{
- int ch = *buffer++;
+ ch = *buffer++;
- /* If the ONLCR flag is set, we should translate \n to \r\n */
+ /* Do output post-processing */
- ret = OK;
- if ((ch == '\n') && (dev->termios_s.c_oflag & ONLCR))
- {
- ret = uart_putxmitchar(dev, '\r');
- }
+#ifdef CONFIG_SERIAL_TERMIOS
- /* Put the character into the transmit buffer */
+ if (dev->tc_oflag & OPOST)
+ {
- if (ret == OK)
- {
- ret = uart_putxmitchar(dev, ch);
- }
+ /* Mapping CR to NL? */
- /* Were we awakened by a signal? That should be the only condition that
- * uart_putxmitchar() should return an error.
- */
+ if ((ch == '\r') && (dev->tc_oflag & OCRNL))
+ {
+ ch = '\n';
+ }
- if (ret < 0)
- {
- /* POSIX requires that we return -1 and errno set if no data was
- * transferred. Otherwise, we return the number of bytes in the
- * interrupted transfer.
- */
+ /* Are we interested in newline processing? */
- if (buflen < nread)
+ if ((ch == '\n') && (dev->tc_oflag & (ONLCR | ONLRET)))
{
- /* Some data was transferred. Return the number of bytes that were
- * successfully transferred.
- */
+ ret = uart_putxmitchar(dev, '\r');
- nread -= buflen;
- }
- else
- {
- /* No data was transferred. Return -EINTR. The VFS layer will
- * set the errno value appropriately).
- */
-
- nread = -EINTR;
+ if (ret != OK)
+ {
+ break;
+ }
}
+ /* Specifically not handled:
+ *
+ * OXTABS - primarily a full-screen terminal optimisation
+ * ONOEOT - Unix interoperability hack
+ * OLCUC - Not specified by Posix
+ * ONOCR - low-speed interactive optimisation
+ */
+
+ }
+
+#else /* !CONFIG_SERIAL_TERMIOS */
+
+ /* If this is the console, convert \n -> \r\n */
+
+ if (dev->isconsole && ch == '\n')
+ {
+ ret = uart_putxmitchar(dev, '\r');
+ }
+
+#endif
+
+ /* Put the character into the transmit buffer */
+
+ ret = uart_putxmitchar(dev, ch);
+
+ if (ret != OK)
+ {
break;
}
+
}
if (dev->xmit.head != dev->xmit.tail)
@@ -378,6 +389,36 @@ 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.
+ */
+
+ if (ret < 0)
+ {
+ /* POSIX requires that we return -1 and errno set if no data was
+ * transferred. Otherwise, we return the number of bytes in the
+ * interrupted transfer.
+ */
+
+ if (buflen < nread)
+ {
+ /* Some data was transferred. Return the number of bytes that were
+ * successfully transferred.
+ */
+
+ nread -= buflen;
+ }
+ else
+ {
+ /* No data was transferred. Return -EINTR. The VFS layer will
+ * set the errno value appropriately).
+ */
+
+ nread = -EINTR;
+ }
+ }
+
return nread;
}
@@ -393,6 +434,7 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
ssize_t recvd = 0;
int16_t tail;
int ret;
+ char ch;
/* Only one user can access dev->recv.tail at a time */
@@ -430,8 +472,7 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
{
/* Take the next character from the tail of the buffer */
- *buffer++ = dev->recv.buffer[tail];
- recvd++;
+ ch = dev->recv.buffer[tail];
/* Increment the tail index. Most operations are done using the
* local variable 'tail' so that the final dev->recv.tail update
@@ -444,6 +485,49 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
}
dev->recv.tail = tail;
+
+#ifdef CONFIG_SERIAL_TERMIOS
+
+ /* Do input processing if any is enabled */
+
+ if (dev->tc_iflag & (INLCR | IGNCR | ICRNL))
+ {
+
+ /* \n -> \r or \r -> \n translation? */
+
+ if ((ch == '\n') && (dev->tc_iflag & INLCR))
+ {
+ ch = '\r';
+ }
+ else if ((ch == '\r') && (dev->tc_iflag & ICRNL))
+ {
+ ch = '\n';
+ }
+
+ /* discarding \r ? */
+ if ((ch == '\r') & (dev->tc_iflag & IGNCR))
+ {
+ continue;
+ }
+
+ }
+
+ /* Specifically not handled:
+ *
+ * All of the local modes; echo, line editing, etc.
+ * Anything to do with break or parity errors.
+ * ISTRIP - we should be 8-bit clean.
+ * IUCLC - Not Posix
+ * IXON/OXOFF - no xon/xoff flow control.
+ */
+
+#endif
+
+ /* store the received character */
+
+ *buffer++ = ch;
+ recvd++;
+
}
#ifdef CONFIG_DEV_SERIAL_FULLBLOCKS
@@ -573,43 +657,77 @@ static int uart_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
/* Handle TTY-level IOCTLs here */
/* Let low-level driver handle the call first */
+
int ret = dev->ops->ioctl(filep, cmd, arg);
+
/* Append any higher level TTY flags */
- switch (cmd)
+
+ if (ret == OK)
{
- case TCGETS:
- {
- struct termios *termiosp = (struct termios*)arg;
+ switch (cmd)
+ {
- if (!termiosp)
- {
- ret = -EINVAL;
- break;
- }
+ case FIONREAD:
+ {
+ int count;
+ irqstate_t state = irqsave();
- /* Fetch the out flags */
- termiosp->c_oflag = dev->termios_s.c_oflag;
- /* Fetch the in flags */
- termiosp->c_iflag = dev->termios_s.c_iflag;
- }
- break;
+ /* determine the number of bytes available in the buffer */
- case TCSETS:
- {
- struct termios *termiosp = (struct termios*)arg;
+ if (dev->recv.tail <= dev->recv.head)
+ {
+ count = dev->recv.head - dev->recv.tail;
+ }
+ else
+ {
+ count = dev->recv.size - (dev->recv.tail - dev->recv.head);
+ }
- if (!termiosp)
- {
- ret = -EINVAL;
- break;
- }
+ irqrestore(state);
+
+ *(int *)arg = count;
+ }
+
+#ifdef CONFIG_SERIAL_TERMIOS
+ case TCGETS:
+ {
+ struct termios *termiosp = (struct termios*)arg;
+
+ if (!termiosp)
+ {
+ ret = -EINVAL;
+ break;
+ }
+
+ /* and update with flags from this layer */
- /* Set the out flags */
- dev->termios_s.c_oflag = termiosp->c_oflag;
- /* Set the in flags */
- dev->termios_s.c_iflag = termiosp->c_iflag;
- }
- break;
+ termiosp->c_iflag = dev->tc_iflag;
+ termiosp->c_oflag = dev->tc_oflag;
+ termiosp->c_lflag = dev->tc_lflag;
+ }
+
+ break;
+
+ case TCSETS:
+ {
+ struct termios *termiosp = (struct termios*)arg;
+
+ if (!termiosp)
+ {
+ ret = -EINVAL;
+ break;
+ }
+
+ /* update the flags we keep at this layer */
+
+ dev->tc_iflag = termiosp->c_iflag;
+ dev->tc_oflag = termiosp->c_oflag;
+ dev->tc_lflag = termiosp->c_lflag;
+ }
+
+ break;
+#endif
+ }
}
return ret;
}
@@ -900,6 +1018,25 @@ static int uart_open(FAR struct file *filep)
dev->recv.head = 0;
dev->recv.tail = 0;
+ /* initialise termios state */
+
+#ifdef CONFIG_SERIAL_TERMIOS
+
+ dev->tc_iflag = 0;
+ if (dev->isconsole == true)
+ {
+
+ /* enable \n -> \r\n translation for the console */
+
+ dev->tc_oflag = OPOST | ONLCR;
+ }
+ else
+ {
+ dev->tc_oflag = 0;
+ }
+
+#endif
+
/* Enable the RX interrupt */
uart_enablerxint(dev);
@@ -937,14 +1074,22 @@ int uart_register(FAR const char *path, FAR uart_dev_t *dev)
#ifndef CONFIG_DISABLE_POLL
sem_init(&dev->pollsem, 0, 1);
#endif
+
/* Setup termios flags */
- memset(&dev->termios_s, 0, sizeof(dev->termios_s));
+
+#ifdef CONFIG_SERIAL_TERMIOS
+
if (dev->isconsole == true)
{
- /* Device is console, set up termios flags */
- dev->termios_s.c_oflag |= ONLCR;
+
+ /* enable \n -> \r\n translation for the console as early as possible */
+
+ dev->tc_oflag = OPOST | ONLCR;
+ dev->tc_iflag = 0;
}
+#endif
+
dbg("Registering %s\n", path);
return register_driver(path, &g_serialops, 0666, dev);
}
diff --git a/nuttx/include/nuttx/fs/ioctl.h b/nuttx/include/nuttx/fs/ioctl.h
index 19f29b1fb..08f62e164 100644
--- a/nuttx/include/nuttx/fs/ioctl.h
+++ b/nuttx/include/nuttx/fs/ioctl.h
@@ -106,6 +106,10 @@
* OUT: None
*/
+#define FIONREAD _FIOC(0x0004) /* IN: Location to return value (int *)
+ * OUT: Bytes readable from this fd
+ */
+
/* NuttX file system ioctl definitions **************************************/
#define _DIOCVALID(c) (_IOC_TYPE(c)==_DIOCBASE)
diff --git a/nuttx/include/nuttx/serial/serial.h b/nuttx/include/nuttx/serial/serial.h
index 67a7f9d99..49dba3795 100644
--- a/nuttx/include/nuttx/serial/serial.h
+++ b/nuttx/include/nuttx/serial/serial.h
@@ -46,7 +46,9 @@
#include <stdint.h>
#include <stdbool.h>
#include <semaphore.h>
-#include <termios.h>
+#ifdef CONFIG_SERIAL_TERMIOS
+# include <termios.h>
+#endif
#include <nuttx/fs/fs.h>
/************************************************************************************
@@ -216,7 +218,12 @@ struct uart_dev_s
#endif
/* Terminal control flags */
- struct termios termios_s;
+
+#ifdef CONFIG_SERIAL_TERMIOS
+ tcflag_t tc_iflag; /* Input modes */
+ tcflag_t tc_oflag; /* Output modes */
+ tcflag_t tc_lflag; /* Local modes */
+#endif
};
typedef struct uart_dev_s uart_dev_t;
diff --git a/nuttx/include/termios.h b/nuttx/include/termios.h
index af1867a22..c8f590a5b 100644
--- a/nuttx/include/termios.h
+++ b/nuttx/include/termios.h
@@ -58,7 +58,7 @@
#define INLCR (1 << 5) /* Bit 5: Map NL to CR on input */
#define INPCK (1 << 6) /* Bit 6: Enable input parity check */
#define ISTRIP (1 << 7) /* Bit 7: Strip character */
-#define IUCLC (1 << 8) /* Bit 8: Map upper-case to lower-case on input (LEGACY) */
+ /* Bit 8: unused */
#define IXANY (1 << 9) /* Bit 9: Enable any character to restart output */
#define IXOFF (1 << 10) /* Bit 10: Enable start/stop input control */
#define IXON (1 << 11) /* Bit 11: Enable start/stop output control */
@@ -67,7 +67,7 @@
/* Terminal output modes (c_oflag in the termios structure) */
#define OPOST (1 << 0) /* Bit 0: Post-process output */
-#define OLCUC (1 << 1) /* Bit 1: Map lower-case to upper-case on output (LEGACY) */
+ /* Bit 1: unused */
#define ONLCR (1 << 2) /* Bit 2: Map NL to CR-NL on output */
#define OCRNL (1 << 3) /* Bit 3: Map CR to NL on output */
#define ONOCR (1 << 4) /* Bit 4: No CR output at column 0 */
@@ -98,17 +98,20 @@
/* Control Modes (c_cflag in the termios structure) */
-#define CSIZE (3 << 0) /* Bits 0-1: Character size: */
-# define CS5 (0 << 0) /* 5 bits */
-# define CS6 (1 << 0) /* 6 bits */
-# define CS7 (2 << 0) /* 7 bits */
-# define CS8 (3 << 0) /* 8 bits */
-#define CSTOPB (1 << 2) /* Bit 2: Send two stop bits, else one */
-#define CREAD (1 << 3) /* Bit 3: Enable receiver */
-#define PARENB (1 << 4) /* Bit 4: Parity enable */
-#define PARODD (1 << 5) /* Bit 5: Odd parity, else even */
-#define HUPCL (1 << 6) /* Bit 6: Hang up on last close */
-#define CLOCAL (1 << 7) /* Bit 7: Ignore modem status lines */
+#define CSIZE (3 << 0) /* Bits 0-1: Character size: */
+# define CS5 (0 << 0) /* 5 bits */
+# define CS6 (1 << 0) /* 6 bits */
+# define CS7 (2 << 0) /* 7 bits */
+# define CS8 (3 << 0) /* 8 bits */
+#define CSTOPB (1 << 2) /* Bit 2: Send two stop bits, else one */
+#define CREAD (1 << 3) /* Bit 3: Enable receiver */
+#define PARENB (1 << 4) /* Bit 4: Parity enable */
+#define PARODD (1 << 5) /* Bit 5: Odd parity, else even */
+#define HUPCL (1 << 6) /* Bit 6: Hang up on last close */
+#define CLOCAL (1 << 7) /* Bit 7: Ignore modem status lines */
+#define CCTS_OFLOW (1 << 8) /* Bit 8: CTS flow control of output */
+#define CRTSCTS CCTS_OFLOW
+#define CRTS_IFLOW (1 << 9) /* Bit 9: RTS flow control of input */
/* Local Modes (c_lflag in the termios structure) */
@@ -121,7 +124,6 @@
#define ISIG (1 << 6) /* Bit 6: Enable signals */
#define NOFLSH (1 << 7) /* Bit 7: Disable flush after interrupt or quit */
#define TOSTOP (1 << 8) /* Bit 8: Send SIGTTOU for background output */
-#define XCASE (1 << 9) /* Bit 9: Canonical upper/lower presentation (LEGACY) */
/* The following are subscript names for the termios c_cc array */