aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--apps/px4/tests/test_hott_telemetry.c4
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_serial.c8
-rw-r--r--nuttx/include/nuttx/serial/tioctl.h6
3 files changed, 12 insertions, 6 deletions
diff --git a/apps/px4/tests/test_hott_telemetry.c b/apps/px4/tests/test_hott_telemetry.c
index dbef021e3..74aa0e614 100644
--- a/apps/px4/tests/test_hott_telemetry.c
+++ b/apps/px4/tests/test_hott_telemetry.c
@@ -143,7 +143,7 @@ int test_hott_telemetry(int argc, char *argv[])
}
/* Activate single wire mode */
- ioctl(fd, TIOCSRS485, SER_RS485_ENABLED);
+ ioctl(fd, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED);
char send = 'a';
write(fd, &send, 1);
@@ -223,7 +223,7 @@ int test_hott_telemetry(int argc, char *argv[])
/* Disable single wire */
- ioctl(fd, TIOCSRS485, ~SER_RS485_ENABLED);
+ ioctl(fd, TIOCSSINGLEWIRE, ~SER_SINGLEWIRE_ENABLED);
write(fd, &send, 1);
diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c
index 80c4ce357..7e8537b2a 100644
--- a/nuttx/arch/arm/src/stm32/stm32_serial.c
+++ b/nuttx/arch/arm/src/stm32/stm32_serial.c
@@ -1307,11 +1307,11 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
}
break;
- /* Set RS485 mode */
- case TIOCSRS485:
+ /* Set single-wire mode */
+ case TIOCSSINGLEWIRE:
{
/* Change the TX port to be open-drain/push-pull */
- if (arg == SER_RS485_ENABLED) {
+ if (arg == SER_SINGLEWIRE_ENABLED) {
stm32_configgpio(priv->tx_gpio | GPIO_OPENDRAIN);
} else {
stm32_configgpio(priv->tx_gpio | GPIO_PUSHPULL);
@@ -1319,7 +1319,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
/* Enable/disable half-duplex mode */
uint32_t cr = up_serialin(priv, STM32_USART_CR3_OFFSET);
- if (arg == SER_RS485_ENABLED) {
+ if (arg == SER_SINGLEWIRE_ENABLED) {
cr |= (USART_CR3_HDSEL);
} else {
cr &= ~(USART_CR3_HDSEL);
diff --git a/nuttx/include/nuttx/serial/tioctl.h b/nuttx/include/nuttx/serial/tioctl.h
index b309ff37c..76185a22e 100644
--- a/nuttx/include/nuttx/serial/tioctl.h
+++ b/nuttx/include/nuttx/serial/tioctl.h
@@ -169,6 +169,9 @@
#define TIOCSERGSTRUCT _TIOC(0x002c) /* Get device TTY structure */
+#define TIOCSSINGLEWIRE _TIOC(0x002d) /* Set single-wire mode */
+#define TIOCGSINGLEWIRE _TIOC(0x002e) /* Get single-wire mode */
+
/* Definitions used in struct serial_rs485 (Linux compatible) */
#define SER_RS485_ENABLED (1 << 0) /* Enable/disble RS-485 support */
@@ -176,6 +179,9 @@
#define SER_RS485_RTS_AFTER_SEND (1 << 2) /* Logic level for RTS pin after sent */
#define SER_RS485_RX_DURING_TX (1 << 4)
+/* single-wire definitions */
+#define SER_SINGLEWIRE_ENABLED (1 << 0) /* Enable/disble single-wire support */
+
/********************************************************************************************
* Public Type Definitions
********************************************************************************************/