2024-04-11 16:14:07

by Parker Newman

[permalink] [raw]
Subject: [PATCH 2/2] serial: exar: adding CTI PCI/PCIe serial port support to 8250_exar

From: Parker Newman <[email protected]>

This patch adds support for most of Connect Tech's (CTI) PCI/PCIe
serial cards to the 8250_exar driver.

Major changes:
- Added (optional) board_setup function called once during probe
- Added exar_get_nr_ports function
- Removed old Connect Tech setup functions
- Added new UART family based CTI setup functions
- Added PCI IDs entries for Exar XR17V25x and CTI FPGA based cards
- Added MPIO functions for configuring/setting a single MPIO
- Added support for reading from the Exar EEPROM

Signed-off-by: Parker Newman <[email protected]>
---
drivers/tty/serial/8250/8250_exar.c | 1089 +++++++++++++++++++++++++--
1 file changed, 1019 insertions(+), 70 deletions(-)

diff --git a/drivers/tty/serial/8250/8250_exar.c b/drivers/tty/serial/8250/8250_exar.c
index eb00fcd79a8e..8516b92741f2 100644
--- a/drivers/tty/serial/8250/8250_exar.c
+++ b/drivers/tty/serial/8250/8250_exar.c
@@ -83,12 +83,25 @@
#define UART_EXAR_DLD 0x02 /* Divisor Fractional */
#define UART_EXAR_DLD_485_POLARITY 0x80 /* RS-485 Enable Signal Polarity */

+/* EEPROM registers */
+#define UART_EXAR_REGB 0x8e
+#define UART_EXAR_REGB_EECK BIT(4)
+#define UART_EXAR_REGB_EECS BIT(5)
+#define UART_EXAR_REGB_EEDI BIT(6)
+#define UART_EXAR_REGB_EEDO BIT(7)
+#define UART_EXAR_REGB_EE_ADDR_SIZE 6
+#define UART_EXAR_REGB_EE_DATA_SIZE 16
+
+#define UART_EXAR_XR17C15X_PORT_OFFSET 0x200
+#define UART_EXAR_XR17V25X_PORT_OFFSET 0x200
+#define UART_EXAR_XR17V35X_PORT_OFFSET 0x400
+
/*
* IOT2040 MPIO wiring semantics:
*
* MPIO Port Function
* ---- ---- --------
- * 0 2 Mode bit 0
+ * 0 2 Mode bit 0
* 1 2 Mode bit 1
* 2 2 Terminate bus
* 3 - <reserved>
@@ -118,36 +131,293 @@
#define IOT2040_UARTS_ENABLE 0x03
#define IOT2040_UARTS_GPIO_HI_MODE 0xF8 /* enable & LED as outputs */

+/* CTI EEPROM offsets */
+#define CTI_EE_OFF_XR17C15X_OSC_FREQ 0x04 /* 2 words (4 bytes) */
+#define CTI_EE_OFF_XR17V25X_OSC_FREQ 0x08 /* 2 words (4 bytes) */
+#define CTI_EE_OFF_XR17C15X_PART_NUM 0x0A /* 4 words (8 bytes) */
+#define CTI_EE_OFF_XR17V25X_PART_NUM 0x0E /* 4 words (8 bytes) */
+#define CTI_EE_OFF_XR17C15X_SERIAL_NUM 0x0E /* 1 word (2 bytes) */
+#define CTI_EE_OFF_XR17V25X_SERIAL_NUM 0x12 /* 1 word (2 bytes) */
+#define CTI_EE_OFF_XR17V35X_SERIAL_NUM 0x11 /* 2 word (4 bytes) */
+#define CTI_EE_OFF_XR17V35X_BOARD_FLAGS 0x13 /* 1 word (2 bytes) */
+#define CTI_EE_OFF_XR17V35X_PORT_FLAGS 0x14 /* 1 word (per port) */
+
+#define CTI_FPGA_RS485_IO_REG 0x2008
+
+#define CTI_DEFAULT_PCI_OSC_FREQ 29491200
+#define CTI_DEFAULT_PCIE_OSC_FREQ 125000000
+#define CTI_DEFAULT_FPGA_OSC_FREQ 33333333
+
+/*
+ * CTI Serial port line types. These match the values stored in the first
+ * nibble of the CTI EEPROM port_flags word.
+ */
+enum cti_port_type {
+ CTI_PORT_TYPE_NONE = 0,
+ CTI_PORT_TYPE_RS232, //RS232 ONLY
+ CTI_PORT_TYPE_RS422_485, //RS422/RS485 ONLY
+ CTI_PORT_TYPE_RS232_422_485_HW, //RS232/422/485 HW ONLY Switchable
+ CTI_PORT_TYPE_RS232_422_485_SW, //RS232/422/485 SW ONLY Switchable
+ CTI_PORT_TYPE_RS232_422_485_4B, //RS232/422/485 HW/SW (4bit ex. BCG004)
+ CTI_PORT_TYPE_RS232_422_485_2B, //RS232/422/485 HW/SW (2bit ex. BBG008)
+ CTI_PORT_TYPE_MAX,
+};
+
+#define CTI_PORT_TYPE_VALID(_port_type) \
+ (((_port_type) > CTI_PORT_TYPE_NONE) && \
+ ((_port_type) < CTI_PORT_TYPE_MAX))
+
+#define CTI_PORT_TYPE_RS485(_port_type) \
+ (((_port_type) > CTI_PORT_TYPE_RS232) && \
+ ((_port_type) < CTI_PORT_TYPE_MAX))
+
struct exar8250;

struct exar8250_platform {
int (*rs485_config)(struct uart_port *port, struct ktermios *termios,
struct serial_rs485 *rs485);
const struct serial_rs485 *rs485_supported;
- int (*register_gpio)(struct pci_dev *, struct uart_8250_port *);
- void (*unregister_gpio)(struct uart_8250_port *);
+ int (*register_gpio)(struct pci_dev *pcidev, struct uart_8250_port *port);
+ void (*unregister_gpio)(struct uart_8250_port *port);
};

/**
* struct exar8250_board - board information
* @num_ports: number of serial ports
* @reg_shift: describes UART register mapping in PCI memory
- * @setup: quirk run at ->probe() stage
+ * @board_setup: quirk run once at ->probe() stage before setting up ports
+ * @setup: quirk run at ->probe() stage for each port
* @exit: quirk run at ->remove() stage
*/
struct exar8250_board {
unsigned int num_ports;
unsigned int reg_shift;
- int (*setup)(struct exar8250 *, struct pci_dev *,
- struct uart_8250_port *, int);
+ int (*board_setup)(struct exar8250 *priv);
+ int (*setup)(struct exar8250 *priv, struct pci_dev *pcidev,
+ struct uart_8250_port *port, int idx);
void (*exit)(struct pci_dev *pcidev);
};

struct exar8250 {
unsigned int nr;
+ unsigned int osc_freq;
+ struct pci_dev *pcidev;
struct exar8250_board *board;
void __iomem *virt;
- int line[];
+ int line[]; //must be last
+};
+
+static inline void exar_write_reg(struct exar8250 *priv,
+ unsigned int reg, uint8_t value)
+{
+ if (!priv || !priv->virt)
+ return;
+
+ writeb(value, priv->virt + reg);
+}
+
+static inline uint8_t exar_read_reg(struct exar8250 *priv, unsigned int reg)
+{
+ if (!priv || !priv->virt)
+ return 0;
+
+ return readb(priv->virt + reg);
+}
+
+static inline void exar_ee_select(struct exar8250 *priv, bool enable)
+{
+ uint8_t value = 0x00;
+
+ if (enable)
+ value |= UART_EXAR_REGB_EECS;
+
+ exar_write_reg(priv, UART_EXAR_REGB, value);
+ udelay(2);
+}
+
+static inline void exar_ee_write_bit(struct exar8250 *priv, int bit)
+{
+ uint8_t value = UART_EXAR_REGB_EECS;
+
+ if (bit)
+ value |= UART_EXAR_REGB_EEDI;
+
+ //Clock out the bit on the i2c interface
+ exar_write_reg(priv, UART_EXAR_REGB, value);
+ udelay(2);
+
+ value |= UART_EXAR_REGB_EECK;
+
+ exar_write_reg(priv, UART_EXAR_REGB, value);
+ udelay(2);
+}
+
+static inline uint8_t exar_ee_read_bit(struct exar8250 *priv)
+{
+ uint8_t regb;
+ uint8_t value = UART_EXAR_REGB_EECS;
+
+ //Clock in the bit on the i2c interface
+ exar_write_reg(priv, UART_EXAR_REGB, value);
+ udelay(2);
+
+ value |= UART_EXAR_REGB_EECK;
+
+ exar_write_reg(priv, UART_EXAR_REGB, value);
+ udelay(2);
+
+ regb = exar_read_reg(priv, UART_EXAR_REGB);
+
+ return (regb & UART_EXAR_REGB_EEDO ? 1 : 0);
+}
+
+/**
+ * exar_ee_read() - Read a word from the EEPROM
+ * @priv: Device's private structure
+ * @ee_addr: Offset of EEPROM to read word from
+ *
+ * Read a single 16bit word from an Exar UART's EEPROM
+ *
+ * Return: EEPROM word on success, negative error code on failure
+ */
+static int exar_ee_read(struct exar8250 *priv, uint8_t ee_addr)
+{
+ int i;
+ int data = 0;
+
+ exar_ee_select(priv, true);
+
+ //Send read command (opcode 110)
+ exar_ee_write_bit(priv, 1);
+ exar_ee_write_bit(priv, 1);
+ exar_ee_write_bit(priv, 0);
+
+ //Send address to read from
+ for (i = 1 << (UART_EXAR_REGB_EE_ADDR_SIZE - 1); i; i >>= 1)
+ exar_ee_write_bit(priv, (ee_addr & i));
+
+ //Read data 1 bit at a time
+ for (i = 0; i <= UART_EXAR_REGB_EE_DATA_SIZE; i++) {
+ data <<= 1;
+ data |= exar_ee_read_bit(priv);
+ }
+
+ exar_ee_select(priv, false);
+
+ return data;
+}
+
+/**
+ * exar_mpio_config() - Configure an EXar MPIO as input or output
+ * @priv: Device's private structure
+ * @mpio_num: MPIO number/offset to configure
+ * @output: Configure as output if true, inout if false
+ *
+ * Configure a single MPIO as an input or output and disable trisate.
+ * If configuring as output it is reccomended to set value with
+ * exar_mpio_set prior to calling this function to ensure default state.
+ *
+ * Return: 0 on success, negative error code on failure
+ */
+static int exar_mpio_config(struct exar8250 *priv,
+ unsigned int mpio_num, bool output)
+{
+ uint8_t sel_reg; //MPIO Select register (input/output)
+ uint8_t tri_reg; //MPIO Tristate register
+ uint8_t value;
+ unsigned int bit;
+
+ if (mpio_num < 8) {
+ sel_reg = UART_EXAR_MPIOSEL_7_0;
+ tri_reg = UART_EXAR_MPIO3T_7_0;
+ bit = mpio_num;
+ } else if (mpio_num >= 8 && mpio_num < 16) {
+ sel_reg = UART_EXAR_MPIOSEL_15_8;
+ tri_reg = UART_EXAR_MPIO3T_15_8;
+ bit = mpio_num - 8;
+ } else {
+ return -EINVAL;
+ }
+
+ //Disable MPIO pin tri-state
+ value = exar_read_reg(priv, tri_reg);
+ value &= ~(BIT(bit));
+ exar_write_reg(priv, tri_reg, value);
+
+ value = exar_read_reg(priv, sel_reg);
+ //Set MPIO as input (1) or output (0)
+ if (output)
+ value &= ~(BIT(bit));
+ else
+ value |= BIT(bit);
+
+ exar_write_reg(priv, sel_reg, value);
+
+ return 0;
+}
+/**
+ * exar_mpio_set() - Set an Exar MPIO output high or low
+ * @priv: Device's private structure
+ * @mpio_num: MPIO number/offset to set
+ * @high: Set MPIO high if true, low if false
+ *
+ * Set a single MPIO high or low. exar_mpio_config must also be called
+ * to configure the pin as an output.
+ *
+ * Return: 0 on success, negative error code on failure
+ */
+static int exar_mpio_set(struct exar8250 *priv,
+ unsigned int mpio_num, bool high)
+{
+ uint8_t reg;
+ uint8_t value;
+ unsigned int bit;
+
+ if (mpio_num < 8) {
+ reg = UART_EXAR_MPIOSEL_7_0;
+ bit = mpio_num;
+ } else if (mpio_num >= 8 && mpio_num < 16) {
+ reg = UART_EXAR_MPIOSEL_15_8;
+ bit = mpio_num - 8;
+ } else {
+ return -EINVAL;
+ }
+
+ value = exar_read_reg(priv, reg);
+
+ if (high)
+ value |= BIT(bit);
+ else
+ value &= ~(BIT(bit));
+
+ exar_write_reg(priv, reg, value);
+
+ return 0;
+}
+
+static int generic_rs485_config(struct uart_port *port, struct ktermios *termios,
+ struct serial_rs485 *rs485)
+{
+ bool is_rs485 = !!(rs485->flags & SER_RS485_ENABLED);
+ u8 __iomem *p = port->membase;
+ u8 value;
+
+ value = readb(p + UART_EXAR_FCTR);
+ if (is_rs485)
+ value |= UART_FCTR_EXAR_485;
+ else
+ value &= ~UART_FCTR_EXAR_485;
+
+ writeb(value, p + UART_EXAR_FCTR);
+
+ if (is_rs485)
+ writeb(UART_EXAR_RS485_DLY(4), p + UART_MSR);
+
+ return 0;
+}
+
+static const struct serial_rs485 generic_rs485_supported = {
+ .flags = SER_RS485_ENABLED | SER_RS485_RTS_ON_SEND,
};

static void exar_pm(struct uart_port *port, unsigned int state, unsigned int old)
@@ -182,8 +452,8 @@ static void xr17v35x_set_divisor(struct uart_port *p, unsigned int baud,
serial8250_do_set_divisor(p, baud, quot, quot_frac);

/* Preserve bits not related to baudrate; DLD[7:4]. */
- quot_frac |= serial_port_in(p, 0x2) & 0xf0;
- serial_port_out(p, 0x2, quot_frac);
+ quot_frac |= serial_port_in(p, UART_EXAR_DLD) & 0xf0;
+ serial_port_out(p, UART_EXAR_DLD, quot_frac);
}

static int xr17v35x_startup(struct uart_port *port)
@@ -312,15 +582,644 @@ pci_fastcom335_setup(struct exar8250 *priv, struct pci_dev *pcidev,
return 0;
}

-static int
-pci_connect_tech_setup(struct exar8250 *priv, struct pci_dev *pcidev,
- struct uart_8250_port *port, int idx)
+/**
+ * cti_set_tristate() - Enable/Disable RS485 transciever tristate
+ * @priv: Device's private structure
+ * @port_num: Port number to set tristate on/off
+ * @enable: Enable tristate if true, disable if false
+ *
+ * Most RS485 capable cards have a power on tristate jumper/switch that ensures
+ * the RS422/RS485 transciever does not drive a multi-drop RS485 bus when it is
+ * not the master. When this jumper is installed the user must set the RS485
+ * mode to disable tristate prior to using the port.
+ *
+ * Some Exar UARTs have an auto-tristate feature while others require setting
+ * an MPIO to disable the tristate.
+ *
+ * Return: 0 on success, negative error code on failure
+ */
+static int cti_set_tristate(struct exar8250 *priv,
+ unsigned int port_num, bool enable)
{
- unsigned int offset = idx * 0x200;
- unsigned int baud = 1843200;
+ int ret = 0;

- port->port.uartclk = baud * 16;
- return default_setup(priv, pcidev, idx, offset, port);
+ if (!priv || (port_num >= priv->nr))
+ return -EINVAL;
+
+ //Only Exar based cards use MPIO, return 0 otherwise
+ if (priv->pcidev->vendor != PCI_VENDOR_ID_EXAR)
+ return 0;
+
+ pci_dbg(priv->pcidev, "%s tristate for port %u\n",
+ (enable ? "enabling" : "disabling"), port_num);
+
+ ret = exar_mpio_set(priv, port_num, !enable);
+ if (ret)
+ return ret;
+
+ //ensure MPIO is an output
+ ret = exar_mpio_config(priv, port_num, true);
+
+ return ret;
+}
+
+/**
+ * cti_set_plx_int_enable() - Enable/Disable PCI interrupts
+ * @priv: Device's private structure
+ * @enable: Enable interrupts if true, disable if false
+ *
+ * Some older CTI cards require MPIO_0 to be set low to enable the PCI
+ * interupts from the UART to the PLX PCI->PCIe bridge.
+ *
+ * Return: 0 on success, negative error code on failure
+ */
+static int cti_set_plx_int_enable(struct exar8250 *priv, bool enable)
+{
+ int ret = 0;
+
+ if (!priv)
+ return -EINVAL;
+
+ //Only Exar based cards use MPIO, return 0 otherwise
+ if (priv->pcidev->vendor != PCI_VENDOR_ID_EXAR)
+ return 0;
+
+ pci_dbg(priv->pcidev, "%s plx fix\n",
+ (enable ? "enabling" : "disabling"));
+
+ //INT enabled when MPIO0 is LOW
+ ret = exar_mpio_set(priv, 0, !enable);
+ if (ret)
+ return ret;
+
+ //ensure MPIO is an output
+ ret = exar_mpio_config(priv, 0, true);
+
+ return ret;
+}
+
+/**
+ * cti_read_osc_freq() - Read the UART oscillator frequency from EEPROM
+ * @priv: Device's private structure
+ *
+ * CTI XR17x15X and XR17V25X cards have the serial boards oscillator frequency
+ * stored in the EEPROM. FPGA and XR17V35X based cards use the PCI/PCIe clock.
+ *
+ * Return: frequency on success, negative error code on failure
+ */
+static int cti_read_osc_freq(struct exar8250 *priv, uint8_t eeprom_offset)
+{
+ int osc_freq;
+
+ if (!priv)
+ return -EINVAL;
+
+ osc_freq = (exar_ee_read(priv, eeprom_offset));
+ osc_freq |= (exar_ee_read(priv, (eeprom_offset + 1)) << 16);
+
+ //check if EEPROM word was blank
+ if ((osc_freq == 0xFFFF) || (osc_freq == 0x0000))
+ return -EIO;
+
+ pci_dbg(priv->pcidev, "osc_freq from EEPROM %d\n", osc_freq);
+
+ return osc_freq;
+}
+
+static inline const char *cti_serial_port_type_to_str(enum cti_port_type type)
+{
+ switch (type) {
+ case CTI_PORT_TYPE_NONE:
+ return "NONE";
+ case CTI_PORT_TYPE_RS232:
+ return "RS232";
+ case CTI_PORT_TYPE_RS422_485:
+ return "RS422/485";
+ case CTI_PORT_TYPE_RS232_422_485_HW:
+ return "RS232/422/485 HW";
+ case CTI_PORT_TYPE_RS232_422_485_SW:
+ return "RS232/422/485 SW";
+ case CTI_PORT_TYPE_RS232_422_485_4B:
+ return "RS232/422/485 HW/SW (4 bit)";
+ case CTI_PORT_TYPE_RS232_422_485_2B:
+ return "RS232/422/485 HW/SW (2 bit)";
+ default:
+ break;
+ }
+
+ return "UNKNOWN";
+}
+
+/**
+ * cti_get_port_type_xr17c15x_xr17v25x() - Get the port type of a xr17c15x
+ * or xr17v25x card
+ *
+ * @priv: Device's private structure
+ * @port_num: Port to get type of
+ *
+ * CTI xr17c15x and xr17v25x based cards port types are based on PCI IDs
+ *
+ * Return: port type on success, CTI_PORT_TYPE_NONE on failure
+ */
+
+static enum cti_port_type cti_get_port_type_xr17c15x_xr17v25x(struct exar8250 *priv,
+ unsigned int port_num)
+{
+ enum cti_port_type port_type;
+
+ if (!priv)
+ return CTI_PORT_TYPE_NONE;
+
+ switch (priv->pcidev->subsystem_device) {
+ //RS232 only cards
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_232:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_232:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_232:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_SP_232:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_SP_232_NS:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_XPRS_LP_232:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_XPRS_LP_232_NS:
+ port_type = CTI_PORT_TYPE_RS232;
+ break;
+ //1x RS232, 1x RS422/RS485
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_1_1:
+ port_type = (port_num == 0) ?
+ CTI_PORT_TYPE_RS232 : CTI_PORT_TYPE_RS422_485;
+ break;
+ //2x RS232, 2x RS422/RS485
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_2:
+ port_type = (port_num < 2) ?
+ CTI_PORT_TYPE_RS232 : CTI_PORT_TYPE_RS422_485;
+ break;
+ //4x RS232, 4x RS422/RS485
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_4:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_4_SP:
+ port_type = (port_num < 4) ?
+ CTI_PORT_TYPE_RS232 : CTI_PORT_TYPE_RS422_485;
+ break;
+ //RS232/RS422/RS485 HW (jumper) selectable
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_SP_OPTO:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_SP_OPTO_A:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_SP_OPTO_B:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_XPRS:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_XPRS_A:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_XPRS_B:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_XPRS:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_16_XPRS_A:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_16_XPRS_B:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_XPRS_OPTO:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_XPRS_OPTO_A:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_XPRS_OPTO_B:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_SP:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_XP_OPTO_LEFT:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_XP_OPTO_RIGHT:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_XP_OPTO:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_4_XPRS_OPTO:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_XPRS_LP:
+ port_type = CTI_PORT_TYPE_RS232_422_485_HW;
+ break;
+ //RS422/RS485 HW (jumper) selectable
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_485:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_485:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_485:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_SP_485:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_XPRS_LP_485:
+ port_type = CTI_PORT_TYPE_RS422_485;
+ break;
+ //6x RS232, 2x RS422/RS485
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_6_2_SP:
+ port_type = (port_num < 6) ?
+ CTI_PORT_TYPE_RS232 : CTI_PORT_TYPE_RS422_485;
+ break;
+ //2x RS232, 6x RS422/RS485
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_6_SP:
+ port_type = (port_num < 2) ?
+ CTI_PORT_TYPE_RS232 : CTI_PORT_TYPE_RS422_485;
+ break;
+ default:
+ pci_err(priv->pcidev, "unknown/unsupported device\n");
+ port_type = CTI_PORT_TYPE_NONE;
+ }
+
+ return port_type;
+}
+
+/**
+ * cti_get_port_type_fpga() - Get the port type of a CTI FPGA card
+ * @priv: Device's private structure
+ * @port_num: Port to get type of
+ *
+ * FPGA based cards port types are based on PCI IDs
+ *
+ * Return: port type on success, CTI_PORT_TYPE_NONE on failure
+ */
+static enum cti_port_type cti_get_port_type_fpga(struct exar8250 *priv,
+ unsigned int port_num)
+{
+ enum cti_port_type port_type;
+
+ if (!priv)
+ return CTI_PORT_TYPE_NONE;
+
+ switch (priv->pcidev->device) {
+ case PCI_DEVICE_ID_CONNECT_TECH_PCI_XR79X_12_XIG00X:
+ case PCI_DEVICE_ID_CONNECT_TECH_PCI_XR79X_12_XIG01X:
+ case PCI_DEVICE_ID_CONNECT_TECH_PCI_XR79X_16:
+ port_type = CTI_PORT_TYPE_RS232_422_485_HW;
+ break;
+ default:
+ pci_err(priv->pcidev, "unknown/unsupported device\n");
+ return CTI_PORT_TYPE_NONE;
+ }
+
+ return port_type;
+}
+
+/**
+ * cti_get_port_type_xr17v35x() - Read port type from the EEPROM
+ * @priv: Device's private structure
+ * @port_num: port offset
+ *
+ * CTI XR17V35X based cards have the port types stored in the EEPROM.
+ * This function reads the port type for a single port.
+ *
+ * Return: port type on success, CTI_PORT_TYPE_NONE on failure
+ */
+static enum cti_port_type cti_get_port_type_xr17v35x(struct exar8250 *priv,
+ unsigned int port_num)
+{
+ uint16_t port_flags;
+ uint8_t offset;
+ enum cti_port_type port_type;
+
+ if (!priv)
+ return CTI_PORT_TYPE_NONE;
+
+ offset = CTI_EE_OFF_XR17V35X_PORT_FLAGS + port_num;
+ port_flags = exar_ee_read(priv, offset);
+
+ port_type = (port_flags & 0x00FF);
+
+ if (!CTI_PORT_TYPE_VALID(port_type)) {
+ /*
+ * If the port type is missing the card assume it is a
+ * RS232/RS422/RS485 card to be safe.
+ *
+ * There is one known board (BEG013) that only has
+ * 3 of 4 port types written to the EEPROM so this
+ * acts as a work around.
+ */
+ pci_warn(priv->pcidev,
+ "failed to get port %d type from EEPROM\n", port_num);
+ port_type = CTI_PORT_TYPE_RS232_422_485_HW;
+ }
+
+ return port_type;
+}
+
+static int cti_rs485_config_mpio_tristate(struct uart_port *port,
+ struct ktermios *termios,
+ struct serial_rs485 *rs485)
+{
+ struct exar8250 *priv;
+ int ret;
+
+ priv = (struct exar8250 *)port->private_data;
+ if (!priv)
+ return -EINVAL;
+
+ ret = generic_rs485_config(port, termios, rs485);
+ if (ret)
+ return ret;
+
+ //disable power-on tri-state via MPIO
+ return cti_set_tristate(priv, port->port_id, false);
+}
+
+static int cti_port_setup_common(struct exar8250 *priv,
+ int idx, unsigned int offset,
+ struct uart_8250_port *port)
+{
+ int ret;
+
+ if (!priv || !port)
+ return -EINVAL;
+
+ if (priv->osc_freq == 0)
+ return -EINVAL;
+
+ port->port.port_id = idx;
+ port->port.uartclk = priv->osc_freq;
+
+ ret = serial8250_pci_setup_port(priv->pcidev, port, 0, offset, 0);
+ if (ret) {
+ pci_err(priv->pcidev,
+ "failed to setup pci for port %d err: %d\n", idx, ret);
+ return ret;
+ }
+
+ port->port.private_data = (void *)priv;
+ port->port.pm = exar_pm;
+ port->port.shutdown = exar_shutdown;
+
+ return 0;
+}
+
+static int cti_port_setup_fpga(struct exar8250 *priv,
+ struct pci_dev *pcidev,
+ struct uart_8250_port *port,
+ int idx)
+{
+ enum cti_port_type port_type;
+ unsigned int offset;
+
+ port_type = cti_get_port_type_fpga(priv, idx);
+
+ pci_dbg(priv->pcidev, "Setting up CTI FPGA Port %d, Type: %s\n",
+ idx, cti_serial_port_type_to_str(port_type));
+
+ //FPGA shares port offests with XR17C15X
+ offset = idx * UART_EXAR_XR17C15X_PORT_OFFSET;
+ port->port.type = PORT_XR17D15X;
+
+ port->port.get_divisor = xr17v35x_get_divisor;
+ port->port.set_divisor = xr17v35x_set_divisor;
+ port->port.startup = xr17v35x_startup;
+
+ //TODO: Add support for setting line mode on cards that support it
+ if (CTI_PORT_TYPE_RS485(port_type)) {
+ port->port.rs485_config = generic_rs485_config;
+ port->port.rs485_supported = generic_rs485_supported;
+ }
+
+ return cti_port_setup_common(priv, idx, offset, port);
+}
+
+static int cti_port_setup_xr17v35x(struct exar8250 *priv,
+ struct pci_dev *pcidev,
+ struct uart_8250_port *port,
+ int idx)
+{
+ enum cti_port_type port_type;
+ unsigned int offset;
+ int ret;
+
+ port_type = cti_get_port_type_xr17v35x(priv, idx);
+
+ pci_dbg(priv->pcidev, "Setting up CTI XR17V35X Port %d, Type: %s\n",
+ idx, cti_serial_port_type_to_str(port_type));
+
+ offset = idx * UART_EXAR_XR17V35X_PORT_OFFSET;
+ port->port.type = PORT_XR17V35X;
+
+ port->port.get_divisor = xr17v35x_get_divisor;
+ port->port.set_divisor = xr17v35x_set_divisor;
+ port->port.startup = xr17v35x_startup;
+
+ switch (port_type) {
+ case CTI_PORT_TYPE_RS422_485:
+ case CTI_PORT_TYPE_RS232_422_485_HW:
+ port->port.rs485_config = cti_rs485_config_mpio_tristate;
+ port->port.rs485_supported = generic_rs485_supported;
+ break;
+ //TODO: Add support for setting line mode on cards that support it
+ case CTI_PORT_TYPE_RS232_422_485_SW:
+ case CTI_PORT_TYPE_RS232_422_485_4B:
+ case CTI_PORT_TYPE_RS232_422_485_2B:
+ port->port.rs485_config = generic_rs485_config;
+ port->port.rs485_supported = generic_rs485_supported;
+ break;
+ default:
+ break;
+ }
+
+ ret = cti_port_setup_common(priv, idx, offset, port);
+ if (ret)
+ return ret;
+
+ exar_write_reg(priv, (offset + UART_EXAR_8XMODE), 0x00);
+ exar_write_reg(priv, (offset + UART_EXAR_FCTR), UART_FCTR_EXAR_TRGD);
+ exar_write_reg(priv, (offset + UART_EXAR_TXTRG), 128);
+ exar_write_reg(priv, (offset + UART_EXAR_RXTRG), 128);
+
+ return 0;
+}
+
+static int cti_port_setup_xr17v25x(struct exar8250 *priv,
+ struct pci_dev *pcidev,
+ struct uart_8250_port *port,
+ int idx)
+{
+ enum cti_port_type port_type;
+ unsigned int offset;
+ int ret;
+
+ port_type = cti_get_port_type_xr17c15x_xr17v25x(priv, idx);
+
+ pci_dbg(priv->pcidev, "Setting up CTI XR17V25X Port %d, Type: %s\n",
+ idx, cti_serial_port_type_to_str(port_type));
+
+ offset = idx * UART_EXAR_XR17V25X_PORT_OFFSET;
+ port->port.type = PORT_XR17D15X;
+
+ //xr17v25x supports fractional baudrates
+ port->port.get_divisor = xr17v35x_get_divisor;
+ port->port.set_divisor = xr17v35x_set_divisor;
+ port->port.startup = xr17v35x_startup;
+
+ if (CTI_PORT_TYPE_RS485(port_type)) {
+ switch (priv->pcidev->subsystem_device) {
+ //These cards support power on 485 tri-state via MPIO
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_SP:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_SP_485:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_4_SP:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_6_2_SP:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_6_SP:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_XP_OPTO_LEFT:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_XP_OPTO_RIGHT:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_XP_OPTO:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_4_XPRS_OPTO:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_XPRS_LP:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_XPRS_LP_485:
+ port->port.rs485_config = cti_rs485_config_mpio_tristate;
+ break;
+ //Otherwise auto or no power on 485 tri-state support
+ default:
+ port->port.rs485_config = generic_rs485_config;
+ break;
+ }
+
+ port->port.rs485_supported = generic_rs485_supported;
+ }
+
+ ret = cti_port_setup_common(priv, idx, offset, port);
+ if (ret)
+ return ret;
+
+ exar_write_reg(priv, (offset + UART_EXAR_8XMODE), 0x00);
+ exar_write_reg(priv, (offset + UART_EXAR_FCTR), UART_FCTR_EXAR_TRGD);
+ exar_write_reg(priv, (offset + UART_EXAR_TXTRG), 32);
+ exar_write_reg(priv, (offset + UART_EXAR_RXTRG), 32);
+
+ return 0;
+}
+
+static int cti_port_setup_xr17c15x(struct exar8250 *priv,
+ struct pci_dev *pcidev,
+ struct uart_8250_port *port,
+ int idx)
+{
+ enum cti_port_type port_type;
+ unsigned int offset;
+
+ port_type = cti_get_port_type_xr17c15x_xr17v25x(priv, idx);
+
+ pci_dbg(priv->pcidev, "Setting up CTI XR17V15X Port %d, Type: %s\n",
+ idx, cti_serial_port_type_to_str(port_type));
+
+ offset = idx * UART_EXAR_XR17C15X_PORT_OFFSET;
+ port->port.type = PORT_XR17D15X;
+
+ if (CTI_PORT_TYPE_RS485(port_type)) {
+ switch (priv->pcidev->subsystem_device) {
+ //These cards support power on 485 tri-state via MPIO
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_SP:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_SP_485:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_4_SP:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_6_2_SP:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_6_SP:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_XP_OPTO_LEFT:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_XP_OPTO_RIGHT:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_XP_OPTO:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_4_XPRS_OPTO:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_XPRS_LP:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_XPRS_LP_485:
+ port->port.rs485_config = cti_rs485_config_mpio_tristate;
+ break;
+ //Otherwise auto or no power on 485 tri-state support
+ default:
+ port->port.rs485_config = generic_rs485_config;
+ break;
+ }
+
+ port->port.rs485_supported = generic_rs485_supported;
+ }
+
+ return cti_port_setup_common(priv, idx, offset, port);
+}
+
+static int cti_board_setup_xr17v35x(struct exar8250 *priv)
+{
+ if (!priv)
+ return -EINVAL;
+
+ //XR17V35X use the PCIe clock rather than crystal
+ priv->osc_freq = CTI_DEFAULT_PCIE_OSC_FREQ;
+
+ return 0;
+}
+
+static int cti_board_setup_xr17v25x(struct exar8250 *priv)
+{
+ int osc_freq;
+
+ if (!priv)
+ return -EINVAL;
+
+ osc_freq = cti_read_osc_freq(priv, CTI_EE_OFF_XR17V25X_OSC_FREQ);
+ if (osc_freq < 0) {
+ pci_warn(priv->pcidev,
+ "failed to read osc freq from EEPROM, using default\n");
+ osc_freq = CTI_DEFAULT_PCI_OSC_FREQ;
+ }
+
+ priv->osc_freq = osc_freq;
+
+ /* enable interupts on cards that need the "PLX fix" */
+ switch (priv->pcidev->subsystem_device) {
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_XPRS:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_XPRS_A:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_XPRS_B:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_XPRS:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_16_XPRS_A:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_16_XPRS_B:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_XPRS_OPTO:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_XPRS_OPTO_A:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_XPRS_OPTO_B:
+ cti_set_plx_int_enable(priv, true);
+ break;
+ default:
+ break;
+ }
+
+ return 0;
+}
+
+static int cti_board_setup_xr17c15x(struct exar8250 *priv)
+{
+ int osc_freq;
+
+ if (!priv)
+ return -EINVAL;
+
+ osc_freq = cti_read_osc_freq(priv, CTI_EE_OFF_XR17C15X_OSC_FREQ);
+ if (osc_freq <= 0) {
+ pci_warn(priv->pcidev,
+ "failed to read osc freq from EEPROM, using default\n");
+ osc_freq = CTI_DEFAULT_PCI_OSC_FREQ;
+ }
+
+ priv->osc_freq = osc_freq;
+
+ /* enable interrupts on cards that need the "PLX fix" */
+ switch (priv->pcidev->subsystem_device) {
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_XPRS:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_XPRS_A:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_XPRS_B:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_8_XPRS:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_16_XPRS_A:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_16_XPRS_B:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_2_XPRS_OPTO:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_XPRS_OPTO_A:
+ case PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_UART_4_XPRS_OPTO_B:
+ cti_set_plx_int_enable(priv, true);
+ break;
+ default:
+ break;
+ }
+
+ return 0;
+}
+
+static int cti_board_setup_fpga(struct exar8250 *priv)
+{
+ int ret;
+ uint16_t cfg_val;
+
+ if (!priv)
+ return -EINVAL;
+
+ //FPGA OSC is fixed to the 33MHz PCI clock
+ priv->osc_freq = CTI_DEFAULT_FPGA_OSC_FREQ;
+
+ //Enable external interrupts in special cfg space register
+ ret = pci_read_config_word(priv->pcidev, 0x48, &cfg_val);
+ if (ret)
+ return ret;
+
+ cfg_val |= BIT(15);
+
+ ret = pci_write_config_word(priv->pcidev, 0x48, cfg_val);
+ if (ret)
+ return ret;
+
+ //RS485 gate needs to be enabled; otherwise RTS/CTS will not work
+ exar_write_reg(priv, CTI_FPGA_RS485_IO_REG, 0x01);
+
+ return 0;
}

static int
@@ -422,26 +1321,6 @@ static void xr17v35x_unregister_gpio(struct uart_8250_port *port)
port->port.private_data = NULL;
}

-static int generic_rs485_config(struct uart_port *port, struct ktermios *termios,
- struct serial_rs485 *rs485)
-{
- bool is_rs485 = !!(rs485->flags & SER_RS485_ENABLED);
- u8 __iomem *p = port->membase;
- u8 value;
-
- value = readb(p + UART_EXAR_FCTR);
- if (is_rs485)
- value |= UART_FCTR_EXAR_485;
- else
- value &= ~UART_FCTR_EXAR_485;
-
- writeb(value, p + UART_EXAR_FCTR);
-
- if (is_rs485)
- writeb(UART_EXAR_RS485_DLY(4), p + UART_MSR);
-
- return 0;
-}

static int sealevel_rs485_config(struct uart_port *port, struct ktermios *termios,
struct serial_rs485 *rs485)
@@ -481,10 +1360,6 @@ static int sealevel_rs485_config(struct uart_port *port, struct ktermios *termio
return 0;
}

-static const struct serial_rs485 generic_rs485_supported = {
- .flags = SER_RS485_ENABLED | SER_RS485_RTS_ON_SEND,
-};
-
static const struct exar8250_platform exar8250_default_platform = {
.register_gpio = xr17v35x_register_gpio,
.unregister_gpio = xr17v35x_unregister_gpio,
@@ -669,6 +1544,39 @@ static irqreturn_t exar_misc_handler(int irq, void *data)
return IRQ_HANDLED;
}

+static unsigned int exar_get_nr_ports(struct exar8250_board *board,
+ struct pci_dev *pcidev)
+{
+ unsigned int nr_ports = 0;
+
+ if (!board || !pcidev)
+ return 0;
+
+ if (pcidev->vendor == PCI_VENDOR_ID_ACCESSIO) {
+ nr_ports = BIT(((pcidev->device & 0x38) >> 3) - 1);
+ } else if (board->num_ports > 0) {
+ //Check if board struct overrides number of ports
+ nr_ports = board->num_ports;
+ } else if (pcidev->vendor == PCI_VENDOR_ID_EXAR) {
+ //Exar encodes # ports in last nibble of PCI Device ID ex. 0358
+ nr_ports = pcidev->device & 0x0f;
+ } else if (pcidev->vendor == PCI_VENDOR_ID_CONNECT_TECH) {
+ //Handle CTI FPGA cards
+ switch (pcidev->device) {
+ case PCI_DEVICE_ID_CONNECT_TECH_PCI_XR79X_12_XIG00X:
+ case PCI_DEVICE_ID_CONNECT_TECH_PCI_XR79X_12_XIG01X:
+ nr_ports = 12;
+ break;
+ case PCI_DEVICE_ID_CONNECT_TECH_PCI_XR79X_16:
+ nr_ports = 16;
+ default:
+ break;
+ }
+ }
+
+ return nr_ports;
+}
+
static int
exar_pci_probe(struct pci_dev *pcidev, const struct pci_device_id *ent)
{
@@ -688,18 +1596,18 @@ exar_pci_probe(struct pci_dev *pcidev, const struct pci_device_id *ent)

maxnr = pci_resource_len(pcidev, bar) >> (board->reg_shift + 3);

- if (pcidev->vendor == PCI_VENDOR_ID_ACCESSIO)
- nr_ports = BIT(((pcidev->device & 0x38) >> 3) - 1);
- else if (board->num_ports)
- nr_ports = board->num_ports;
- else
- nr_ports = pcidev->device & 0x0f;
+ nr_ports = exar_get_nr_ports(board, pcidev);
+ if (nr_ports == 0) {
+ pci_err(pcidev, "failed to get number of ports\n");
+ return -ENODEV;
+ }

priv = devm_kzalloc(&pcidev->dev, struct_size(priv, line, nr_ports), GFP_KERNEL);
if (!priv)
return -ENOMEM;

priv->board = board;
+ priv->pcidev = pcidev;
priv->virt = pcim_iomap(pcidev, bar, 0);
if (!priv->virt)
return -ENOMEM;
@@ -723,6 +1631,15 @@ exar_pci_probe(struct pci_dev *pcidev, const struct pci_device_id *ent)
if (rc)
return rc;

+ if (board->board_setup) {
+ rc = board->board_setup(priv);
+ if (rc) {
+ pci_err(pcidev,
+ "failed to setup serial board: %d\n", rc);
+ return rc;
+ }
+ }
+
for (i = 0; i < nr_ports && i < maxnr; i++) {
rc = board->setup(priv, pcidev, &uart, i);
if (rc) {
@@ -730,12 +1647,12 @@ exar_pci_probe(struct pci_dev *pcidev, const struct pci_device_id *ent)
break;
}

- dev_dbg(&pcidev->dev, "Setup PCI port: port %lx, irq %d, type %d\n",
+ pci_dbg(pcidev, "Setup PCI port: port %lx, irq %d, type %d\n",
uart.port.iobase, uart.port.irq, uart.port.iotype);

priv->line[i] = serial8250_register_8250_port(&uart);
if (priv->line[i] < 0) {
- dev_err(&pcidev->dev,
+ pci_err(pcidev,
"Couldn't register serial port %lx, irq %d, type %d, error %d\n",
uart.port.iobase, uart.port.irq,
uart.port.iotype, priv->line[i]);
@@ -753,7 +1670,8 @@ static void exar_pci_remove(struct pci_dev *pcidev)
unsigned int i;

for (i = 0; i < priv->nr; i++)
- serial8250_unregister_port(priv->line[i]);
+ if (priv->line[i] >= 0)
+ serial8250_unregister_port(priv->line[i]);

/* Ensure that every init quirk is properly torn down */
if (priv->board->exit)
@@ -803,8 +1721,24 @@ static const struct exar8250_board pbn_fastcom335_8 = {
.setup = pci_fastcom335_setup,
};

-static const struct exar8250_board pbn_connect = {
- .setup = pci_connect_tech_setup,
+static const struct exar8250_board pbn_cti_xr17c15x = {
+ .board_setup = cti_board_setup_xr17c15x,
+ .setup = cti_port_setup_xr17c15x,
+};
+
+static const struct exar8250_board pbn_cti_xr17v25x = {
+ .board_setup = cti_board_setup_xr17v25x,
+ .setup = cti_port_setup_xr17v25x,
+};
+
+static const struct exar8250_board pbn_cti_xr17v35x = {
+ .board_setup = cti_board_setup_xr17v35x,
+ .setup = cti_port_setup_xr17v35x,
+};
+
+static const struct exar8250_board pbn_cti_fpga = {
+ .board_setup = cti_board_setup_fpga,
+ .setup = cti_port_setup_fpga,
};

static const struct exar8250_board pbn_exar_ibm_saturn = {
@@ -851,15 +1785,27 @@ static const struct exar8250_board pbn_exar_XR17V8358 = {
.exit = pci_xr17v35x_exit,
};

-#define CONNECT_DEVICE(devid, sdevid, bd) { \
- PCI_DEVICE_SUB( \
- PCI_VENDOR_ID_EXAR, \
- PCI_DEVICE_ID_EXAR_##devid, \
- PCI_SUBVENDOR_ID_CONNECT_TECH, \
- PCI_SUBDEVICE_ID_CONNECT_TECH_PCI_##sdevid), 0, 0, \
- (kernel_ulong_t)&bd \
+//For Connect Tech cards with Exar vendor/device PCI IDs
+#define CTI_EXAR_DEVICE(devid, bd) { \
+ PCI_DEVICE_SUB( \
+ PCI_VENDOR_ID_EXAR, \
+ PCI_DEVICE_ID_EXAR_##devid, \
+ PCI_SUBVENDOR_ID_CONNECT_TECH, \
+ PCI_ANY_ID), 0, 0, \
+ (kernel_ulong_t)&bd \
}

+//For Connect Tech cards with Connect Tech vendor/device PCI IDs (FPGA based)
+#define CTI_PCI_DEVICE(devid, bd) { \
+ PCI_DEVICE_SUB( \
+ PCI_VENDOR_ID_CONNECT_TECH, \
+ PCI_DEVICE_ID_CONNECT_TECH_PCI_##devid, \
+ PCI_ANY_ID, \
+ PCI_ANY_ID), 0, 0, \
+ (kernel_ulong_t)&bd \
+ }
+
+
#define EXAR_DEVICE(vend, devid, bd) { PCI_DEVICE_DATA(vend, devid, &bd) }

#define IBM_DEVICE(devid, sdevid, bd) { \
@@ -889,18 +1835,21 @@ static const struct pci_device_id exar_pci_tbl[] = {
EXAR_DEVICE(ACCESSIO, COM_4SM, pbn_exar_XR17C15x),
EXAR_DEVICE(ACCESSIO, COM_8SM, pbn_exar_XR17C15x),

- CONNECT_DEVICE(XR17C152, UART_2_232, pbn_connect),
- CONNECT_DEVICE(XR17C154, UART_4_232, pbn_connect),
- CONNECT_DEVICE(XR17C158, UART_8_232, pbn_connect),
- CONNECT_DEVICE(XR17C152, UART_1_1, pbn_connect),
- CONNECT_DEVICE(XR17C154, UART_2_2, pbn_connect),
- CONNECT_DEVICE(XR17C158, UART_4_4, pbn_connect),
- CONNECT_DEVICE(XR17C152, UART_2, pbn_connect),
- CONNECT_DEVICE(XR17C154, UART_4, pbn_connect),
- CONNECT_DEVICE(XR17C158, UART_8, pbn_connect),
- CONNECT_DEVICE(XR17C152, UART_2_485, pbn_connect),
- CONNECT_DEVICE(XR17C154, UART_4_485, pbn_connect),
- CONNECT_DEVICE(XR17C158, UART_8_485, pbn_connect),
+ CTI_EXAR_DEVICE(XR17C152, pbn_cti_xr17c15x),
+ CTI_EXAR_DEVICE(XR17C154, pbn_cti_xr17c15x),
+ CTI_EXAR_DEVICE(XR17C158, pbn_cti_xr17c15x),
+
+ CTI_EXAR_DEVICE(XR17V252, pbn_cti_xr17v25x),
+ CTI_EXAR_DEVICE(XR17V254, pbn_cti_xr17v25x),
+ CTI_EXAR_DEVICE(XR17V258, pbn_cti_xr17v25x),
+
+ CTI_EXAR_DEVICE(XR17V352, pbn_cti_xr17v35x),
+ CTI_EXAR_DEVICE(XR17V354, pbn_cti_xr17v35x),
+ CTI_EXAR_DEVICE(XR17V358, pbn_cti_xr17v35x),
+
+ CTI_PCI_DEVICE(XR79X_12_XIG00X, pbn_cti_fpga),
+ CTI_PCI_DEVICE(XR79X_12_XIG01X, pbn_cti_fpga),
+ CTI_PCI_DEVICE(XR79X_16, pbn_cti_fpga),

IBM_DEVICE(XR17C152, SATURN_SERIAL_ONE_PORT, pbn_exar_ibm_saturn),

--
2.43.2



2024-04-11 17:25:19

by Greg Kroah-Hartman

[permalink] [raw]
Subject: Re: [PATCH 2/2] serial: exar: adding CTI PCI/PCIe serial port support to 8250_exar

On Thu, Apr 11, 2024 at 11:29:27AM -0400, [email protected] wrote:
> From: Parker Newman <[email protected]>
>
> This patch adds support for most of Connect Tech's (CTI) PCI/PCIe
> serial cards to the 8250_exar driver.
>
> Major changes:
> - Added (optional) board_setup function called once during probe
> - Added exar_get_nr_ports function
> - Removed old Connect Tech setup functions
> - Added new UART family based CTI setup functions
> - Added PCI IDs entries for Exar XR17V25x and CTI FPGA based cards
> - Added MPIO functions for configuring/setting a single MPIO
> - Added support for reading from the Exar EEPROM

When you need to list the different things you did in a single patch,
that's a huge hint it needs to be broken up into smaller, easier to
review, pieces.

>
> Signed-off-by: Parker Newman <[email protected]>
> ---
> drivers/tty/serial/8250/8250_exar.c | 1089 +++++++++++++++++++++++++--
> 1 file changed, 1019 insertions(+), 70 deletions(-)

Reviewing 1000 lines of changes at once that does different things,
isn't easy. Please break this up into smaller,
one-logical-step-at-a-time patches.

thanks,

greg k-h

2024-04-11 18:47:03

by Parker Newman

[permalink] [raw]
Subject: Re: [PATCH 2/2] serial: exar: adding CTI PCI/PCIe serial port support to 8250_exar

On Thu, 11 Apr 2024 17:55:54 +0200
Greg Kroah-Hartman <[email protected]> wrote:

> On Thu, Apr 11, 2024 at 11:29:27AM -0400, [email protected] wrote:
> > From: Parker Newman <[email protected]>
> >
> > This patch adds support for most of Connect Tech's (CTI) PCI/PCIe
> > serial cards to the 8250_exar driver.
> >
> > Major changes:
> > - Added (optional) board_setup function called once during probe
> > - Added exar_get_nr_ports function
> > - Removed old Connect Tech setup functions
> > - Added new UART family based CTI setup functions
> > - Added PCI IDs entries for Exar XR17V25x and CTI FPGA based cards
> > - Added MPIO functions for configuring/setting a single MPIO
> > - Added support for reading from the Exar EEPROM
>
> When you need to list the different things you did in a single patch,
> that's a huge hint it needs to be broken up into smaller, easier to
> review, pieces.
>
> >
> > Signed-off-by: Parker Newman <[email protected]>
> > ---
> > drivers/tty/serial/8250/8250_exar.c | 1089 +++++++++++++++++++++++++--
> > 1 file changed, 1019 insertions(+), 70 deletions(-)
>
> Reviewing 1000 lines of changes at once that does different things,
> isn't easy. Please break this up into smaller,
> one-logical-step-at-a-time patches.
>
> thanks,
>
> greg k-h

I will try to split it up better and submit a v2.

Thank you,
- Parker

2024-04-12 04:53:43

by kernel test robot

[permalink] [raw]
Subject: Re: [PATCH 2/2] serial: exar: adding CTI PCI/PCIe serial port support to 8250_exar

Hi,

kernel test robot noticed the following build warnings:

[auto build test WARNING on tty/tty-testing]
[also build test WARNING on tty/tty-next tty/tty-linus usb/usb-testing usb/usb-next usb/usb-linus pci/next pci/for-linus linus/master v6.9-rc3 next-20240411]
[If your patch is applied to the wrong git tree, kindly drop us a note.
And when submitting patch, we suggest to use '--base' as documented in
https://git-scm.com/docs/git-format-patch#_base_tree_information]

url: https://github.com/intel-lab-lkp/linux/commits/parker-finest-io/serial-exar-add-missing-CTI-Exar-PCI-IDs-to-include-linux-pci_ids-h/20240412-011902
base: https://git.kernel.org/pub/scm/linux/kernel/git/gregkh/tty.git tty-testing
patch link: https://lore.kernel.org/r/9ffdef053f455c87f705dff169346bc10d307787.1712846026.git.pnewman%40connecttech.com
patch subject: [PATCH 2/2] serial: exar: adding CTI PCI/PCIe serial port support to 8250_exar
config: parisc-defconfig (https://download.01.org/0day-ci/archive/20240412/[email protected]/config)
compiler: hppa-linux-gcc (GCC) 13.2.0
reproduce (this is a W=1 build): (https://download.01.org/0day-ci/archive/20240412/[email protected]/reproduce)

If you fix the issue in a separate patch/commit (i.e. not just a new version of
the same patch/commit), kindly add following tags
| Reported-by: kernel test robot <[email protected]>
| Closes: https://lore.kernel.org/oe-kbuild-all/[email protected]/

All warnings (new ones prefixed by >>):

>> drivers/tty/serial/8250/8250_exar.c:672: warning: Function parameter or struct member 'eeprom_offset' not described in 'cti_read_osc_freq'


vim +672 drivers/tty/serial/8250/8250_exar.c

661
662 /**
663 * cti_read_osc_freq() - Read the UART oscillator frequency from EEPROM
664 * @priv: Device's private structure
665 *
666 * CTI XR17x15X and XR17V25X cards have the serial boards oscillator frequency
667 * stored in the EEPROM. FPGA and XR17V35X based cards use the PCI/PCIe clock.
668 *
669 * Return: frequency on success, negative error code on failure
670 */
671 static int cti_read_osc_freq(struct exar8250 *priv, uint8_t eeprom_offset)
> 672 {
673 int osc_freq;
674
675 if (!priv)
676 return -EINVAL;
677
678 osc_freq = (exar_ee_read(priv, eeprom_offset));
679 osc_freq |= (exar_ee_read(priv, (eeprom_offset + 1)) << 16);
680
681 //check if EEPROM word was blank
682 if ((osc_freq == 0xFFFF) || (osc_freq == 0x0000))
683 return -EIO;
684
685 pci_dbg(priv->pcidev, "osc_freq from EEPROM %d\n", osc_freq);
686
687 return osc_freq;
688 }
689

--
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests/wiki

2024-04-12 05:19:23

by kernel test robot

[permalink] [raw]
Subject: Re: [PATCH 2/2] serial: exar: adding CTI PCI/PCIe serial port support to 8250_exar

Hi,

kernel test robot noticed the following build warnings:

[auto build test WARNING on tty/tty-testing]
[also build test WARNING on tty/tty-next tty/tty-linus usb/usb-testing usb/usb-next usb/usb-linus pci/next pci/for-linus linus/master v6.9-rc3 next-20240411]
[If your patch is applied to the wrong git tree, kindly drop us a note.
And when submitting patch, we suggest to use '--base' as documented in
https://git-scm.com/docs/git-format-patch#_base_tree_information]

url: https://github.com/intel-lab-lkp/linux/commits/parker-finest-io/serial-exar-add-missing-CTI-Exar-PCI-IDs-to-include-linux-pci_ids-h/20240412-011902
base: https://git.kernel.org/pub/scm/linux/kernel/git/gregkh/tty.git tty-testing
patch link: https://lore.kernel.org/r/9ffdef053f455c87f705dff169346bc10d307787.1712846026.git.pnewman%40connecttech.com
patch subject: [PATCH 2/2] serial: exar: adding CTI PCI/PCIe serial port support to 8250_exar
config: riscv-defconfig (https://download.01.org/0day-ci/archive/20240412/[email protected]/config)
compiler: clang version 19.0.0git (https://github.com/llvm/llvm-project 8b3b4a92adee40483c27f26c478a384cd69c6f05)
reproduce (this is a W=1 build): (https://download.01.org/0day-ci/archive/20240412/[email protected]/reproduce)

If you fix the issue in a separate patch/commit (i.e. not just a new version of
the same patch/commit), kindly add following tags
| Reported-by: kernel test robot <[email protected]>
| Closes: https://lore.kernel.org/oe-kbuild-all/[email protected]/

All warnings (new ones prefixed by >>):

In file included from drivers/tty/serial/8250/8250_exar.c:13:
In file included from include/linux/interrupt.h:21:
In file included from arch/riscv/include/asm/sections.h:9:
In file included from include/linux/mm.h:2208:
include/linux/vmstat.h:522:36: warning: arithmetic between different enumeration types ('enum node_stat_item' and 'enum lru_list') [-Wenum-enum-conversion]
522 | return node_stat_name(NR_LRU_BASE + lru) + 3; // skip "nr_"
| ~~~~~~~~~~~ ^ ~~~
>> drivers/tty/serial/8250/8250_exar.c:1573:3: warning: unannotated fall-through between switch labels [-Wimplicit-fallthrough]
1573 | default:
| ^
drivers/tty/serial/8250/8250_exar.c:1573:3: note: insert 'break;' to avoid fall-through
1573 | default:
| ^
| break;
2 warnings generated.


vim +1573 drivers/tty/serial/8250/8250_exar.c

1547
1548 static unsigned int exar_get_nr_ports(struct exar8250_board *board,
1549 struct pci_dev *pcidev)
1550 {
1551 unsigned int nr_ports = 0;
1552
1553 if (!board || !pcidev)
1554 return 0;
1555
1556 if (pcidev->vendor == PCI_VENDOR_ID_ACCESSIO) {
1557 nr_ports = BIT(((pcidev->device & 0x38) >> 3) - 1);
1558 } else if (board->num_ports > 0) {
1559 //Check if board struct overrides number of ports
1560 nr_ports = board->num_ports;
1561 } else if (pcidev->vendor == PCI_VENDOR_ID_EXAR) {
1562 //Exar encodes # ports in last nibble of PCI Device ID ex. 0358
1563 nr_ports = pcidev->device & 0x0f;
1564 } else if (pcidev->vendor == PCI_VENDOR_ID_CONNECT_TECH) {
1565 //Handle CTI FPGA cards
1566 switch (pcidev->device) {
1567 case PCI_DEVICE_ID_CONNECT_TECH_PCI_XR79X_12_XIG00X:
1568 case PCI_DEVICE_ID_CONNECT_TECH_PCI_XR79X_12_XIG01X:
1569 nr_ports = 12;
1570 break;
1571 case PCI_DEVICE_ID_CONNECT_TECH_PCI_XR79X_16:
1572 nr_ports = 16;
> 1573 default:
1574 break;
1575 }
1576 }
1577
1578 return nr_ports;
1579 }
1580

--
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests/wiki