[PATCH v1 29/31] serial: 8250_mxpcie: Add sysfs to control terminator

Crescent Hsieh posted 31 patches 1 day, 11 hours ago
[PATCH v1 29/31] serial: 8250_mxpcie: Add sysfs to control terminator
Posted by Crescent Hsieh 1 day, 11 hours ago
Some Moxa PCIe serial board variants support software-controlled
termination resistors on each port. Users currently have no standardized
interface to enable or disable terminator state from userspace.

This patch introduces the following:

- EXPORT a new sysfs attribute `/sys/class/tty/*/mxpcie8250_terminator`
  to allow users to read or set the terminator state (enabled/disabled).
- Implement both CPLD-based and GPIO-based paths depending on board model.
- Track runtime terminator state in `struct mxpcie8250_port`.
- Serialize CPLD modifications using a new `board_lock` spinlock.

Example usage:

    # Enable terminator on ttyS*
    echo 1 > /sys/class/tty/ttyS*/mxpcie8250_terminator

    # Check current state
    cat /sys/class/tty/ttyS*/mxpcie8250_terminator
    enabled

Signed-off-by: Crescent Hsieh <crescentcy.hsieh@moxa.com>
---
 drivers/tty/serial/8250/8250_mxpcie.c | 205 ++++++++++++++++++++++++++
 1 file changed, 205 insertions(+)

diff --git a/drivers/tty/serial/8250/8250_mxpcie.c b/drivers/tty/serial/8250/8250_mxpcie.c
index 7a1030a47b00..9dcb91b917a0 100644
--- a/drivers/tty/serial/8250/8250_mxpcie.c
+++ b/drivers/tty/serial/8250/8250_mxpcie.c
@@ -105,16 +105,22 @@
 
 #define MOXA_CPLD_GET_STATE_BASE	0x10
 #define MOXA_CPLD_SET_STATE_BASE	0x18
+#define MOXA_CPLD_STATE_MASK		0x0F
 
 #define MOXA_CPLD_DATA_MASK	0x1F	/* Pin0 ~ Pin4 */
 #define MOXA_CPLD_CTRL_MASK	0xE0	/* Pin5 ~ Pin7 */
 
+#define MOXA_CPLD_TERMINATOR_FLAG	0x02
+
 #define MOXA_CPLD_READ	0
 #define MOXA_CPLD_WRITE	1
 
 #define MOXA_CPLD_ADDRESS	0
 #define MOXA_CPLD_DATA		1
 
+#define MOXA_TERMINATOR_ENABLE	1
+#define MOXA_TERMINATOR_DISABLE	0
+
 #define MOXA_UIR_OFFSET		0x04
 #define MOXA_UIR_RS232		0x00
 #define MOXA_UIR_RS422		0x01
@@ -129,6 +135,7 @@
 struct mxpcie8250_port {
 	int line;
 	int interface;
+	int terminator;
 	unsigned long event_flags;
 	u8 rx_trig_level;
 	struct uart_port *uport;
@@ -139,6 +146,7 @@ struct mxpcie8250 {
 	struct pci_dev *pdev;
 	unsigned int supp_rs;
 	unsigned int num_ports;
+	spinlock_t board_lock;
 	struct mxpcie8250_port port[];
 };
 
@@ -448,6 +456,59 @@ static void mxpcie8250_cpld_write(resource_size_t iobar_addr, u8 addr, u8 data)
 	}
 }
 
+/**
+ * mxpcie8250_cpld_set_terminator() - Set the terminator of the specified port
+ * @iobar_addr:	The base address of the GPIO I/O region
+ * @port_idx:	The port index (0 to 7)
+ * @state:	Desired terminator state (MOXA_TERMINATOR_ENABLE or MOXA_TERMINATOR_DISABLE)
+ *
+ * Updates the terminator setting in the CPLD for the specified port by reading
+ * the current state, modifying the terminator bit, and writing the updated
+ * state back to the CPLD.
+ */
+static void mxpcie8250_cpld_set_terminator(resource_size_t iobar_addr, u8 port_idx, u8 state)
+{
+	u8 addr, data;
+
+	addr = MOXA_CPLD_GET_STATE_BASE + port_idx;
+	mxpcie8250_cpld_read(iobar_addr, addr, &data);
+
+	data = data & MOXA_CPLD_STATE_MASK;
+
+	if (state == MOXA_TERMINATOR_ENABLE)
+		data |= MOXA_CPLD_TERMINATOR_FLAG;
+	else
+		data &= ~MOXA_CPLD_TERMINATOR_FLAG;
+
+	addr = MOXA_CPLD_SET_STATE_BASE + port_idx;
+	mxpcie8250_cpld_write(iobar_addr, addr, data);
+}
+
+/**
+ * mxpcie8250_cpld_get_terminator() - Get the terminator state of the specified port
+ * @iobar_addr:	The base address of the GPIO I/O region
+ * @port_idx:	The port index (0 to 7)
+ *
+ * Reads the terminator from the CPLD by accessing the appropriate GET_STATE
+ * register for the specified port using GPIO-based communication.
+ *
+ * Returns:
+ * 	MOXA_TERMINATOR_ENABLE  if terminator is enabled,
+ * 	MOXA_TERMINATOR_DISABLE if terminator is disabled.
+ */
+static int mxpcie8250_cpld_get_terminator(resource_size_t iobar_addr, u8 port_idx)
+{
+	u8 addr, data;
+
+	addr = MOXA_CPLD_GET_STATE_BASE + port_idx;
+	mxpcie8250_cpld_read(iobar_addr, addr, &data);
+
+	if (data & MOXA_CPLD_TERMINATOR_FLAG)
+		return MOXA_TERMINATOR_ENABLE;
+
+	return MOXA_TERMINATOR_DISABLE;
+}
+
 static bool mxpcie8250_is_mini_pcie(unsigned short device)
 {
 	if (device == PCI_DEVICE_ID_MOXA_CP102N ||
@@ -487,6 +548,75 @@ static unsigned short mxpcie8250_get_nports(unsigned short device)
 	return FIELD_GET(0x00F0, device);
 }
 
+static void mxpcie8250_do_set_terminator(struct pci_dev *pdev,
+					 unsigned int port_idx,
+					 u8 state)
+{
+	struct mxpcie8250 *priv = pci_get_drvdata(pdev);
+	resource_size_t iobar_addr = pci_resource_start(pdev, 2);
+	u8 cval;
+
+	cval = inb(iobar_addr + MOXA_GPIO_INPUT);
+
+	switch (pdev->device) {
+	case PCI_DEVICE_ID_MOXA_CP132EL:
+		cval &= ~(1 << (port_idx + 2));
+		cval |= (state << (port_idx + 2));
+		break;
+	case PCI_DEVICE_ID_MOXA_CP114EL:
+	case PCI_DEVICE_ID_MOXA_CP118EL_A:
+		cval &= ~(1 << port_idx);
+		cval |= (state << port_idx);
+		break;
+	default:
+		return;
+	}
+	outb(0xff, iobar_addr + MOXA_GPIO_DIRECTION);
+	outb(cval, iobar_addr + MOXA_GPIO_OUTPUT);
+
+	priv->port[port_idx].terminator = state;
+}
+
+static int mxpcie8250_set_terminator(struct uart_port *port,
+				     u8 state)
+{
+	struct pci_dev *pdev = to_pci_dev(port->dev);
+	struct mxpcie8250 *priv = pci_get_drvdata(pdev);
+	resource_size_t iobar_addr = pci_resource_start(pdev, 2);
+
+	if (priv->port[port->port_id].interface == MOXA_UIR_RS232)
+		return -EINVAL;
+
+	switch (pdev->device) {
+	case PCI_DEVICE_ID_MOXA_CP116E_A_A:
+	case PCI_DEVICE_ID_MOXA_CP116E_A_B:
+	case PCI_DEVICE_ID_MOXA_CP118E_A_I:
+	case PCI_DEVICE_ID_MOXA_CP134EL_A:
+	case PCI_DEVICE_ID_MOXA_CP138E_A:
+		spin_lock(&priv->board_lock);
+		mxpcie8250_cpld_set_terminator(iobar_addr, port->port_id, state);
+		spin_unlock(&priv->board_lock);
+		break;
+	/* RS232 only, no need to be set */
+	case PCI_DEVICE_ID_MOXA_CP104EL_A:
+	case PCI_DEVICE_ID_MOXA_CP102E:
+	case PCI_DEVICE_ID_MOXA_CP102EL:
+	case PCI_DEVICE_ID_MOXA_CP168EL_A:
+	/* CP100N series doesn't support SW control terminator */
+	case PCI_DEVICE_ID_MOXA_CP102N:
+	case PCI_DEVICE_ID_MOXA_CP132N:
+	case PCI_DEVICE_ID_MOXA_CP112N:
+	case PCI_DEVICE_ID_MOXA_CP104N:
+	case PCI_DEVICE_ID_MOXA_CP134N:
+	case PCI_DEVICE_ID_MOXA_CP114N:
+		return -ENODEV;
+	default:
+		mxpcie8250_do_set_terminator(pdev, port->port_id, state);
+	}
+
+	return 0;
+}
+
 static int mxpcie8250_set_interface(struct mxpcie8250 *priv,
 				    unsigned int port_idx,
 				    u8 mode)
@@ -495,6 +625,9 @@ static int mxpcie8250_set_interface(struct mxpcie8250 *priv,
 	resource_size_t UIR_addr = iobar_addr + MOXA_UIR_OFFSET + port_idx / 2;
 	u8 cval;
 
+	if (priv->port[port_idx].uport && mode == MOXA_UIR_RS232)
+		mxpcie8250_set_terminator(priv->port[port_idx].uport, MOXA_TERMINATOR_DISABLE);
+
 	cval = inb(UIR_addr);
 
 	if (port_idx % 2) {
@@ -811,6 +944,76 @@ static int mxpcie8250_get_rxtrig(struct uart_port *port)
 	return rx_trig_byte;
 }
 
+static ssize_t mxpcie8250_terminator_store(struct device *dev,
+					   struct device_attribute *attr,
+					   const char *buf,
+					   size_t count)
+{
+	struct tty_port *tport = dev_get_drvdata(dev);
+	struct uart_state *ustate = container_of(tport, struct uart_state, port);
+	struct uart_port *port = ustate->uart_port;
+	int ret;
+	u8 state;
+
+	if (!count)
+		return -EINVAL;
+
+	ret = kstrtou8(buf, 10, &state);
+
+	if (ret < 0)
+		return ret;
+
+	if (state != MOXA_TERMINATOR_ENABLE && state != MOXA_TERMINATOR_DISABLE)
+		return -EINVAL;
+
+	ret = mxpcie8250_set_terminator(port, state);
+
+	if (ret < 0)
+		return ret;
+
+	return count;
+}
+
+static ssize_t mxpcie8250_terminator_show(struct device *dev,
+					  struct device_attribute *attr,
+					  char *buf)
+{
+	struct tty_port *tport = dev_get_drvdata(dev);
+	struct uart_state *ustate = container_of(tport, struct uart_state, port);
+	struct uart_port *port = ustate->uart_port;
+	struct pci_dev *pdev = to_pci_dev(port->dev);
+	struct mxpcie8250 *priv = pci_get_drvdata(pdev);
+	resource_size_t iobar_addr = pci_resource_start(pdev, 2);
+	int ret;
+
+	if (pdev->device == PCI_DEVICE_ID_MOXA_CP118E_A_I ||
+	    pdev->device == PCI_DEVICE_ID_MOXA_CP138E_A   ||
+	    pdev->device == PCI_DEVICE_ID_MOXA_CP134EL_A  ||
+	    pdev->device == PCI_DEVICE_ID_MOXA_CP116E_A_A ||
+	    pdev->device == PCI_DEVICE_ID_MOXA_CP116E_A_B) {
+		spin_lock(&priv->board_lock);
+		ret = mxpcie8250_cpld_get_terminator(iobar_addr, port->port_id);
+		spin_unlock(&priv->board_lock);
+	} else {
+		ret = priv->port[port->port_id].terminator;
+	}
+	if (ret == MOXA_TERMINATOR_ENABLE)
+		return sysfs_emit(buf, "enabled\n");
+
+	return sysfs_emit(buf, "disabled\n");
+}
+
+static DEVICE_ATTR_RW(mxpcie8250_terminator);
+
+static struct attribute *mxpcie8250_dev_attrs[] = {
+	&dev_attr_mxpcie8250_terminator.attr,
+	NULL
+};
+
+static struct attribute_group mxpcie8250_dev_attr_group = {
+	.attrs = mxpcie8250_dev_attrs,
+};
+
 static void mxpcie8250_work_handler(struct work_struct *work)
 {
 	struct mxpcie8250_port *priv_port = container_of(work, struct mxpcie8250_port, work);
@@ -924,6 +1127,7 @@ static int mxpcie8250_probe(struct pci_dev *pdev, const struct pci_device_id *id
 	up.port.break_ctl = mxpcie8250_break_ctl;
 	up.port.set_rxtrig = mxpcie8250_set_rxtrig;
 	up.port.get_rxtrig = mxpcie8250_get_rxtrig;
+	up.port.attr_group = &mxpcie8250_dev_attr_group;
 
 	for (i = 0; i < num_ports; i++) {
 		if (mxpcie8250_setup(pdev, priv, &up, i))
@@ -943,6 +1147,7 @@ static int mxpcie8250_probe(struct pci_dev *pdev, const struct pci_device_id *id
 		}
 		new_port = serial8250_get_port(priv->port[i].line);
 
+		priv->port[i].terminator = MOXA_TERMINATOR_DISABLE;
 		priv->port[i].rx_trig_level = 96;
 		priv->port[i].uport = &new_port->port;
 
-- 
2.45.2
Re: [PATCH v1 29/31] serial: 8250_mxpcie: Add sysfs to control terminator
Posted by Andy Shevchenko 19 hours ago
On Sun, Nov 30, 2025 at 12:46 PM Crescent Hsieh
<crescentcy.hsieh@moxa.com> wrote:
>
> Some Moxa PCIe serial board variants support software-controlled
> termination resistors on each port. Users currently have no standardized
> interface to enable or disable terminator state from userspace.
>
> This patch introduces the following:
>
> - EXPORT a new sysfs attribute `/sys/class/tty/*/mxpcie8250_terminator`
>   to allow users to read or set the terminator state (enabled/disabled).
> - Implement both CPLD-based and GPIO-based paths depending on board model.
> - Track runtime terminator state in `struct mxpcie8250_port`.
> - Serialize CPLD modifications using a new `board_lock` spinlock.
>
> Example usage:
>
>     # Enable terminator on ttyS*
>     echo 1 > /sys/class/tty/ttyS*/mxpcie8250_terminator
>
>     # Check current state
>     cat /sys/class/tty/ttyS*/mxpcie8250_terminator
>     enabled

This introduces an ABI without documentation update. It's no go.

...

> +#define MOXA_CPLD_STATE_MASK           0x0F
>
>  #define MOXA_CPLD_DATA_MASK    0x1F    /* Pin0 ~ Pin4 */
>  #define MOXA_CPLD_CTRL_MASK    0xE0    /* Pin5 ~ Pin7 */

Use GENMASK() for the above.

...

>  struct mxpcie8250_port {

Run `pahole`.

>         int line;
>         int interface;
> +       int terminator;
>         unsigned long event_flags;
>         u8 rx_trig_level;
>         struct uart_port *uport;

>  struct mxpcie8250 {

>         struct pci_dev *pdev;
>         unsigned int supp_rs;
>         unsigned int num_ports;
> +       spinlock_t board_lock;
>         struct mxpcie8250_port port[];
>  };

...

> +/**
> + * mxpcie8250_cpld_get_terminator() - Get the terminator state of the specified port
> + * @iobar_addr:        The base address of the GPIO I/O region
> + * @port_idx:  The port index (0 to 7)
> + *
> + * Reads the terminator from the CPLD by accessing the appropriate GET_STATE
> + * register for the specified port using GPIO-based communication.
> + *
> + * Returns:
> + *     MOXA_TERMINATOR_ENABLE  if terminator is enabled,
> + *     MOXA_TERMINATOR_DISABLE if terminator is disabled.

Have you rendered this with the kernel-doc script? I believe you want
a list, so you need something like

 * * List item 1
 * * List item 2

> + */

...

> +static void mxpcie8250_do_set_terminator(struct pci_dev *pdev,
> +                                        unsigned int port_idx,
> +                                        u8 state)
> +{
> +       struct mxpcie8250 *priv = pci_get_drvdata(pdev);
> +       resource_size_t iobar_addr = pci_resource_start(pdev, 2);
> +       u8 cval;
> +
> +       cval = inb(iobar_addr + MOXA_GPIO_INPUT);
> +
> +       switch (pdev->device) {
> +       case PCI_DEVICE_ID_MOXA_CP132EL:
> +               cval &= ~(1 << (port_idx + 2));

BIT()

> +               cval |= (state << (port_idx + 2));

state can be more than one bit set, is it a problem?

> +               break;
> +       case PCI_DEVICE_ID_MOXA_CP114EL:
> +       case PCI_DEVICE_ID_MOXA_CP118EL_A:
> +               cval &= ~(1 << port_idx);
> +               cval |= (state << port_idx);

Same questions as above.

> +               break;
> +       default:
> +               return;
> +       }
> +       outb(0xff, iobar_addr + MOXA_GPIO_DIRECTION);
> +       outb(cval, iobar_addr + MOXA_GPIO_OUTPUT);
> +
> +       priv->port[port_idx].terminator = state;
> +}

...

> +static int mxpcie8250_set_terminator(struct uart_port *port,
> +                                    u8 state)
> +{
> +       struct pci_dev *pdev = to_pci_dev(port->dev);
> +       struct mxpcie8250 *priv = pci_get_drvdata(pdev);

> +       resource_size_t iobar_addr = pci_resource_start(pdev, 2);

Why can't you use what is stored in the "port"? IIRC there are 3
variables: 2 for MMIO (membase/mapbase) and one for IO (iobase).

> +       if (priv->port[port->port_id].interface == MOXA_UIR_RS232)
> +               return -EINVAL;
> +
> +       switch (pdev->device) {
> +       case PCI_DEVICE_ID_MOXA_CP116E_A_A:
> +       case PCI_DEVICE_ID_MOXA_CP116E_A_B:
> +       case PCI_DEVICE_ID_MOXA_CP118E_A_I:
> +       case PCI_DEVICE_ID_MOXA_CP134EL_A:
> +       case PCI_DEVICE_ID_MOXA_CP138E_A:
> +               spin_lock(&priv->board_lock);
> +               mxpcie8250_cpld_set_terminator(iobar_addr, port->port_id, state);
> +               spin_unlock(&priv->board_lock);
> +               break;
> +       /* RS232 only, no need to be set */
> +       case PCI_DEVICE_ID_MOXA_CP104EL_A:
> +       case PCI_DEVICE_ID_MOXA_CP102E:
> +       case PCI_DEVICE_ID_MOXA_CP102EL:
> +       case PCI_DEVICE_ID_MOXA_CP168EL_A:
> +       /* CP100N series doesn't support SW control terminator */
> +       case PCI_DEVICE_ID_MOXA_CP102N:
> +       case PCI_DEVICE_ID_MOXA_CP132N:
> +       case PCI_DEVICE_ID_MOXA_CP112N:
> +       case PCI_DEVICE_ID_MOXA_CP104N:
> +       case PCI_DEVICE_ID_MOXA_CP134N:
> +       case PCI_DEVICE_ID_MOXA_CP114N:
> +               return -ENODEV;
> +       default:
> +               mxpcie8250_do_set_terminator(pdev, port->port_id, state);

Missing break, but see below.

> +       }

> +
> +       return 0;

Just move it to each case (group of cases) where it's needed.

> +}

...

> +static ssize_t mxpcie8250_terminator_store(struct device *dev,
> +                                          struct device_attribute *attr,
> +                                          const char *buf,
> +                                          size_t count)
> +{
> +       struct tty_port *tport = dev_get_drvdata(dev);
> +       struct uart_state *ustate = container_of(tport, struct uart_state, port);
> +       struct uart_port *port = ustate->uart_port;
> +       int ret;
> +       u8 state;

> +       if (!count)
> +               return -EINVAL;

Dead code?

> +       ret = kstrtou8(buf, 10, &state);

Why is this strictly decimal?

> +

Unneeded blank line.

> +       if (ret < 0)
> +               return ret;

> +       if (state != MOXA_TERMINATOR_ENABLE && state != MOXA_TERMINATOR_DISABLE)
> +               return -EINVAL;
> +
> +       ret = mxpcie8250_set_terminator(port, state);

> +

Ditto.

> +       if (ret < 0)
> +               return ret;
> +
> +       return count;
> +}

...

> +               spin_lock(&priv->board_lock);
> +               ret = mxpcie8250_cpld_get_terminator(iobar_addr, port->port_id);
> +               spin_unlock(&priv->board_lock);

scoped_guard() from cleanup.h helps here.

...

> +       if (ret == MOXA_TERMINATOR_ENABLE)
> +               return sysfs_emit(buf, "enabled\n");
> +
> +       return sysfs_emit(buf, "disabled\n");

str_enabled_disabled() from string_choices.h helps here.

> +}

> +

Unneeded blank line.

> +static DEVICE_ATTR_RW(mxpcie8250_terminator);

-- 
With Best Regards,
Andy Shevchenko