summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-07-20 16:58:39 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-07-20 16:58:39 +0000
commitaaab49d3299b2f2ebbbbb35bcfc5a027da8ed4a6 (patch)
tree1f721949aec6fcb3c70430b5990daadf4f26751d
parentaf87d2de769a3f148b56f256e8c870c0f1b84580 (diff)
downloadpx4-nuttx-aaab49d3299b2f2ebbbbb35bcfc5a027da8ed4a6.tar.gz
px4-nuttx-aaab49d3299b2f2ebbbbb35bcfc5a027da8ed4a6.tar.bz2
px4-nuttx-aaab49d3299b2f2ebbbbb35bcfc5a027da8ed4a6.zip
Add infrastructure to support RS-485 on the LPC43xx (logic still incomplete)
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4958 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/ChangeLog5
-rw-r--r--nuttx/arch/arm/src/lpc43xx/lpc43_serial.c60
-rw-r--r--nuttx/configs/lpc4330-xplorer/README.txt6
-rw-r--r--nuttx/configs/lpc4330-xplorer/nsh/defconfig7
-rw-r--r--nuttx/configs/lpc4330-xplorer/ostest/defconfig7
-rw-r--r--nuttx/include/nuttx/serial/tioctl.h23
6 files changed, 106 insertions, 2 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index befaf0f77..9a7421070 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3029,4 +3029,9 @@
add the ability to run the chip off the internal oscillator. There is no open
board configuration for this part yet (the STM32VLDiscovery would be a candidate).
Contributed by Mike Smith.
+ * arch/arm/src/stm32: Fixed typos in conditional compilation in the CAN and DMA
+ and some pin configuration. This would have caused problems for STM32 F107xx.
+ Typos noted by Mike Smith.
+ * arch/arm/src/lpc43xx/lpc43_serial.c: Add support for certain RS-485 features
+ in the serial driver (still a work in progress on initial check-in).
diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_serial.c b/nuttx/arch/arm/src/lpc43xx/lpc43_serial.c
index 1c4e56fe4..bfee7a222 100644
--- a/nuttx/arch/arm/src/lpc43xx/lpc43_serial.c
+++ b/nuttx/arch/arm/src/lpc43xx/lpc43_serial.c
@@ -858,6 +858,50 @@ static int up_interrupt(int irq, void *context)
}
/****************************************************************************
+ * Name: up_set_rs485_mode
+ *
+ * Description:
+ * Handle LPC43xx USART0,2,3 RS485 mode set ioctl (TIOCSRS485) to enable
+ * and disable RS-485 mode. This is part of the serial ioctl logic.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_USART_RS485MODE
+static inline int up_set_rs485_mode(struct up_dev_s *priv,
+ const struct serial_rs485 *mode)
+{
+ irqstate_t flags;
+
+ DEBUGASSERT(priv && mode);
+ flags = irqsave();
+#warning "Missing logic"
+ irqrestore(flags);
+}
+#endif
+
+/****************************************************************************
+ * Name: up_get_rs485_mode
+ *
+ * Description:
+ * Handle LPC43xx USART0,2,3 RS485 mode get ioctl (TIOCGRS485) to get the
+ * current RS-485 mode.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_USART_RS485MODE
+static inline int up_get_rs485_mode(struct up_dev_s *priv,
+ struct serial_rs485 *mode)
+{
+ irqstate_t flags;
+
+ DEBUGASSERT(priv && mode);
+ flags = irqsave();
+#warning "Missing logic"
+ irqrestore(flags);
+}
+#endif
+
+/****************************************************************************
* Name: up_ioctl
*
* Description:
@@ -906,6 +950,22 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
}
break;
+#ifdef CONFIG_USART_RS485MODE
+ case TIOCSRS485: /* Set RS485 mode, arg: pointer to struct serial_rs485 */
+ {
+ ret = up_set_rs485_mode(priv,
+ (const struct serial_rs485 *)((uintptr_t)arg));
+ }
+ break;
+
+ case TIOCGRS485: /* Get RS485 mode, arg: pointer to struct serial_rs485 */
+ {
+ ret = up_get_rs485_mode(priv,
+ (struct serial_rs485 *)((uintptr_t)arg));
+ }
+ break;
+#endif
+
default:
*get_errno_ptr() = ENOTTY;
ret = ERROR;
diff --git a/nuttx/configs/lpc4330-xplorer/README.txt b/nuttx/configs/lpc4330-xplorer/README.txt
index 5a58d3769..3e89b478f 100644
--- a/nuttx/configs/lpc4330-xplorer/README.txt
+++ b/nuttx/configs/lpc4330-xplorer/README.txt
@@ -716,7 +716,7 @@ LPC4330-Xplorer Configuration Options
CONFIG_LPC43_USB1_ULPI=y
CONFIG_LPC43_WWDT=y
- LPC43xx specific device driver settings
+ LPC43xx specific U[S]ART device driver settings
CONFIG_U[S]ARTn_SERIAL_CONSOLE - selects the UARTn for the
console and ttys0 (default is the USART0).
@@ -729,6 +729,10 @@ LPC4330-Xplorer Configuration Options
CONFIG_U[S]ARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
CONFIG_U[S]ARTn_2STOP - Two stop bits
+ CONFIG_USART_RS485MODE - Support LPC43xx USART0,2,3 RS485 mode
+ ioctls (TIOCSRS485 and TIOCGRS485) to enable and disable
+ RS-485 mode.
+
LPC43xx specific CAN device driver settings. These settings all
require CONFIG_CAN:
diff --git a/nuttx/configs/lpc4330-xplorer/nsh/defconfig b/nuttx/configs/lpc4330-xplorer/nsh/defconfig
index deb3ff19e..8f6660ede 100644
--- a/nuttx/configs/lpc4330-xplorer/nsh/defconfig
+++ b/nuttx/configs/lpc4330-xplorer/nsh/defconfig
@@ -228,6 +228,13 @@ CONFIG_USART2_2STOP=0
CONFIG_USART3_2STOP=0
#
+# CONFIG_USART_RS485MODE - Support LPC43xx USART0,2,3 RS485 mode
+# ioctls (TIOCSRS485 and TIOCGRS485) to enable and disable
+# RS-485 mode.
+#
+CONFIG_USART_RS485MODE=n
+
+#
# LPC43xx specific PHY/Ethernet device driver settings
#
# CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY
diff --git a/nuttx/configs/lpc4330-xplorer/ostest/defconfig b/nuttx/configs/lpc4330-xplorer/ostest/defconfig
index c20897b76..202192635 100644
--- a/nuttx/configs/lpc4330-xplorer/ostest/defconfig
+++ b/nuttx/configs/lpc4330-xplorer/ostest/defconfig
@@ -228,6 +228,13 @@ CONFIG_USART2_2STOP=0
CONFIG_USART3_2STOP=0
#
+# CONFIG_USART_RS485MODE - Support LPC43xx USART0,2,3 RS485 mode
+# ioctls (TIOCSRS485 and TIOCGRS485) to enable and disable
+# RS-485 mode.
+#
+CONFIG_USART_RS485MODE=n
+
+#
# LPC43xx specific PHY/Ethernet device driver settings
#
# CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY
diff --git a/nuttx/include/nuttx/serial/tioctl.h b/nuttx/include/nuttx/serial/tioctl.h
index a3ce2c7d3..a923fa324 100644
--- a/nuttx/include/nuttx/serial/tioctl.h
+++ b/nuttx/include/nuttx/serial/tioctl.h
@@ -160,9 +160,21 @@
#define TIOCMIWAIT _TIOC(0x0028) /* Wait for a change on serial input line(s): void */
#define TIOCGICOUNT _TIOC(0x0029) /* Read serial port interrupt count: FAR struct serial_icounter_struct */
+/* RS-485 Support */
+
+#define TIOCSRS485 _TIOC(0x002a) /* Set RS485 mode, arg: pointer to struct serial_rs485 */
+#define TIOCGRS485 _TIOC(0x002b) /* Get RS485 mode, arg: pointer to struct serial_rs485 */
+
/* Debugging */
-#define TIOCSERGSTRUCT _TIOC(0x002a) /* Get device TTY structure */
+#define TIOCSERGSTRUCT _TIOC(0x002c) /* Get device TTY structure */
+
+/* Definitions used in struct serial_rs485 (Linux compatible) */
+
+#define SER_RS485_ENABLED (1 << 0) /* Enable/disble RS-485 support */
+#define SER_RS485_RTS_ON_SEND (1 << 1) /* Logic level for RTS pin when sending */
+#define SER_RS485_RTS_AFTER_SEND (1 << 2) /* Logic level for RTS pin after sent */
+#define SER_RS485_RX_DURING_TX (1 << 4)
/********************************************************************************************
* Public Type Definitions
@@ -178,6 +190,15 @@ struct winsize
/* uint16_t ws_ypixel; unused */
};
+/* Structure used with TIOCSRS485 and TIOCGRS485 (Linux compatible) */
+
+struct serial_rs485
+{
+ uint32_t flags /* See SER_RS485_* definitions */
+ uint32_t delay_rts_before_send; /* Delay before send (milliseconds) */
+ uint32_t delay_rts_after_send; /* Delay after send (milliseconds) */
+};
+
/********************************************************************************************
* Public Function Prototypes
********************************************************************************************/