From a1a39ed3784b76b5b9c356ee9554fdca82f4dca0 Mon Sep 17 00:00:00 2001 From: Davide Cardillo <davide.cardillo@seco.com> Date: Tue, 2 Nov 2021 11:59:00 +0100 Subject: [PATCH] [i.MX6][CPLD][driver/seco] Add driver v1.0 for SECO CPLD LPC/GPIO This driver coming from SECO driver library: - driver: seco_cpld_imx6 - version: v1.0 This driver is generic but is used only by [i.MX6][928]. The WEIM bus is used to communicate with the CPLD. There are two CPLD's versions: - LPC bridge: a LPC bridge is implemented and the actual drivers compatible with this bus are: - sio_xr28v382: support for MaxLinear XR28V382 with x2 UARTs - sio_w83627: support for Nuvoton W83627 superIO - GPIO x8 + PWM: a GPIO expander plus a PWM controller are present into CPLD. In this case the driver are cgpio_expander.c and pwm_cpld.c respectively. The serial_core of the kernel has been modified inorder to support the specific UART type coming from LPC compatible driver. Since, as mentioned, this driver is used only by the [928] module, please, refer to its dts file about the device-tree, where there is the hierarchy: WEIM |__ CPLD |__ GPIO + PWM |__ LPC |__ XR28V382 |__ W83627 Note: all node on the same level are mutually exclusive --- drivers/seco/Kconfig | 9 + drivers/seco/Makefile | 2 + drivers/seco/cgpio_expander.c | 614 ++++++++++++++++++++++ drivers/seco/cpld.c | 305 +++++++++++ drivers/seco/lpc_bridge.c | 509 ++++++++++++++++++ drivers/seco/pwm_cpld.c | 289 +++++++++++ drivers/seco/sio_w83627.c | 461 ++++++++++++++++ drivers/seco/sio_w83627_gpio.c | 497 ++++++++++++++++++ drivers/seco/sio_w83627_serial.c | 292 +++++++++++ drivers/seco/sio_xr28v382.c | 807 +++++++++++++++++++++++++++++ drivers/seco/sio_xr28v382_reg.h | 146 ++++++ drivers/seco/sio_xr28v382_serial.c | 244 +++++++++ drivers/tty/serial/serial_core.c | 4 + include/linux/seco_cpld.h | 61 +++ include/linux/seco_lpc.h | 32 ++ include/linux/serial_core.h | 1 + include/linux/sio-w83627.h | 20 + include/linux/sio-xr28v382.h | 19 + include/linux/sio_lpc_serial.h | 68 +++ include/uapi/linux/serial.h | 1 + include/uapi/linux/serial_core.h | 2 + 21 files changed, 4383 insertions(+) create mode 100644 drivers/seco/cgpio_expander.c create mode 100644 drivers/seco/cpld.c create mode 100644 drivers/seco/lpc_bridge.c create mode 100644 drivers/seco/pwm_cpld.c create mode 100644 drivers/seco/sio_w83627.c create mode 100644 drivers/seco/sio_w83627_gpio.c create mode 100644 drivers/seco/sio_w83627_serial.c create mode 100644 drivers/seco/sio_xr28v382.c create mode 100644 drivers/seco/sio_xr28v382_reg.h create mode 100644 drivers/seco/sio_xr28v382_serial.c create mode 100644 include/linux/seco_cpld.h create mode 100644 include/linux/seco_lpc.h create mode 100644 include/linux/sio-w83627.h create mode 100644 include/linux/sio-xr28v382.h create mode 100644 include/linux/sio_lpc_serial.h diff --git a/drivers/seco/Kconfig b/drivers/seco/Kconfig index 3894a67aa9e43b..5c5e9af37e28a9 100644 --- a/drivers/seco/Kconfig +++ b/drivers/seco/Kconfig @@ -12,4 +12,13 @@ config ECTRL_MSP430 if usure, say Y. + +config SECO_CPLD_FW + bool "CLPD Firmware management system" + depends on ARCH_MXC + help + Say Y here if you want to use the CLPD Firmware management system. + + if usure, say Y. + endmenu diff --git a/drivers/seco/Makefile b/drivers/seco/Makefile index c442932e80a34d..83a960b0e142e2 100644 --- a/drivers/seco/Makefile +++ b/drivers/seco/Makefile @@ -4,3 +4,5 @@ obj-$(CONFIG_ECTRL_MSP430) += ectrl_msp430.o +obj-$(CONFIG_SECO_CPLD_FW) += cpld.o cgpio_expander.o lpc_bridge.o sio_w83627.o sio_w83627_gpio.o sio_w83627_serial.o sio_xr28v382.o sio_xr28v382_serial.o pwm_cpld.o + diff --git a/drivers/seco/cgpio_expander.c b/drivers/seco/cgpio_expander.c new file mode 100644 index 00000000000000..513d07eb4e04dd --- /dev/null +++ b/drivers/seco/cgpio_expander.c @@ -0,0 +1,614 @@ + + +#include <linux/kernel.h> +#include <linux/device.h> +#include <linux/mutex.h> +#include <linux/module.h> +#include <linux/gpio.h> +#include <linux/slab.h> +#include <asm/byteorder.h> +#include <linux/interrupt.h> +#include <linux/of_irq.h> +#include <linux/of_device.h> +#include <linux/of_platform.h> + +#include <linux/seco_cpld.h> + + +#define CGPIO_INFO(fmt, arg...) printk(KERN_INFO "SecoCGPIO: " fmt "\n" , ## arg) +#define CGPIO_ERR(fmt, arg...) printk(KERN_ERR "%s: " fmt "\n" , __func__ , ## arg) +#define CGPIO_DBG(fmt, arg...) pr_debug("%s: " fmt "\n" , __func__ , ## arg) + + +#define DRV_VERSION "1.0" + + + +#define NR_GPIO 8 +#define CGPIO_LBL "seco_cgpio" +#define CAN_SLEEP 0 + +#define GPIO1 0x01 +#define GPIO2 0x02 +#define GPIO3 0x04 +#define GPIO4 0x08 +#define GPIO5 0x0F +#define GPIO6 0x20 +#define GPIO7 0x40 +#define GPIO8 0x80 +#define GPIO_ALL 0xFF + +#define REG_FW_REV CPLD_REG_0 +#define REG_GPIO_BUFFER CPLD_REG_1 +#define REG_GPIO_DIR CPLD_REG_2 +#define REG_GPIO_INT_MASK CPLD_REG_3 +#define REG_GPIO_INT_EN CPLD_REG_4 +#define REG_GPIO_INT_CONF CPLD_REG_5 +#define REG_GPIO_WR_MASK CPLD_REG_6 +#define REG_GPIO_INT CPLD_REG_7 + +#define INT_IGNORED 0x0 +#define INT_GLOBAL 0x1 + +#define WRITABLE 0x0 +#define NOWRITABLE 0x1 + +#define DIR_OUT 0x0 +#define DIR_IN 0x1 + +#define INT_MASK 1 +#define INT_UNMASK 0 + +#define INT_EN 1 +#define INT_DIS 0 + + +struct cgpio_exp_chip { + struct gpio_chip gpio_chip; + + struct mutex lock; + struct mutex lock_irq; + + uint8_t cache[8]; + + struct irq_domain *irq_domain; + int irq; + +}; + +static struct lock_class_key gpio_lock_class; +static struct lock_class_key gpio_request_class; + +/* __________________________________________________________________________ +* | | +* | W/R BASIC FUNCTION | +* |__________________________________________________________________________| +*/ +static void cgpio_exp_writeb (unsigned int reg, uint8_t value) { + cpld_reg_write (reg, (uint16_t)value); +} + + +static void cgpio_exp_readb (unsigned int reg, uint8_t *data) { + uint16_t value; + cpld_reg_read (reg, &value); + *data = (uint8_t)value; +} + + +static int cgpio_exp_sync_to_cache_reg (struct cgpio_exp_chip *cgpio_chip) { + int i, nreg; + int ret = 0; + nreg = ARRAY_SIZE (cgpio_chip->cache); + + for ( i = 0 ; i < nreg && ret >= 0 ; i++ ) { + cgpio_exp_readb (i, &cgpio_chip->cache[i]); + } + + return (nreg - i); +} + + +static int cgpio_exp_sync_from_cache_reg (struct cgpio_exp_chip *cgpio_chip) { + + /* no all registers are to write */ + cgpio_exp_writeb (REG_GPIO_DIR, cgpio_chip->cache[REG_GPIO_DIR]); + cgpio_exp_writeb (REG_GPIO_INT_MASK, cgpio_chip->cache[REG_GPIO_INT_MASK]); + cgpio_exp_writeb (REG_GPIO_INT_EN, cgpio_chip->cache[REG_GPIO_INT_EN]); + cgpio_exp_writeb (REG_GPIO_INT_CONF, cgpio_chip->cache[REG_GPIO_INT_CONF]); + cgpio_exp_writeb (REG_GPIO_WR_MASK, cgpio_chip->cache[REG_GPIO_WR_MASK]); + + return 0; +} + +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + + +/* __________________________________________________________________________ +* | | +* | GPIO CHIP INTERFACE | +* |__________________________________________________________________________| +*/ +static int cgpio_exp_get_value (struct gpio_chip *chip, unsigned offset) { + uint8_t reg_value; + int status = 0; + struct cgpio_exp_chip *cgpio_chip; + uint8_t mask = 1u << offset; + + cgpio_chip = container_of (chip, struct cgpio_exp_chip, gpio_chip); + + mutex_lock (&cgpio_chip->lock); + cgpio_exp_readb (REG_GPIO_BUFFER, ®_value); + mutex_unlock (&cgpio_chip->lock); + + status = (int)(reg_value & mask); + return status; +} + + +static void __cgpio_exp_set_value (struct cgpio_exp_chip *cgpio_chip, unsigned mask, int value) { + uint8_t reg_out = (value) ? cgpio_chip->cache[REG_GPIO_BUFFER] | (uint8_t)mask : + cgpio_chip->cache[REG_GPIO_BUFFER] & (uint8_t)~mask; + + cgpio_exp_writeb (REG_GPIO_WR_MASK, 0xFF & ~mask); + cgpio_exp_writeb (REG_GPIO_BUFFER, reg_out); + + cgpio_chip->cache[REG_GPIO_BUFFER] = reg_out; +} + + +static void cgpio_exp_set_value (struct gpio_chip *chip, unsigned offset, int value) { + struct cgpio_exp_chip *cgpio_chip; + uint8_t mask = 1u << offset; + + cgpio_chip = container_of (chip, struct cgpio_exp_chip, gpio_chip); + + mutex_lock (&cgpio_chip->lock); + __cgpio_exp_set_value (cgpio_chip, mask, value); + mutex_unlock (&cgpio_chip->lock); +} + + +static int cgpio_exp_direction_input (struct gpio_chip *chip, unsigned offset) { + struct cgpio_exp_chip *cgpio_chip; + + cgpio_chip = container_of (chip, struct cgpio_exp_chip, gpio_chip); + + mutex_lock (&cgpio_chip->lock); + cgpio_chip->cache[REG_GPIO_DIR] |= (1 << offset); + cgpio_exp_writeb (REG_GPIO_DIR, cgpio_chip->cache[REG_GPIO_DIR]); + mutex_unlock (&cgpio_chip->lock); + + return 0; +} + + +static int cgpio_exp_direction_output (struct gpio_chip *chip, unsigned offset, int value) { + struct cgpio_exp_chip *cgpio_chip; + unsigned mask = 1 << offset; + + cgpio_chip = container_of (chip, struct cgpio_exp_chip, gpio_chip); + + mutex_lock (&cgpio_chip->lock); + __cgpio_exp_set_value (cgpio_chip, mask, value); + cgpio_chip->cache[REG_GPIO_DIR] &= ~mask; + cgpio_exp_writeb (REG_GPIO_DIR, cgpio_chip->cache[REG_GPIO_DIR]); + mutex_unlock (&cgpio_chip->lock); + + return 0; +} + + +static void cgpio_exp_dbg_show (struct seq_file *s, struct gpio_chip *chip) { + struct cgpio_exp_chip *cgpio_chip; + int i; + unsigned mask = 1u; + + cgpio_chip = container_of (chip, struct cgpio_exp_chip, gpio_chip); + + mutex_lock (&cgpio_chip->lock); + + /* sync cache with current register sertting */ + i = cgpio_exp_sync_to_cache_reg (cgpio_chip); + if ( i < 0 ) { + seq_printf (s, " I/O ERROR %d\n", i); + goto done; + } + + for ( i = 0 ; i < chip->ngpio ; i++, mask <<= 1) { + const char *label; + + label = gpiochip_is_requested (chip, i); + if (!label) + continue; + + seq_printf(s, " gpio-%-3d (%-12s) %s %s", + chip->base + i, label, + (cgpio_chip->cache[REG_GPIO_DIR] & mask) ? "in " : "out", + (cgpio_chip->cache[REG_GPIO_BUFFER] & mask) ? "hi" : "lo"); + seq_printf(s, "\n"); + } + +done: + mutex_unlock (&cgpio_chip->lock); + +} +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + + + +/* __________________________________________________________________________ +* | | +* | IRQ MANAGEMENT | +* |__________________________________________________________________________| +*/ +static irqreturn_t cgpio_exp_hanlder_irq (int irq, void *data) { + unsigned int child_irq, i; + uint8_t reg_interrupt; + struct cgpio_exp_chip *cgpio_chip = (struct cgpio_exp_chip *)data; + + cgpio_exp_readb (REG_GPIO_INT, ®_interrupt); + cgpio_chip->cache[REG_GPIO_INT] = reg_interrupt; + + for ( i = 0 ; i < cgpio_chip->gpio_chip.ngpio ; i++ ) { + if ( BIT(i) & reg_interrupt ) { + child_irq = irq_find_mapping (cgpio_chip->irq_domain, i); + handle_nested_irq (child_irq); + } + } + + cgpio_exp_writeb (REG_GPIO_INT, 0xFF); + + return IRQ_HANDLED; +} + + +static void cgpio_exp_free_irq (struct cgpio_exp_chip *cgpio_chip) { + unsigned int irq, i; + + free_irq (cgpio_chip->irq, cgpio_chip); + + for ( i = 0; i < cgpio_chip->gpio_chip.ngpio ; i++ ) { + irq = irq_find_mapping (cgpio_chip->irq_domain, i); + if ( irq > 0 ) + irq_dispose_mapping (irq); + } + + irq_domain_remove (cgpio_chip->irq_domain); +} + + +static int cgpio_exp_gpio_to_irq (struct gpio_chip *chip, unsigned offset) { + struct cgpio_exp_chip *cgpio_chip; + cgpio_chip = container_of (chip, struct cgpio_exp_chip, gpio_chip); + + return irq_find_mapping(cgpio_chip->irq_domain, offset); +} + + +static void cgpio_exp_irq_mask (struct irq_data *data) { + struct cgpio_exp_chip *cgpio_chip; + unsigned int pos; + + cgpio_chip = irq_data_get_irq_chip_data(data); + pos = data->hwirq; + + cgpio_chip->cache[REG_GPIO_INT_EN] &= ~BIT(pos); + cgpio_chip->cache[REG_GPIO_INT_MASK] |= BIT(pos); +} + + +static void cgpio_exp_irq_unmask (struct irq_data *data) { + struct cgpio_exp_chip *cgpio_chip; + unsigned int pos; + + cgpio_chip = irq_data_get_irq_chip_data(data); + pos = data->hwirq; + + cgpio_chip->cache[REG_GPIO_INT_EN] |= BIT(pos); + cgpio_chip->cache[REG_GPIO_INT_MASK] &= ~BIT(pos); +} + + +static int cgpio_exp_irq_set_type (struct irq_data *data, unsigned int type) { + struct cgpio_exp_chip *cgpio_chip; + unsigned int pos = data->hwirq; + int status = 0; + + cgpio_chip = irq_data_get_irq_chip_data(data); + + if ( type & IRQ_TYPE_EDGE_FALLING ) { + cgpio_chip->cache[REG_GPIO_INT_CONF] &= ~BIT(pos); + } else if ( type & IRQ_TYPE_LEVEL_HIGH ) { + cgpio_chip->cache[REG_GPIO_INT_CONF] |= BIT(pos); + } else + status = -EINVAL; + + return status; +} + + +static void cgpio_exp_irq_bus_lock (struct irq_data *data) { + struct cgpio_exp_chip *cgpio_chip; + + cgpio_chip = irq_data_get_irq_chip_data(data); + mutex_lock (&cgpio_chip->lock_irq); +} + + +static void cgpio_exp_irq_bus_unlock (struct irq_data *data) { + struct cgpio_exp_chip *cgpio_chip; + + cgpio_chip = irq_data_get_irq_chip_data(data); + + mutex_lock (&cgpio_chip->lock); + cgpio_exp_writeb (REG_GPIO_INT_MASK, cgpio_chip->cache[REG_GPIO_INT_MASK]); + cgpio_exp_writeb (REG_GPIO_INT_EN, cgpio_chip->cache[REG_GPIO_INT_EN]); + cgpio_exp_writeb (REG_GPIO_INT_CONF, cgpio_chip->cache[REG_GPIO_INT_CONF]); + mutex_unlock (&cgpio_chip->lock); + + mutex_unlock (&cgpio_chip->lock_irq); + +} + + +static unsigned int cgpio_exp_irq_startup (struct irq_data *data) { + struct cgpio_exp_chip *cgpio_chip; + + cgpio_chip = irq_data_get_irq_chip_data(data); + + if ( gpiochip_lock_as_irq (&cgpio_chip->gpio_chip, data->hwirq) ) { + CGPIO_ERR ("unable to lock HW IRQ %lu for IRQ usage", data->hwirq); + } + + cgpio_exp_irq_unmask (data); + return 0; +} + + +static void cgpio_exp_irq_shutdown (struct irq_data *data) { + struct cgpio_exp_chip *cgpio_chip; + + cgpio_chip = irq_data_get_irq_chip_data(data); + cgpio_exp_irq_mask (data); + gpiochip_unlock_as_irq (&cgpio_chip->gpio_chip, data->hwirq); +} + + +static struct irq_chip cgpio_exp_irq_chip = { + .name = "cgpio-exp-seco", + .irq_mask = cgpio_exp_irq_mask, + .irq_unmask = cgpio_exp_irq_unmask, + .irq_set_type = cgpio_exp_irq_set_type, + .irq_bus_lock = cgpio_exp_irq_bus_lock, + .irq_bus_sync_unlock = cgpio_exp_irq_bus_unlock, + .irq_startup = cgpio_exp_irq_startup, + .irq_shutdown = cgpio_exp_irq_shutdown, +}; +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + + + +/* __________________________________________________________________________ +* | | +* | DRIVER SETUP | +* |__________________________________________________________________________| +*/ +static int cgpio_exp_irq_setup (struct cgpio_exp_chip *cgpio_chip) { + int err, irq, i, done; + struct gpio_chip *chip = &cgpio_chip->gpio_chip; + + cgpio_chip->irq_domain = irq_domain_add_linear(chip->of_node, chip->ngpio, + &irq_domain_simple_ops, cgpio_chip); + if ( !cgpio_chip->irq_domain ) { + CGPIO_ERR ("cannot assign irq domain"); + err = -ENODEV; + goto err_irq_domain_add; + } + + err = devm_request_threaded_irq (chip->parent, cgpio_chip->irq, NULL, cgpio_exp_hanlder_irq, + IRQF_TRIGGER_HIGH | IRQF_ONESHOT, + dev_name(chip->parent), cgpio_chip); + if (err != 0) { + CGPIO_ERR ("unable to request IRQ#%d: %d", cgpio_chip->irq, err); + goto err_request_thr_irq; + } + + chip->to_irq = cgpio_exp_gpio_to_irq; + + for ( i = 0 ; i < chip->ngpio ; i++ ) { + irq = irq_create_mapping (cgpio_chip->irq_domain, i); + if ( irq < 0 ) { + CGPIO_ERR ("cannot map irq"); + done = i; + err = -EINVAL; + goto err_map_irq; + } + irq_set_lockdep_class (irq, &gpio_lock_class, &gpio_request_class); + irq_set_chip_data (irq, cgpio_chip); + irq_set_chip (irq, &cgpio_exp_irq_chip); + irq_set_nested_thread (irq, true); + } + + return 0; +err_map_irq: + while ( --done ) { + irq = irq_find_mapping (cgpio_chip->irq_domain, i); + if ( irq > 0 ) + irq_dispose_mapping (irq); + } +err_request_thr_irq: + irq_domain_remove (cgpio_chip->irq_domain); +err_irq_domain_add: + return err; +} + + +static int cgpio_exp_setup (struct cgpio_exp_chip *cgpio_chip, struct device *dev, + unsigned base) { + int ret, err, status; + + /* init gpio chip structure */ + cgpio_chip->gpio_chip.get = cgpio_exp_get_value; + cgpio_chip->gpio_chip.set = cgpio_exp_set_value; + cgpio_chip->gpio_chip.direction_input = cgpio_exp_direction_input; + cgpio_chip->gpio_chip.direction_output = cgpio_exp_direction_output; + cgpio_chip->gpio_chip.dbg_show = cgpio_exp_dbg_show; + + cgpio_chip->gpio_chip.of_gpio_n_cells = 2; + cgpio_chip->gpio_chip.of_node = dev->of_node; + + cgpio_chip->gpio_chip.ngpio = NR_GPIO; + cgpio_chip->gpio_chip.label = CGPIO_LBL; + + cgpio_chip->gpio_chip.base = base; + cgpio_chip->gpio_chip.can_sleep = CAN_SLEEP; + cgpio_chip->gpio_chip.parent = dev; + cgpio_chip->gpio_chip.owner = THIS_MODULE; + + mutex_init (&cgpio_chip->lock); + mutex_init (&cgpio_chip->lock_irq); + + /* init registers configuration */ + cgpio_chip->cache[REG_GPIO_DIR] = 0xFF; // all gpios as input + cgpio_chip->cache[REG_GPIO_INT_MASK] = 0x00; // all interrupt masked + cgpio_chip->cache[REG_GPIO_INT_EN] = 0x00; // all interrupt disabled + cgpio_chip->cache[REG_GPIO_INT_CONF] = 0x00; // all interrupt over falling edge + cgpio_chip->cache[REG_GPIO_WR_MASK] = 0x00; // all output gpios as writable + cgpio_exp_sync_from_cache_reg (cgpio_chip); + + /* init cache with current register sertting */ + ret = cgpio_exp_sync_to_cache_reg (cgpio_chip); + if ( ret != 0 ) { + CGPIO_ERR ("cannot read external register... no sync"); + err = -ret; + goto err_sync_cache; + } + + /* add this gpio bank */ + status = gpiochip_add (&cgpio_chip->gpio_chip); + if ( status < 0 ) { + CGPIO_ERR ("cannot add gpio bank to the system"); + err = status; + goto err_gpio_add; + } + + status = cgpio_exp_irq_setup (cgpio_chip); + if ( status ) { + CGPIO_ERR ("cannot setup gpio irq"); + err = status; + goto err_irq_setup; + } + + return 0; +err_irq_setup: +err_gpio_add: +err_sync_cache: + return err; +} +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + + + +static int cgpio_exp_probe (struct platform_device *pdev) { + struct device_node *dp = pdev->dev.of_node; + struct cgpio_exp_chip *cgpio_chip; + int ret, err; + unsigned base = -1; + + /* check that the CPLD firmware is a GPIO expander */ + if ( !cpld_is_gpio () ) { + CGPIO_ERR ("the CPLD firmware is no a GPIO expander"); + err = EINVAL; + goto err_cpld; + } + + cgpio_chip = kzalloc (sizeof (struct cgpio_exp_chip), GFP_KERNEL); + if ( !cgpio_chip ) { + CGPIO_ERR ("cannot allocate memory for structure data"); + err = -ENOMEM; + goto err_data_allocate; + } + + platform_set_drvdata (pdev, cgpio_chip); + + cgpio_chip->irq = irq_of_parse_and_map (dp, 0); + + ret = cgpio_exp_setup (cgpio_chip, &pdev->dev, base); + if ( ret != 0 ) { + CGPIO_ERR ("cannot driver setup"); + err = ret; + goto err_setup; + } + + CGPIO_INFO ("cgpio_expander driver ver %s probed!!!", DRV_VERSION); + return 0; +err_setup: + kfree (cgpio_chip); +err_data_allocate: +err_cpld: + return err; +} + + +static int cgpio_exp_remove (struct platform_device *pdev) { + + struct cgpio_exp_chip *cgpio_chip = (struct cgpio_exp_chip *)platform_get_drvdata (pdev); + + cgpio_exp_free_irq (cgpio_chip); + + gpiochip_remove (&cgpio_chip->gpio_chip); + + kfree (cgpio_chip); + + return 0; +} + + +static const struct of_device_id seco_cgpio_exp_match[] = { + { .compatible = "seco,cgpio_expander" }, + { /* sentinel */ } +}; + +MODULE_DEVICE_TABLE(of, seco_cgpio_exp_match); + + +static struct platform_driver cgpio_exp_driver = { + .driver = { + .name = "cpgio_expander", + .owner = THIS_MODULE, + .of_match_table = seco_cgpio_exp_match, + }, + .probe = cgpio_exp_probe, + .remove = cgpio_exp_remove, +}; + + + +static int __init cgpio_exp_init(void) { + return platform_driver_register (&cgpio_exp_driver); +} + +subsys_initcall(cgpio_exp_init); + + +static void __exit cgpio_exp_exit (void) { + return platform_driver_unregister (&cgpio_exp_driver); +} + +module_exit(cgpio_exp_exit); + + + +MODULE_AUTHOR("Davide Cardillo, SECO srl"); +MODULE_DESCRIPTION("SECO GPIO Expander over CPLD logic"); +MODULE_LICENSE("GPL"); +MODULE_VERSION(DRV_VERSION); diff --git a/drivers/seco/cpld.c b/drivers/seco/cpld.c new file mode 100644 index 00000000000000..b0c0cc19a49500 --- /dev/null +++ b/drivers/seco/cpld.c @@ -0,0 +1,305 @@ + +#include <linux/kernel.h> +#include <linux/io.h> +#include <linux/device.h> +#include <linux/mutex.h> +#include <linux/module.h> +#include <linux/slab.h> +#include <asm/byteorder.h> +#include <linux/interrupt.h> +#include <linux/of_irq.h> +#include <linux/sysctl.h> +#include <linux/of_device.h> +#include <linux/of_address.h> +#include <linux/of_platform.h> + + +#include <linux/seco_cpld.h> + + +#define DRV_VERSION "1.0" + + +#define REG_ADDR(x) (CPLD_OFFSET_BASE + (x*2)) +#define WEIM_ADDR(x) (cpld_d->virt + (x)) + +#define CPLD_INFO(fmt, arg...) printk(KERN_INFO "CPLD: " fmt "\n" , ## arg) +#define CPLD_ERR(fmt, arg...) printk(KERN_ERR "%s: " fmt "\n" , __func__ , ## arg) +#define CPLD_DBG(fmt, arg...) pr_debug("%s: " fmt "\n" , __func__ , ## arg) + +static struct cpld_data *cpld_d = NULL; + + +void cpld_reg_read (unsigned int addr, uint16_t *data) { + *data = __raw_readw (WEIM_ADDR(REG_ADDR(addr))); +} + + +void cpld_reg_write (unsigned int addr, uint16_t value) { + writew (value, WEIM_ADDR(REG_ADDR(addr))); +} + + +void cpld_read (unsigned int addr, uint16_t *data) { + *data = readw (WEIM_ADDR(addr << 1)); +} + + +void cpld_write (unsigned int addr, uint16_t value) { + writew (value, WEIM_ADDR(addr << 1)); +} + + +int inline cpld_get_membase (void) { + return cpld_d->mem_addr_base; +} + + +int cpld_get_revision (void) { + uint16_t rev; + cpld_reg_read (REG_REVISION, &rev); + return rev; +} + + +int cpld_is_gpio (void) { + int is_gpio = 0; + uint16_t rev = cpld_get_revision (); + switch (rev) { + case 0x3a06: + case 0x3a04: + case 0x3a02: + is_gpio = 1; + break; + default: + is_gpio = 0; + break; + } + return is_gpio; +} + + +int cpld_is_lpc (void) { + return !cpld_is_gpio (); +} + + +void dump_reg (void) { + int i; + uint16_t val; + + for ( i = 0 ; i < NREG ; i++ ) { + cpld_reg_read (i, &val); + CPLD_INFO ("dump register %d -> 0x%04X", i, val); + } +} + + +#define CPLD_NAME "CPLD_device" + +int __cpld_init (struct device_node *dp, struct resource *resource) { + uint16_t rev = 0; + int err = 0; + + if ( cpld_d != NULL ) { + CPLD_ERR ("CPLD resource already initialized"); + err = EINVAL; + goto err_out; + } + + cpld_d = kzalloc(sizeof(struct cpld_data), GFP_KERNEL); + if (cpld_d == NULL) { + err = ENOMEM; + goto err_out; + } + + if ( of_address_to_resource(dp, 0, resource) ) { + err = EINVAL; + goto err_out; + } + + CPLD_INFO ("platform CPLD device: %.8llx at %.8llx", + (unsigned long long)resource_size(&resource[0]), + (unsigned long long)resource[0].start); + + if (!request_mem_region(resource[0].start, + resource_size(&resource[0]), + CPLD_NAME)) { + CPLD_ERR ("Could not reserve memory region"); + err = -ENOMEM; + goto err_out; + } + pr_debug ("%s: memory request done!\n", __func__); + + cpld_d->name = CPLD_NAME; + cpld_d->mem_addr_base = resource[0].start; + cpld_d->mem_size = resource_size(&resource[0]); + cpld_d->virt = ioremap_cache (cpld_d->mem_addr_base, cpld_d->mem_size); + if (cpld_d->virt == NULL) { + CPLD_ERR ("Failed to ioremap seco CPLD region"); + err = -EIO; + goto err_out; + } + + mutex_init (&cpld_d->bus_lock); + + cpld_reg_read (REG_REVISION, &rev); + CPLD_INFO ("ver.: %04x", rev); + return 0; +err_out: + return err; +} + + + +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ +static ssize_t sys_cpld_dump_regs_show (struct device *dev, struct device_attribute *attr, + char *buf) +{ + unsigned char msg[500]; + unsigned char tmp[50]; + int i; + uint16_t value; + + sprintf (msg, "\n#\tvalue"); + for ( i = 0 ; i < NREG ; i++ ) { + cpld_reg_read (i, &value); + sprintf (tmp, "\n%02d\t0x%04X", i, value); + strcat (msg, tmp); + } + + return sprintf (buf, "%s\n", msg); +} + + +static ssize_t sys_cpld_version_show (struct device *dev, struct device_attribute *attr, + char *buf) +{ + uint16_t ver; + cpld_reg_read (REG_REVISION, &ver); + return sprintf(buf, "0x%04X\n",ver); +} + +static DEVICE_ATTR(dump_regs, S_IRUGO, sys_cpld_dump_regs_show, NULL); +static DEVICE_ATTR(cpld_ver, S_IRUGO, sys_cpld_version_show, NULL); + + +static struct attribute *cpld_attrs[] = { + &dev_attr_dump_regs.attr, + &dev_attr_cpld_ver.attr, + NULL, +}; + + +static struct attribute_group cpld_attr_group = { + .attrs = cpld_attrs, +}; + + + +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ +#define TYPE_GPIO 0 +#define TYPE_LPC 1 + + +static int clpd_client_register (struct device_node *dp, struct device *parent_dev) { + int ret; +#if 0 // use direct dts status selection + u32 type = 0; + u32 ctype = (u32)cpld_is_gpio (); + struct device_node *child; + const char *en_code = "okay"; +#endif + +#if 0 // use direct dts status selection + for_each_child_of_node (dp, child) { + ret = of_property_read_u32 (child, "type", (u32 *)&type); + if ( ret == 0 ) { + if ( (ctype && (type == TYPE_GPIO)) || + (!ctype && (type == TYPE_LPC)) ) { + + of_property_write_string (child, "status", en_code); + + } + } else { + CPLD_ERR ("failed to create device"); + } + } +#endif + + ret = of_platform_populate (dp, NULL, NULL, parent_dev); + if ( ret ) { + CPLD_ERR ("failed to create device"); + } else { + CPLD_INFO ("device created"); + } + + return !ret; +} + + +static int cpld_probe (struct platform_device *pdev) { + struct device_node *dp = pdev->dev.of_node; + struct resource res; + int error = 0; + int registred; + + __cpld_init (dp, &res); + + registred = clpd_client_register (dp, &pdev->dev); + if ( registred ) + error = sysfs_create_group(&pdev->dev.kobj, &cpld_attr_group); + return error; +} + + +static int cpld_remove (struct platform_device *pdev) { + return 0; +} + + +static const struct of_device_id seco_cpld_match[] = { + { .compatible = "seco,cpld" }, + { /* sentinel */ } +}; + +MODULE_DEVICE_TABLE(of, seco_cpld_match); + + +static struct platform_driver cpld_driver = { + .driver = { + .name = "cpld", + .owner = THIS_MODULE, + .of_match_table = seco_cpld_match, + }, + .probe = cpld_probe, + .remove = cpld_remove, +}; + + + +static int __init cpld_init(void) { + return platform_driver_register (&cpld_driver); +} + +subsys_initcall(cpld_init); + + +static void __exit cpld_exit (void) { + return platform_driver_unregister (&cpld_driver); +} + +module_exit(cpld_exit); + + + + +MODULE_AUTHOR("Davide Cardillo, SECO srl"); +MODULE_DESCRIPTION("SECO CPLD interface"); +MODULE_ALIAS("platform:cpld"); +MODULE_LICENSE("GPL"); +MODULE_VERSION(DRV_VERSION); diff --git a/drivers/seco/lpc_bridge.c b/drivers/seco/lpc_bridge.c new file mode 100644 index 00000000000000..19709d613a17a7 --- /dev/null +++ b/drivers/seco/lpc_bridge.c @@ -0,0 +1,509 @@ + + +#include <linux/kernel.h> +#include <linux/device.h> +#include <linux/mutex.h> +#include <linux/module.h> +#include <linux/gpio.h> +#include <linux/slab.h> +#include <asm/byteorder.h> +#include <linux/interrupt.h> +#include <linux/of_irq.h> +#include <linux/of_device.h> +#include <linux/of_platform.h> + +#include <linux/seco_lpc.h> +#include <linux/seco_cpld.h> + +#define LPC_INFO(fmt, arg...) printk(KERN_INFO "LPC Bridge: " fmt "\n" , ## arg) +#define LPC_ERR(fmt, arg...) printk(KERN_ERR "%s: " fmt "\n" , __func__ , ## arg) +#define LPC_DBG(fmt, arg...) pr_debug("%s: " fmt "\n" , __func__ , ## arg) + + +#define LPC_REG_IRQ_BUFFER CPLD_REG_1 +#define LPC_REG_MEM_PAGE_SEL CPLD_REG_2 +#define LPC_REG_IRQ_MASK CPLD_REG_3 +#define LPC_REG_LPC_BUSY CPLD_REG_4 +#define LPC_REG_IRQ_CONF CPLD_REG_5 + +#define NR_IRQ 3 + +#define LPC_BUSY 0x1 + +#define NR_RETRIES 10 +#define LPC_TIME_OUT 100 + +#define IRQ_MASKERED 0x00 +#define IRQ_UNMASKERED 0x01 + +#define LPC_IRQ_MASKABLE 0x1 +#define LPC_IRQ_UNMASKABLE 0x0 + +#define NR_LPC_SLOTS 16 + +#define DRV_VERSION "1.0" + + +struct lpc_table_element *lpc_table; + + +struct lpc_data { + const char *name; + struct device *dev; + + uint16_t cache[6]; + + struct mutex bus_lock; + struct mutex lock_irq; + + resource_size_t mem_addr_base; + unsigned long mem_base; + + struct irq_domain *irq_domain; + int irq; + +}; + + + +struct lpc_data *lpc_d; + +static struct lock_class_key lpc_lock_class; +static struct lock_class_key lpc_request_class; + +/* __________________________________________________________________________ +* | | +* | BASIC I/O FUNCTIONS | +* |__________________________________________________________________________| +*/ +static void lpc_reg_read (unsigned int reg, uint16_t *data) { + cpld_reg_read (reg, data); +} + + +static void lpc_reg_write (unsigned int reg, uint16_t value) { + cpld_reg_write (reg, value); +} + + +static int inline lpc_read_status (void) { + uint16_t state; + cpld_reg_read (LPC_REG_LPC_BUSY, &state); + return ((state & 0x8000) >> 15); +} + +int lpc_readw (unsigned long mem_addr, uint16_t *data) { + unsigned long orig_jiffies; + int try; + int res = 0; + int status = -EIO; + + orig_jiffies = jiffies; + for (try = 0 ; try <= NR_RETRIES ; try++) { + res = lpc_read_status(); + if (res != LPC_BUSY) { + cpld_read (mem_addr, data); + status = res; + break; + } + if (time_after (jiffies, orig_jiffies + LPC_TIME_OUT)) { + LPC_ERR ("read operation TIMEOUT!"); + break; + } + } + + return status; +} + + +int lpc_writew (unsigned long mem_addr, uint16_t value) { + unsigned long orig_jiffies; + int try; + int res = 0; + int status = -EIO; + + orig_jiffies = jiffies; + for (try = 0 ; try <= NR_RETRIES ; try++) { + res = lpc_read_status(); + if (res != LPC_BUSY) { + cpld_write (mem_addr, value); + status = res; + break; + } + if (time_after (jiffies, orig_jiffies + LPC_TIME_OUT)) { + LPC_ERR ("read operation TIMEOUT!"); + break; + } + } + + return status; +} +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + + +/* __________________________________________________________________________ +* | | +* | IRQ MANAGEMENT | +* |__________________________________________________________________________| +*/ +#include <asm/delay.h> +static irqreturn_t lpc_bridge_hanlder_irq (int irq, void *data) { + unsigned int child_irq, i; + uint16_t reg_interrupt, mask, conf; + int count; + struct lpc_data *lpc_d = (struct lpc_data *)data; + + lpc_reg_read (LPC_REG_IRQ_BUFFER, ®_interrupt); + lpc_reg_read (LPC_REG_IRQ_MASK, &mask); + lpc_reg_read (LPC_REG_IRQ_CONF, &conf); + lpc_d->cache[LPC_REG_IRQ_BUFFER] = reg_interrupt; + for ( i = 0 ; i < NR_LPC_SLOTS ; i++ ) { + if ( BIT(i) & reg_interrupt ) { + child_irq = irq_find_mapping (lpc_d->irq_domain, i); + handle_nested_irq (child_irq); + count++; + } + } + + return IRQ_HANDLED; +} + + +static void lpc_bridge_irq_disable (struct irq_data *data) { + struct lpc_data *lpc_d; + unsigned int pos; + + lpc_d = irq_data_get_irq_chip_data (data); + pos = data->hwirq; + + lpc_d->cache[LPC_REG_IRQ_MASK] &= ~BIT(pos); +} + + +static void lpc_bridge_irq_mask (struct irq_data *data) { + struct lpc_data *lpc_d; + unsigned int pos; + + lpc_d = irq_data_get_irq_chip_data (data); + pos = data->hwirq; + + lpc_d->cache[LPC_REG_IRQ_MASK] &= ~BIT(pos); +} + + +static void lpc_bridge_irq_enable (struct irq_data *data) { + struct lpc_data *lpc_d; + unsigned int pos; + + lpc_d = irq_data_get_irq_chip_data (data); + pos = data->hwirq; + + lpc_d->cache[LPC_REG_IRQ_MASK] |= BIT(pos); +} + + +static void lpc_bridge_irq_unmask (struct irq_data *data) { + struct lpc_data *lpc_d; + unsigned int pos; + + lpc_d = irq_data_get_irq_chip_data (data); + pos = data->hwirq; + + lpc_d->cache[LPC_REG_IRQ_MASK] |= BIT(pos); +} + + +static int lpc_bridge_irq_set_type (struct irq_data *data, unsigned int type) { + struct lpc_data *lpc_d; + unsigned int pos = data->hwirq; + int status = 0; + + lpc_d = irq_data_get_irq_chip_data (data); + + if ( type & IRQ_TYPE_EDGE_FALLING ) { + lpc_d->cache[LPC_REG_IRQ_CONF] &= ~BIT(pos); + } else if ( type & IRQ_TYPE_LEVEL_HIGH ) { + lpc_d->cache[LPC_REG_IRQ_CONF] |= BIT(pos); + } else + status = -EINVAL; + + return status; + +} + + +static void lpc_bridge_irq_bus_lock (struct irq_data *data) { + struct lpc_data *lpc_d; + + lpc_d = irq_data_get_irq_chip_data (data); + mutex_lock (&lpc_d->lock_irq); + +} + + +static void lpc_bridge_irq_bus_unlock (struct irq_data *data) { + struct lpc_data *lpc_d; + + lpc_d = irq_data_get_irq_chip_data (data); + + mutex_lock (&lpc_d->bus_lock); + lpc_reg_write (LPC_REG_IRQ_MASK, lpc_d->cache[LPC_REG_IRQ_MASK]); + lpc_reg_write (LPC_REG_IRQ_CONF, lpc_d->cache[LPC_REG_IRQ_CONF]); + mutex_unlock (&lpc_d->bus_lock); + + mutex_unlock (&lpc_d->lock_irq); + +} + + +static unsigned int lpc_bridge_irq_startup (struct irq_data *data) { + struct lpc_data *lpc_d; + + lpc_d = irq_data_get_irq_chip_data (data); + lpc_bridge_irq_unmask (data); + + return 0; +} + + +static void lpc_bridge_irq_shutdown (struct irq_data *data) { + struct lpc_data *lpc_d; + + lpc_d = irq_data_get_irq_chip_data (data); + lpc_bridge_irq_mask (data); + +} + + +static struct irq_chip lpc_bridge_irq_chip = { + .name = "lpc_bridge-seco", + .irq_mask = lpc_bridge_irq_mask, + .irq_unmask = lpc_bridge_irq_unmask, + .irq_enable = lpc_bridge_irq_enable, + .irq_disable = lpc_bridge_irq_disable, + .irq_set_type = lpc_bridge_irq_set_type, + .irq_bus_lock = lpc_bridge_irq_bus_lock, + .irq_bus_sync_unlock = lpc_bridge_irq_bus_unlock, + .irq_startup = lpc_bridge_irq_startup, + .irq_shutdown = lpc_bridge_irq_shutdown, +}; +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + + + +/* __________________________________________________________________________ +* | | +* | SUB-DEVICE ALLOCATION | +* |__________________________________________________________________________| +*/ +static int lpc_driver_allocate (struct device *parent_dev, struct device_node *dp) { + int status; + + status = of_platform_populate (dp, NULL, NULL, parent_dev); + if ( status ) { + LPC_ERR ("failed to create device"); + } else { + LPC_INFO ("lpc device created"); + } + + return status; +} +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + + +/* __________________________________________________________________________ +* | | +* | BUS SETUP | +* |__________________________________________________________________________| +*/ +static int lpc_bridge_irq_setup (struct lpc_data *lpc_d) { + int err, irq, i, done; + + lpc_d->irq_domain = irq_domain_add_linear(lpc_d->dev->of_node, NR_LPC_SLOTS, + &irq_domain_simple_ops, lpc_d); + if ( !lpc_d->irq_domain ) { + LPC_ERR ("cannot assign irq domain"); + err = -ENODEV; + goto err_irq_domain_add; + } + + err = devm_request_threaded_irq (lpc_d->dev, lpc_d->irq, NULL, lpc_bridge_hanlder_irq, + IRQF_TRIGGER_HIGH | IRQF_ONESHOT, + dev_name(lpc_d->dev), lpc_d); + if (err != 0) { + LPC_ERR ("unable to request IRQ#%d: %d", lpc_d->irq, err); + goto err_request_thr_irq; + } + + for ( i = 0 ; i < NR_LPC_SLOTS ; i++ ) { + irq = irq_create_mapping (lpc_d->irq_domain, i); + if ( irq < 0 ) { + LPC_ERR ("cannot map irq"); + done = i; + err = -EINVAL; + goto err_map_irq; + } + irq_set_lockdep_class (irq, &lpc_lock_class, &lpc_request_class); + irq_set_chip_data (irq, lpc_d); + irq_set_chip (irq, &lpc_bridge_irq_chip); + irq_set_nested_thread (irq, true); + } + + return 0; +err_map_irq: + while ( --done ) { + irq = irq_find_mapping (lpc_d->irq_domain, i); + if ( irq > 0 ) + irq_dispose_mapping (irq); + } +err_request_thr_irq: + irq_domain_remove (lpc_d->irq_domain); +err_irq_domain_add: + return err; + +} + + +static int lpc_setup (struct device *dev, struct device_node *dp, + struct lpc_data *lpc_d) +{ + int err, status; + + if (lpc_d == NULL) { + err = -ENOMEM; + goto err_lpc_alloc; + } + + lpc_d->mem_base = cpld_get_membase (); + + lpc_d->name = dev_name (dev); + + lpc_d->dev = dev; + + mutex_init (&lpc_d->bus_lock); + mutex_init (&lpc_d->lock_irq); + + // set register init + + status = lpc_bridge_irq_setup (lpc_d); + if ( status ) { + LPC_ERR ("cannot setup lpc irq"); + err = status; + goto err_irq_setup; + } + + return 0; +err_irq_setup: +err_lpc_alloc: + return err; +} + + +static int lpc_bridge_probe (struct platform_device *pdev) { + struct device_node *dp = pdev->dev.of_node; + int err = 0; + int done, irq, ret; + int i = 0; + + /* check that the CPLD firmware is a GPIO expander */ + if ( !cpld_is_lpc () ) { + LPC_ERR ("the CPLD firmware is no a LPC Bridge"); + err = EINVAL; + goto err_cpld; + } + + lpc_d = kzalloc (sizeof(struct lpc_data), GFP_KERNEL); + if ( !lpc_d ) { + LPC_ERR ("cannot allocate memory for structure data"); + err = -ENOMEM; + goto err_data_allocate; + } + + platform_set_drvdata (pdev, lpc_d); + + lpc_d->irq = irq_of_parse_and_map (dp, 0); + + ret = lpc_setup (&pdev->dev, dp, lpc_d); + if ( ret != 0 ) { + err = ret; + LPC_ERR ("LPC initialization failed. Probe stopped!"); + goto err_lpc_setup; + } + + ret = lpc_driver_allocate (&pdev->dev, dp); + if ( ret != 0 ) { + err = -EINVAL; + LPC_ERR ("cannot allocate sub device!"); + goto err_driver_allocate; + } + + LPC_INFO ("lpc_bridge driver ver %s probed!!!", DRV_VERSION); + return 0; +err_driver_allocate: + free_irq (lpc_d->irq, lpc_d); + done = NR_LPC_SLOTS; + while ( --done ) { + irq = irq_find_mapping (lpc_d->irq_domain, i); + if ( irq > 0 ) + irq_dispose_mapping (irq); + } + irq_domain_remove (lpc_d->irq_domain); +err_lpc_setup: + kfree (lpc_d); +err_data_allocate: + dp = NULL; +err_cpld: + return err; +} + + +static int lpc_bridge_remove (struct platform_device *pdev) { + return 0; +} + + +static const struct of_device_id seco_lpc_bridge_match[] = { + { .compatible = "seco,lpc_bridge" }, + { /* sentinel */ } +}; + +MODULE_DEVICE_TABLE(of, seco_lpc_bridge_match); + + +static struct platform_driver lpc_bridge_driver = { + .driver = { + .name = "lpc_bridge", + .owner = THIS_MODULE, + .of_match_table = seco_lpc_bridge_match, + }, + .probe = lpc_bridge_probe, + .remove = lpc_bridge_remove, +}; + + + +static int __init lpc_bridge_init(void) { + return platform_driver_register (&lpc_bridge_driver); +} + +subsys_initcall(lpc_bridge_init); + + +static void __exit lpc_bridge_exit (void) { + return platform_driver_unregister (&lpc_bridge_driver); +} + +module_exit(lpc_bridge_exit); + + + +MODULE_AUTHOR("Davide Cardillo, SECO srl"); +MODULE_DESCRIPTION("SECO LPC Bridge over CPLD logic"); +MODULE_LICENSE("GPL"); +MODULE_VERSION(DRV_VERSION); diff --git a/drivers/seco/pwm_cpld.c b/drivers/seco/pwm_cpld.c new file mode 100644 index 00000000000000..8d36dd5bb9a34c --- /dev/null +++ b/drivers/seco/pwm_cpld.c @@ -0,0 +1,289 @@ + +#include <linux/kernel.h> +#include <linux/device.h> +#include <linux/mutex.h> +#include <linux/module.h> +#include <linux/gpio.h> +#include <linux/slab.h> +#include <asm/byteorder.h> +#include <linux/interrupt.h> +#include <linux/of_irq.h> +#include <linux/of_device.h> +#include <linux/of_platform.h> +#include <linux/pwm.h> + +#include <linux/seco_cpld.h> + + +#define CPWM_INFO(fmt, arg...) printk(KERN_INFO "SecoCPWM: " fmt "\n" , ## arg) +#define CPWM_ERR(fmt, arg...) printk(KERN_ERR "%s: " fmt "\n" , __func__ , ## arg) +#define CPWM_DBG(fmt, arg...) pr_debug("%s: " fmt "\n" , __func__ , ## arg) + +#define DRV_VERSION "1.0" + +#define PWM_LPC_REG1 CPLD_REG_6 +#define PWM_LPC_REG2 CPLD_REG_7 +#define PWM_LPC_REG3 CPLD_REG_8 + +#define PWM_GPIO_REG1 CPLD_REG_8 +#define PWM_GPIO_REG2 CPLD_REG_9 +#define PWM_GPIO_REG3 CPLD_REG_10 + + +#define PWM_MASK_EN 0x8000 +#define PWM_MASK_POL 0x4000 +#define PWM_MASK_PRESCALE 0x3FFF +#define PWM_MASK_PERIOD 0xFFFF +#define PWM_MASK_DUTY 0xFFFF + +#define MAIN_CLK 33000000 // (Hz) + +struct cpwm_data { + bool polarity_supported; + const struct pwm_ops *ops; +}; + +struct register_map { + u8 PWM_REG_ENABLE; + u8 PWM_REG_POLARITY; + u8 PWM_REG_PRESCALE; + u8 PWM_REG_PERIOD; + u8 PWM_REG_DUTY; +}; + +struct cpwm_chip { + struct pwm_chip chip; + struct register_map reg_map; +}; + + +#define to_cpwm_chip(chip) container_of(chip, struct cpwm_chip, chip) + + +/* __________________________________________________________________________ +* | | +* | W/R BASIC FUNCTION | +* |__________________________________________________________________________| +*/ +static void cpwm_writeb (unsigned int reg, uint16_t value) { + cpld_reg_write (reg, value); +} + + +static void cpwm_readb (unsigned int reg, uint16_t *data) { + uint16_t value; + cpld_reg_read (reg, &value); + *data = value; +} + +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + +/* __________________________________________________________________________ +* | | +* | PWM BASIC FUNCTION | +* |__________________________________________________________________________| +*/ +static void cpwm_enable ( struct pwm_chip *chip ) { + struct cpwm_chip *cpwm = to_cpwm_chip( chip ); + uint16_t reg_value; + + cpwm_readb( cpwm->reg_map.PWM_REG_ENABLE, ®_value ); + cpwm_writeb( cpwm->reg_map.PWM_REG_ENABLE, reg_value | PWM_MASK_EN) ; +} + + +static void cpwm_disable ( struct pwm_chip *chip ) { + struct cpwm_chip *cpwm = to_cpwm_chip( chip ); + uint16_t reg_value; + + cpwm_readb( cpwm->reg_map.PWM_REG_ENABLE, ®_value ); + cpwm_writeb( cpwm->reg_map.PWM_REG_ENABLE, reg_value & ~PWM_MASK_EN) ; +} + + +static void cpwm_pol_inv ( struct pwm_chip *chip ) { + struct cpwm_chip *cpwm = to_cpwm_chip( chip ); + uint16_t reg_value; + + cpwm_readb( cpwm->reg_map.PWM_REG_POLARITY, ®_value ); + cpwm_writeb( cpwm->reg_map.PWM_REG_POLARITY, reg_value & ~PWM_MASK_POL); +} + + +static void cpwm_pol_dir ( struct pwm_chip *chip ) { + struct cpwm_chip *cpwm = to_cpwm_chip( chip ); + uint16_t reg_value; + + cpwm_readb( cpwm->reg_map.PWM_REG_POLARITY, ®_value ); + cpwm_writeb( cpwm->reg_map.PWM_REG_POLARITY, reg_value | PWM_MASK_POL); +} + + +static int cpwm_apply( struct pwm_chip *chip, struct pwm_device *pwm, + const struct pwm_state *state ) +{ + unsigned long long period_cycles, duty_cycles, prescale; + struct cpwm_chip *cpwm = to_cpwm_chip( chip ); + struct pwm_state cstate; + unsigned long long clk1; + unsigned long long nclk; + uint16_t reg_value; + + pwm_get_state(pwm, &cstate); + if (state->enabled) { + prescale = 0; + + do { + clk1 = (MAIN_CLK >> 1); + do_div (clk1, (prescale + 1)); + nclk = state->period * clk1; + do_div (nclk, 1000000000); + nclk--; + prescale++; + } while (nclk & ~((unsigned long long)0xFFFF)); + prescale--; + + period_cycles = nclk; + duty_cycles = nclk * state->duty_cycle; + do_div (duty_cycles, 100); + + cpwm_writeb( cpwm->reg_map.PWM_REG_PERIOD, period_cycles & PWM_MASK_PERIOD); + cpwm_writeb( cpwm->reg_map.PWM_REG_DUTY, duty_cycles & PWM_MASK_DUTY); + if ( state->polarity != PWM_POLARITY_INVERSED ) { + cpwm_pol_dir( chip ); + } else { + cpwm_pol_inv( chip ); + } +cpwm_pol_inv( chip ); + cpwm_readb( cpwm->reg_map.PWM_REG_PRESCALE, ®_value ); + cpwm_writeb( cpwm->reg_map.PWM_REG_PRESCALE, reg_value | (PWM_MASK_PRESCALE & (~PWM_MASK_PRESCALE | prescale))); + + if (cstate.enabled) { + // do nothing + } else { + cpwm_enable( chip ); + } + + } else if ( cstate.enabled ) { + cpwm_disable( chip ); + } + return 0; +} +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + + +static const struct pwm_ops cpwm_ops = { + .apply = cpwm_apply, + .owner = THIS_MODULE, +}; + + +static struct cpwm_data cpwm_data = { + .polarity_supported = true, + .ops = &cpwm_ops, +}; + + + +static int cpwm_probe (struct platform_device *pdev) { + struct cpwm_chip *cpwm; + int ret, err; + + cpwm = kzalloc (sizeof (struct cpwm_chip), GFP_KERNEL); + if ( !cpwm ) { + CPWM_ERR ("cannot allocate memory for structure data"); + err = -ENOMEM; + goto err_data_allocate; + } + + /* check that the CPLD firmware is a GPIO expander */ + if ( cpld_is_gpio () ) { + cpwm->reg_map.PWM_REG_ENABLE = PWM_GPIO_REG1; + cpwm->reg_map.PWM_REG_POLARITY = PWM_GPIO_REG1; + cpwm->reg_map.PWM_REG_PRESCALE = PWM_GPIO_REG1; + cpwm->reg_map.PWM_REG_PERIOD = PWM_GPIO_REG2; + cpwm->reg_map.PWM_REG_DUTY = PWM_GPIO_REG3; + } else { + cpwm->reg_map.PWM_REG_ENABLE = PWM_LPC_REG1; + cpwm->reg_map.PWM_REG_POLARITY = PWM_LPC_REG1; + cpwm->reg_map.PWM_REG_PRESCALE = PWM_LPC_REG1; + cpwm->reg_map.PWM_REG_PERIOD = PWM_LPC_REG2; + cpwm->reg_map.PWM_REG_DUTY = PWM_LPC_REG3; + } + + platform_set_drvdata( pdev, cpwm ); + + cpwm->chip.ops = cpwm_data.ops; + cpwm->chip.dev = &pdev->dev; + cpwm->chip.base = -1; + cpwm->chip.npwm = 1; + + if ( cpwm_data.polarity_supported ) { + cpwm->chip.of_xlate = of_pwm_xlate_with_flags; + cpwm->chip.of_pwm_n_cells = 3; + } + + ret = pwmchip_add(&cpwm->chip); + if ( ret < 0 ) { + err = ret; + goto err_pwmchip_add; + } + + CPWM_INFO ("cpwm driver ver %s probed!!!", DRV_VERSION); + return 0; +err_pwmchip_add: + kfree( cpwm ); +err_data_allocate: + return err; +} + + +static int cpwm_remove (struct platform_device *pdev) { + return 0; +} + + + +static const struct of_device_id seco_cpwm_match[] = { + { .compatible = "seco,cpwm" }, + { /* sentinel */ } +}; + +MODULE_DEVICE_TABLE(of, seco_cpwm_match); + + +static struct platform_driver cpwm_driver = { + .driver = { + .name = "cpwm", + .owner = THIS_MODULE, + .of_match_table = seco_cpwm_match, + }, + .probe = cpwm_probe, + .remove = cpwm_remove, +}; + + + +static int __init cpwm_init(void) { + return platform_driver_register (&cpwm_driver); +} + +subsys_initcall(cpwm_init); + + +static void __exit cpwm_exit (void) { + return platform_driver_unregister (&cpwm_driver); +} + +module_exit(cpwm_exit); + + + +MODULE_AUTHOR("Davide Cardillo, SECO srl"); +MODULE_DESCRIPTION("SECO PWM over CPLD logic"); +MODULE_LICENSE("GPL"); +MODULE_VERSION(DRV_VERSION); diff --git a/drivers/seco/sio_w83627.c b/drivers/seco/sio_w83627.c new file mode 100644 index 00000000000000..e47a216cbe74a6 --- /dev/null +++ b/drivers/seco/sio_w83627.c @@ -0,0 +1,461 @@ + + +#include <linux/kernel.h> +#include <linux/device.h> +#include <linux/mutex.h> +#include <linux/module.h> +#include <linux/gpio.h> +#include <linux/slab.h> +#include <linux/delay.h> +#include <asm/byteorder.h> +#include <linux/sysctl.h> +#include <linux/interrupt.h> +#include <linux/of_irq.h> +#include <linux/of_device.h> +#include <linux/of_platform.h> +#include <linux/seco_lpc.h> +#include <linux/sio-w83627.h> + + +#define SIO_INFO(fmt, arg...) printk(KERN_INFO "SIO W83627: " fmt "\n" , ## arg) +#define SIO_ERR(fmt, arg...) printk(KERN_ERR "%s: " fmt "\n" , __func__ , ## arg) +#define SIO_DBG(fmt, arg...) pr_debug("%s: " fmt "\n" , __func__ , ## arg) + + +#define DRV_VERSION "1.0" + + +#define W83627DHG_UARTA (uint8_t)0x02 /* UART A */ +#define W83627DHG_UARTB (uint8_t)0x03 /* UART B IR */ +#define W83627EHF_LD_HWM (uint8_t)0x0b +#define W83667HG_LD_VID (uint8_t)0x0d /* Logical device = ?? */ + +#define SIO_REG_LDSEL (uint8_t)0x07 /* Logical device select */ +#define SIO_REG_DEVID (uint8_t)0x20 /* Device ID (2 bytes) */ +#define SIO_REG_GLOBALOPT (uint8_t)0x24 /* Global Options */ +#define SIO_REG_EN_VRM10 (uint8_t)0x2C /* GPIO3, GPIO4 selection */ +#define SIO_REG_ENABLE (uint8_t)0x30 /* Logical device enable */ +#define SIO_REG_ADDR (uint8_t)0x60 /* Logical device address (2 bytes) */ +#define SIO_REG_IRQ (uint8_t)0x70 /* Logical device irq*/ +#define SIO_REG_VID_CTRL (uint8_t)0xF0 /* VID control */ +#define SIO_REG_VID_DATA (uint8_t)0xF1 /* VID data */ + +#define CFG_REG_UART_A_CLK 0xF0 /* CFG REGISTER OF THE UART A CLOCK */ + +#define CFG_REG_UART_B_CLK 0xF0 /* CFG REGISTER OF THE UART B CLOCK */ + +#define WDT_CLOCK_1846200 (0x00) /* 1.8462MHz clock source (24MHz/13) */ +#define WDT_CLOCK_2000000 (0x01) /* 2MHz clock source (24MHz/12) */ +#define WDT_CLOCK_2400000 (0x02) /* 24MHz clock source (24MHz/1) */ + +#define SIO_W83627EHF_ID 0x8850 +#define SIO_W83627EHG_ID 0x8860 +#define SIO_W83627DHG_ID 0xa020 +#define SIO_W83627DHG_P_ID 0xb070 +#define SIO_W83667HG_ID 0xa510 +#define SIO_ID_MASK 0xFFF0 + +#define CFG_REG_IDX (0x2E << 1) +#define CFG_REG_DATA (0x2F << 1) + + +#define SLOT_UART_A 4 +#define SLOT_UART_B 3 + +#define BASE_CHIP_ID 0xB070 + +#define CR_SOFT_RESET 0x02 +#define CR_LOGICAL_DEV 0x07 +#define CR_CHIP_ID_LO 0x21 +#define CR_CHIP_ID_HI 0x20 +#define CR_DEV_PWR_DOWN 0x22 +#define CR_IPD 0x23 +#define CR_GLOBAL_OPT1 0x24 +#define CR_INTERFACE_TRI_EN 0x25 +#define CR_GLOBAL_OPT2 0x26 + + +#define REG_EFER 0x2E // Extended Function Enable/Index Register +#define REG_EFDR 0x2F // Extended Function Data Register + + +#define ENTER_EXT_MODE_CODE 0x87 +#define EXIT_EXT_MODE_CODE 0xAA +#define SW_RESET_CODE 0x01 + + +#define WINBOND_UART_CLOCK 24000000 + +#define SUPERIO_UART3_BASE 0x03F8 +#define SUPERIO_UART4_BASE 0x02F8 + + + +static uint8_t reg_global_addr[] = { + 0x02, 0x07, 0x20, 0x21, 0x22, + 0x23, 0x24, 0x25, 0x26, 0x27, + 0x28, 0x29, 0x2A, 0x2B, 0x2C, + 0x2D, 0x2E, 0x2F +}; + + +static uint8_t reg_ldev_2_addr[] = { + 0x30, 0x60, 0x61, 0x70, 0xF0 +}; + + +static uint8_t reg_ldev_3_addr[] = { + 0x30, 0x60, 0x61, 0x70, 0xF0, 0xF1 +}; + + +static uint8_t reg_ldev_9_addr[] = { + 0x30, 0XE0, 0XE1, 0XE2, 0XE3, + 0XE4, 0XE5, 0XE6, 0XE7, 0XE8, + 0XE9, 0XF0, 0XF1, 0XF2, 0XF3, + 0XF4, 0XF5, 0XF6, 0XF7, 0XF8, + 0XF9, 0XFA, 0XFE +}; + + +/* __________________________________________________________________________ +* | | +* | BASIC FUNCTIONS | +* |__________________________________________________________________________| +*/ + +static inline void superio_outb (uint8_t addr, uint8_t value) { + uint16_t val16 = (uint16_t)value; + uint16_t addr16 = (uint16_t)addr; + lpc_writew (REG_EFER, addr16); + lpc_writew (REG_EFDR, val16); +} + + +static inline void superio_inb (uint8_t addr, uint8_t *data) { + uint16_t val16 = 0; + uint16_t addr16 = (uint16_t)addr; + lpc_writew (REG_EFER, addr16); + lpc_readw (REG_EFDR, &val16); + *data = (uint8_t)(val16); +} + + +static inline void superio_enter_ext_mode (void) { + lpc_writew (REG_EFER, ENTER_EXT_MODE_CODE); + lpc_writew (REG_EFER, ENTER_EXT_MODE_CODE); +} + + +static inline void superio_exit_ext_mode (void) { + lpc_writew (REG_EFER, EXIT_EXT_MODE_CODE); +} + + +static inline void superio_sw_reset (void) { + lpc_writew (REG_EFER, CR_SOFT_RESET); + lpc_writew (REG_EFDR, SW_RESET_CODE); +} +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ +static uint16_t getChipID (void) { + uint8_t r_h = 0x00; + uint8_t r_l = 0x00; + + udelay (10); + superio_inb (CR_CHIP_ID_HI, &r_h); + superio_inb (CR_CHIP_ID_LO, &r_l); + + return ((uint16_t)r_l) | (((uint16_t)r_h) << 8); +} + + +static int chipIDvalidate (uint16_t id) { + return (id & 0xFFF0) == BASE_CHIP_ID ? 1 : 0; +} + + +static inline void superio_select (uint8_t logical_dev_id) { + superio_outb (CR_LOGICAL_DEV, logical_dev_id); +} +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + + +static void superio_gpio_read (uint8_t addr, uint8_t *data, uint8_t ldev_id) { + superio_enter_ext_mode (); + superio_select (ldev_id); + superio_inb (addr, data); + superio_exit_ext_mode (); +} + + +static void superio_gpio_write (uint8_t addr, uint8_t value, uint8_t ldev_id) { + superio_enter_ext_mode (); + superio_select (ldev_id); + superio_outb (addr, value); + superio_exit_ext_mode (); +} + + +static void superio_uart_read (uint8_t addr, uint8_t *data, uint8_t ldev_id) { + superio_enter_ext_mode (); + superio_select (ldev_id); + superio_inb (addr, data); + superio_exit_ext_mode (); +} + + +static void superio_uart_write (uint8_t addr, uint8_t value, uint8_t ldev_id) { + superio_enter_ext_mode (); + superio_select (ldev_id); + superio_outb (addr, value); + superio_exit_ext_mode (); +} + + +static void superio_global_read (uint8_t addr, uint8_t *data) { + superio_enter_ext_mode (); + superio_inb (addr, data); + superio_exit_ext_mode (); +} + + +static void superio_global_write (uint8_t addr, uint8_t value) { + superio_enter_ext_mode (); + superio_outb (addr, value); + superio_exit_ext_mode (); +} + + +static struct sio_w83627_ops gpio_ops = { + .read = superio_gpio_read, + .write = superio_gpio_write, + .g_read = superio_global_read, + .g_write = superio_global_write +}; + + +static struct sio_w83627_ops uart_ops = { + .read = superio_uart_read, + .write = superio_uart_write, + .g_read = superio_global_read, + .g_write = superio_global_write +}; + + +static struct of_dev_auxdata sio_auxdata_lookup[] = { + OF_DEV_AUXDATA("nuvoton,w83627dhg_gpio", 0, "sio_gpio_w83627", &gpio_ops), + OF_DEV_AUXDATA("nuvoton,w83627dhg_A_16550a", 0, "sio_uart_a_w83627", &uart_ops), + OF_DEV_AUXDATA("nuvoton,w83627dhg_B_16550a", 0, "sio_uart_b_w83627", &uart_ops), + { /* sentinel */ }, +}; + + +static int superio_wb_driver_allocate (struct device *parent_dev, struct device_node *dp) { + int status; + + status = of_platform_populate (dp, NULL, sio_auxdata_lookup, parent_dev); + if ( status ) { + SIO_ERR ("failed to create device"); + } else { + SIO_INFO ("superio device created"); + } + + return status; +} + + +/* __________________________________________________________________________ +* | | +* | SYSFS INTERFACE | +* |__________________________________________________________________________| +*/ +static ssize_t sys_superio_wb_revision (struct device *dev, struct device_attribute *attr, + char *buf) +{ + uint16_t ver; + + superio_enter_ext_mode (); + ver = getChipID (); + superio_exit_ext_mode (); + + return sprintf(buf, "0x%04X\n",ver); +} + +static DEVICE_ATTR(superio_ver, S_IRUGO, sys_superio_wb_revision, NULL); + + + +static ssize_t sys_dump_regs (const uint8_t *reg_array, int a_size, char *buf, uint8_t ldev) { + unsigned char msg[500]; + unsigned char tmp[50]; + uint8_t value; + int i; + + superio_enter_ext_mode (); + if ( ldev < 0xD ) { + superio_select (ldev); + } + sprintf (msg, "\n#\tvalue"); + for ( i = 0 ; i < a_size ; i++ ) { + superio_inb (reg_array[i], &value); + sprintf (tmp, "\n0x%02X\t0x%02X", reg_array[i], value); + strcat (msg, tmp); + } + superio_exit_ext_mode (); + + return sprintf (buf, "%s\n", msg); +} + + +static ssize_t sys_superio_dump_global_regs (struct device *dev, struct device_attribute *attr, + char *buf) +{ + return sys_dump_regs (reg_global_addr, ARRAY_SIZE (reg_global_addr), buf, (uint8_t)-1); +} + +static DEVICE_ATTR(dump_global_regs, S_IRUGO, sys_superio_dump_global_regs, NULL); + + +static ssize_t sys_superio_dump_log_dev_2_regs (struct device *dev, struct device_attribute *attr, + char *buf) +{ + return sys_dump_regs (reg_ldev_2_addr, ARRAY_SIZE (reg_ldev_2_addr), buf, (uint8_t)2); +} + +static DEVICE_ATTR(dump_ldev2_regs, S_IRUGO, sys_superio_dump_log_dev_2_regs, NULL); + + +static ssize_t sys_superio_dump_log_dev_3_regs (struct device *dev, struct device_attribute *attr, + char *buf) +{ + return sys_dump_regs (reg_ldev_3_addr, ARRAY_SIZE (reg_ldev_3_addr), buf, (uint8_t)3); +} + +static DEVICE_ATTR(dump_ldev3_regs, S_IRUGO, sys_superio_dump_log_dev_3_regs, NULL); + + +static ssize_t sys_superio_dump_log_dev_9_regs (struct device *dev, struct device_attribute *attr, + char *buf) +{ + return sys_dump_regs (reg_ldev_9_addr, ARRAY_SIZE (reg_ldev_9_addr), buf, (uint8_t)9); +} + +static DEVICE_ATTR(dump_ldev9_regs, S_IRUGO, sys_superio_dump_log_dev_9_regs, NULL); + + +static struct attribute *superio_wb_attrs[] = { + &dev_attr_superio_ver.attr, + &dev_attr_dump_global_regs.attr, + &dev_attr_dump_ldev2_regs.attr, + &dev_attr_dump_ldev3_regs.attr, + &dev_attr_dump_ldev9_regs.attr, + NULL, +}; + + +static struct attribute_group superio_wb_attr_group = { + .attrs = superio_wb_attrs, +}; +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ +static int superio_wb_probe (struct platform_device *pdev) { + struct device_node *dp = pdev->dev.of_node; + int err = 0; + uint16_t rev = 0; + + /* device software restetting */ + superio_sw_reset (); + udelay (10); + + /* validate chip through device and vendor ID */ + superio_enter_ext_mode (); + + rev = getChipID (); + if (chipIDvalidate (rev) ) + SIO_INFO ("Winbond version: 0x%04X", rev); + else { + SIO_ERR ("invalid Winbond version: 0x%04X", rev); + superio_exit_ext_mode (); + err = -EINVAL; + goto err_rev_inval; + } + + superio_exit_ext_mode (); + + + err = sysfs_create_group (&pdev->dev.kobj, &superio_wb_attr_group); + if ( err ) { + SIO_ERR ("cannot create sysfs interface"); + goto err_sysfs; + } + + err = superio_wb_driver_allocate (&pdev->dev, dp); + if ( err ) { + SIO_ERR ("cannot allocat superIO sub-devices: %#X", err); + goto err_device_allocate; + } + + + SIO_INFO ("LPC SuperIO driver ver %s probed!!!", DRV_VERSION); + return 0; +err_device_allocate: + sysfs_remove_group(&pdev->dev.kobj, &superio_wb_attr_group); +err_sysfs: +err_rev_inval: + return err; +} + + +static int superio_wb_remove (struct platform_device *pdev) { + + platform_device_unregister (pdev); + kfree (pdev); + + return 0; +} + + +static const struct of_device_id seco_superio_wb_match[] = { + { .compatible = "nuvoton,w83627dhg" }, + { /* sentinel */ } +}; + +MODULE_DEVICE_TABLE(of, seco_superio_wb_match); + + +static struct platform_driver superio_wb_driver = { + .driver = { + .name = "sio_w83627", + .owner = THIS_MODULE, + .of_match_table = seco_superio_wb_match, + }, + .probe = superio_wb_probe, + .remove = superio_wb_remove, +}; + + + +static int __init superio_wb_init(void) { + return platform_driver_register (&superio_wb_driver); +} + +subsys_initcall(superio_wb_init); + + +static void __exit superio_wb_exit (void) { + return platform_driver_unregister (&superio_wb_driver); +} + +module_exit(superio_wb_exit); + + + +MODULE_AUTHOR("Davide Cardillo, SECO srl"); +MODULE_DESCRIPTION("Nuvoton LPC SuperIO - SECO version"); +MODULE_LICENSE("GPL"); +MODULE_VERSION(DRV_VERSION); diff --git a/drivers/seco/sio_w83627_gpio.c b/drivers/seco/sio_w83627_gpio.c new file mode 100644 index 00000000000000..2051d670f6bcb9 --- /dev/null +++ b/drivers/seco/sio_w83627_gpio.c @@ -0,0 +1,497 @@ + + +#include <linux/kernel.h> +#include <linux/device.h> +#include <linux/mutex.h> +#include <linux/module.h> +#include <linux/gpio.h> +#include <linux/slab.h> +#include <linux/delay.h> +#include <asm/byteorder.h> +#include <linux/sysctl.h> +#include <linux/interrupt.h> +#include <linux/of_irq.h> +#include <linux/of_device.h> +#include <linux/of_platform.h> +#include <linux/sio-w83627.h> + + +#define SIO_GPIO_INFO(fmt, arg...) printk(KERN_INFO "GPIO SIO W83627: " fmt "\n" , ## arg) +#define SIO_GPIO_ERR(fmt, arg...) printk(KERN_ERR "%s: " fmt "\n" , __func__ , ## arg) +#define SIO_GPIO_DBG(fmt, arg...) pr_debug("%s: " fmt "\n" , __func__ , ## arg) + + +#define DRV_VERSION "1.0" + +#define NR_GPIO_BANK 6 +#define NR_GPIO 8 + +#define NUM_REG 4 +#define MAX_N_STRAP 3 + +#define REG_REGISTER 0 +#define REG_DATA 1 +#define REG_STATUS 2 +#define REG_INV 3 + +#define REG_ENABLE (uint8_t)0x30 + +/* In this moment only GPIO2 and GPIO3 are supported */ +static int valid_gpio_id[] = { 2, 3 }; + +static int gpio_logical_device[] = { 0, 9, 9, 9, 9, 7 }; + + +static uint8_t config_reg_map[NR_GPIO_BANK][NUM_REG] = { + [2] = { + [REG_REGISTER] = 0xE3, + [REG_DATA] = 0xE4, + [REG_STATUS] = 0xE5, + [REG_INV] = 0xE6 + }, + [3] = { + [REG_REGISTER] = 0xF0, + [REG_DATA] = 0xF1, + [REG_STATUS] = 0xF2, + [REG_INV] = 0xE7 + }, +}; + + +static uint8_t mux_reg_map[NR_GPIO_BANK][MAX_N_STRAP][3] = { + [2] = { + /* REG AND OR */ + {0x29, 0x06, 0x02}, // for gpio 0, 1 + {0x24, 0x02, 0x00}, // for gpio 2, 3 + {0x2A, 0x01, 0x01}, // for gpio 4, 5, 6, 7 + }, + [3] = { + {0x2C, 0xF0, 0x00}, // for all gpio + {}, + {}, + }, +}; + + +#define NR_GPIO 8 +#define SIO_GPIO_LBL "seco_sio_gpio" +#define CAN_SLEEP 0 + +#define GPIO1 0x01 +#define GPIO2 0x02 +#define GPIO3 0x04 +#define GPIO4 0x08 +#define GPIO5 0x0F +#define GPIO6 0x20 +#define GPIO7 0x40 +#define GPIO8 0x80 +#define GPIO_ALL 0xFF + + +struct sio_gpio_exp_chip { + struct gpio_chip gpio_chip; + int gpio_id; + int gpio_ldev; + struct sio_w83627_ops *sio_ops; + + struct mutex lock; + + uint8_t cache[NUM_REG]; + + uint8_t *conf_reg_map; + uint8_t (*mux_reg_map)[3]; +}; + + + + +#define sio_gpio_read(sio_chip, addr, data) \ + (sio_chip)->sio_ops->read (addr, data, (sio_chip)->gpio_ldev) + +#define sio_gpio_write(sio_chip, addr, data) \ + (sio_chip)->sio_ops->write (addr, data, (sio_chip)->gpio_ldev) + +#define sio_conf_reg(sio_chip, reg) \ + (sio_chip)->conf_reg_map[(reg)] + + + +/* __________________________________________________________________________ +* | | +* | HW SETTING FUNCTION | +* |__________________________________________________________________________| +*/ +static void sio_gpio_wb_active_gpio (struct sio_gpio_exp_chip *sio_gpio_chip, int en) { + uint8_t val = 0; + sio_gpio_chip->sio_ops->read (REG_ENABLE, &val, sio_gpio_chip->gpio_ldev); + val = en ? val | (1u << (sio_gpio_chip->gpio_id - 2)) : + val & ~(1u << (sio_gpio_chip->gpio_id - 2)); + sio_gpio_chip->sio_ops->write (REG_ENABLE, val, sio_gpio_chip->gpio_ldev); +} + + +static void sio_gpio_wb_set_muxing (struct sio_gpio_exp_chip *sio_gpio_chip) { + int i; + uint8_t (*mux_v)[3] = sio_gpio_chip->mux_reg_map; + uint8_t val = 0; + + for ( i = 0 ; i < MAX_N_STRAP ; i++ ) { + if ( mux_v[i] == 0 ) + break; + sio_gpio_chip->sio_ops->g_read (mux_v[i][0], &val); + val &= ~mux_v[i][1]; + val |= mux_v[i][2]; + sio_gpio_chip->sio_ops->g_write (mux_v[i][0], val); + } +} + + +static void sio_gpio_wb_set_info (struct sio_gpio_exp_chip *sio_gpio_chip) { + sio_gpio_chip->conf_reg_map = &config_reg_map[sio_gpio_chip->gpio_id][0]; + sio_gpio_chip->mux_reg_map = &mux_reg_map[sio_gpio_chip->gpio_id][0]; +} + + +static int is_valid_gpio_id (int gpio_id) { + int i; + for ( i = 0 ; i < ARRAY_SIZE(valid_gpio_id) ; i++ ) { + if ( valid_gpio_id[i] == gpio_id ) + break; + } + + return i == ARRAY_SIZE(valid_gpio_id) ? 0 : 1; +} +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + + +/* __________________________________________________________________________ +* | | +* | CACHE SYNC FUNCTION | +* |__________________________________________________________________________| +*/ +static int sio_gpio_exp_sync_to_cache_reg (struct sio_gpio_exp_chip *sio_gpio_chip) { + int i, nreg; + int ret = 0; + nreg = ARRAY_SIZE (sio_gpio_chip->cache); + + for ( i = 0 ; i < nreg && ret >= 0 ; i++ ) { + sio_gpio_write (sio_gpio_chip, i, sio_gpio_chip->cache[i]); + } + + return (nreg - i); +} + + +static int sio_gpio_exp_sync_from_cache_reg (struct sio_gpio_exp_chip *sio_gpio_chip) { + + sio_gpio_write (sio_gpio_chip, sio_conf_reg(sio_gpio_chip, REG_REGISTER), + sio_gpio_chip->cache[REG_REGISTER]); + sio_gpio_write (sio_gpio_chip, sio_conf_reg(sio_gpio_chip, REG_INV), + sio_gpio_chip->cache[REG_INV]); + return 0; +} +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + + + +/* __________________________________________________________________________ +* | | +* | GPIO CHIP INTERFACE | +* |__________________________________________________________________________| +*/ +static int sio_gpio_exp_get_value (struct gpio_chip *chip, unsigned offset) { + uint8_t reg_value; + int status = 0; + struct sio_gpio_exp_chip *sio_gpio_chip; + uint8_t mask = 1u << offset; + + sio_gpio_chip = container_of (chip, struct sio_gpio_exp_chip, gpio_chip); + + mutex_lock (&sio_gpio_chip->lock); + sio_gpio_read (sio_gpio_chip, sio_conf_reg(sio_gpio_chip, REG_DATA), ®_value); + mutex_unlock (&sio_gpio_chip->lock); + + status = (int)(reg_value & mask); + return status; +} + + +static void __sio_gpio_exp_set_value (struct sio_gpio_exp_chip *sio_gpio_chip, unsigned mask, int value) { + uint8_t reg_out = (value) ? sio_gpio_chip->cache[REG_DATA] | (uint8_t)mask : + sio_gpio_chip->cache[REG_DATA] & (uint8_t)~mask; + + sio_gpio_write (sio_gpio_chip, sio_conf_reg(sio_gpio_chip, REG_DATA), reg_out); + + sio_gpio_chip->cache[REG_DATA] = reg_out; +} + + +static void sio_gpio_exp_set_value (struct gpio_chip *chip, unsigned offset, int value) { + struct sio_gpio_exp_chip *sio_gpio_chip; + uint8_t mask = 1u << offset; + + sio_gpio_chip = container_of (chip, struct sio_gpio_exp_chip, gpio_chip); + + mutex_lock (&sio_gpio_chip->lock); + __sio_gpio_exp_set_value (sio_gpio_chip, mask, value); + mutex_unlock (&sio_gpio_chip->lock); +} + + +static int sio_gpio_exp_direction_input (struct gpio_chip *chip, unsigned offset) { + struct sio_gpio_exp_chip *sio_gpio_chip; + + sio_gpio_chip = container_of (chip, struct sio_gpio_exp_chip, gpio_chip); + + mutex_lock (&sio_gpio_chip->lock); + sio_gpio_chip->cache[REG_REGISTER] |= (1 << offset); + sio_gpio_write (sio_gpio_chip, sio_conf_reg(sio_gpio_chip, REG_REGISTER), + sio_gpio_chip->cache[REG_REGISTER]); + mutex_unlock (&sio_gpio_chip->lock); + + return 0; +} + + +static int sio_gpio_exp_direction_output (struct gpio_chip *chip, unsigned offset, int value) { + struct sio_gpio_exp_chip *sio_gpio_chip; + unsigned mask = 1 << offset; + + sio_gpio_chip = container_of (chip, struct sio_gpio_exp_chip, gpio_chip); + + mutex_lock (&sio_gpio_chip->lock); + __sio_gpio_exp_set_value (sio_gpio_chip, mask, value); + sio_gpio_chip->cache[REG_REGISTER] &= ~mask; + sio_gpio_write (sio_gpio_chip, sio_conf_reg(sio_gpio_chip, REG_REGISTER), + sio_gpio_chip->cache[REG_REGISTER]); + mutex_unlock (&sio_gpio_chip->lock); + + return 0; +} + + +static void sio_gpio_exp_dbg_show (struct seq_file *s, struct gpio_chip *chip) { +} + +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + +/* __________________________________________________________________________ +* | | +* | SYSFS INTERFACE | +* |__________________________________________________________________________| +*/ +static ssize_t sys_sio_gpio_dump_global_regs (struct device *dev, struct device_attribute *attr, + char *buf) +{ + struct sio_gpio_exp_chip *sio_gpio_chip = (struct sio_gpio_exp_chip *)dev_get_drvdata (dev); + unsigned char msg[500]; + unsigned char tmp[50]; + uint8_t value; + int i; + + sprintf (msg, "\n#\tvalue"); + for ( i = 0 ; i < NUM_REG ; i++ ) { + sio_gpio_read (sio_gpio_chip, sio_conf_reg(sio_gpio_chip, i), &value); + + sprintf (tmp, "\n0x%02X\t0x%02X", sio_conf_reg(sio_gpio_chip, i), value); + strcat (msg, tmp); + } + sio_gpio_read (sio_gpio_chip, REG_ENABLE, &value); + sprintf (tmp, "\nActive GPIO reg: %#X", value); + strcat (msg, tmp); + + return sprintf (buf, "%s\n", msg); +} + +static DEVICE_ATTR(dump_regs, S_IRUGO, sys_sio_gpio_dump_global_regs, NULL); + + +static struct attribute *sio_gpio_attrs[] = { + &dev_attr_dump_regs.attr, + NULL, +}; + + +static struct attribute_group sio_gpio_attr_group = { + .attrs = sio_gpio_attrs, +}; + + + +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + + +static int sio_gpio_exp_setup (struct sio_gpio_exp_chip *sio_gpio_chip, struct device *dev, + unsigned base) { + int err, status; + + /* init gpio chip structure */ + sio_gpio_chip->gpio_chip.get = sio_gpio_exp_get_value; + sio_gpio_chip->gpio_chip.set = sio_gpio_exp_set_value; + sio_gpio_chip->gpio_chip.direction_input = sio_gpio_exp_direction_input; + sio_gpio_chip->gpio_chip.direction_output = sio_gpio_exp_direction_output; + sio_gpio_chip->gpio_chip.dbg_show = sio_gpio_exp_dbg_show; + + sio_gpio_chip->gpio_chip.of_gpio_n_cells = 2; + sio_gpio_chip->gpio_chip.of_node = dev->of_node; + + sio_gpio_chip->gpio_chip.ngpio = NR_GPIO; + sio_gpio_chip->gpio_chip.label = SIO_GPIO_LBL; + + sio_gpio_chip->gpio_chip.base = base; + sio_gpio_chip->gpio_chip.can_sleep = CAN_SLEEP; + sio_gpio_chip->gpio_chip.parent = dev; + sio_gpio_chip->gpio_chip.owner = THIS_MODULE; + + mutex_init (&sio_gpio_chip->lock); + + /* init registers configuration */ + sio_gpio_chip->cache[REG_REGISTER] = 0xFF; // all gpios as input + sio_gpio_chip->cache[REG_INV] = 0x00; // no inversion value + + sio_gpio_exp_sync_from_cache_reg (sio_gpio_chip); + sio_gpio_exp_sync_to_cache_reg (sio_gpio_chip); + + /* add this gpio bank */ + status = gpiochip_add (&sio_gpio_chip->gpio_chip); + if ( status < 0 ) { + SIO_GPIO_ERR ("cannot add gpio bank to the system"); + err = status; + goto err_gpio_add; + } + + return 0; +err_gpio_add: + return err; +} + + + + +static int sio_gpio_wb_probe (struct platform_device *pdev) { + struct device_node *dp = pdev->dev.of_node; + struct sio_gpio_exp_chip *sio_gpio_chip; + const __be32 *addr; + int ret, err, len, gpio_id; + unsigned base = -1; + + sio_gpio_chip = kzalloc (sizeof (struct sio_gpio_exp_chip), GFP_KERNEL); + if ( !sio_gpio_chip ) { + SIO_GPIO_ERR ("cannot allocate memory for structure data"); + err = -ENOMEM; + goto err_data_allocate; + } + + platform_set_drvdata (pdev, sio_gpio_chip); + + sio_gpio_chip->sio_ops = (struct sio_w83627_ops *)dev_get_platdata(&pdev->dev); + + if ( !sio_gpio_chip->sio_ops ) { + SIO_GPIO_ERR ("cannot obtain ops structure data"); + err = -EINVAL; + goto err_ops_data; + } + if ( !sio_gpio_chip->sio_ops->read || !sio_gpio_chip->sio_ops->write || + !sio_gpio_chip->sio_ops->g_read || !sio_gpio_chip->sio_ops->g_write) { + SIO_GPIO_ERR ("write and read operation not assigned"); + err= -EINVAL; + goto err_ops_data; + } + + addr = of_get_property(dp, "gpio_id", &len); + if ( !addr || (len < sizeof(int))) { + SIO_GPIO_ERR ("unable to obtain gpio ID!!!"); + err = -EINVAL; + goto err_gpio_id; + } + gpio_id = be32_to_cpup (addr); + + if ( !is_valid_gpio_id (gpio_id) ) { + SIO_GPIO_ERR ("invalid gpio ID (%d)!!!", gpio_id); + err = -EINVAL; + goto err_gpio_id; + } + sio_gpio_chip->gpio_id = gpio_id; + sio_gpio_chip->gpio_ldev = gpio_logical_device[gpio_id]; + sio_gpio_wb_active_gpio (sio_gpio_chip, 1); + + sio_gpio_wb_set_info (sio_gpio_chip); + sio_gpio_wb_set_muxing (sio_gpio_chip); + + ret = sio_gpio_exp_setup (sio_gpio_chip, &pdev->dev, base); + if ( ret != 0 ) { + SIO_GPIO_ERR ("cannot driver setup"); + err = ret; + goto err_setup; + } + + err = sysfs_create_group (&pdev->dev.kobj, &sio_gpio_attr_group); + if ( err ) { + SIO_GPIO_ERR ("cannot create sysfs interface"); + goto err_sysfs; + } + + SIO_GPIO_INFO ("LPC SuperIO GPIO-%d driver ver %s probed!!!", gpio_id, DRV_VERSION); + return 0; +err_sysfs: +err_setup: +err_ops_data: +err_gpio_id: + kfree (sio_gpio_chip); +err_data_allocate: + return err; +} + + +static int sio_gpio_wb_remove (struct platform_device *pdev) { + return 0; +} + + +static const struct of_device_id seco_sio_gpio_wb_match[] = { + { .compatible = "nuvoton,w83627dhg_gpio" }, + { /* sentinel */ } +}; + +MODULE_DEVICE_TABLE(of, seco_sio_gpio_wb_match); + + +static struct platform_driver sio_gpio_wb_driver = { + .driver = { + .name = "sio_gpio_w83627", + .owner = THIS_MODULE, + .of_match_table = seco_sio_gpio_wb_match, + }, + .probe = sio_gpio_wb_probe, + .remove = sio_gpio_wb_remove, +}; + + + +static int __init sio_gpio_wb_init(void) { + return platform_driver_register (&sio_gpio_wb_driver); +} + +subsys_initcall(sio_gpio_wb_init); + + +static void __exit sio_gpio_wb_exit (void) { + return platform_driver_unregister (&sio_gpio_wb_driver); +} + +module_exit(sio_gpio_wb_exit); + + + +MODULE_AUTHOR("Davide Cardillo, SECO srl"); +MODULE_DESCRIPTION("Nuvoton LPC SuperIO GPIO Expander - SECO version"); +MODULE_LICENSE("GPL"); +MODULE_VERSION(DRV_VERSION); diff --git a/drivers/seco/sio_w83627_serial.c b/drivers/seco/sio_w83627_serial.c new file mode 100644 index 00000000000000..1948bb4b8b21d6 --- /dev/null +++ b/drivers/seco/sio_w83627_serial.c @@ -0,0 +1,292 @@ +#include <linux/module.h> +#include <linux/slab.h> +#include <linux/delay.h> +#include <linux/serial_core.h> +#include <linux/serial_reg.h> +#include <linux/of_address.h> +#include <linux/of_irq.h> +#include <linux/of_platform.h> +#include <linux/clk.h> +#include <linux/sio-w83627.h> +#include <linux/seco_cpld.h> +#include <linux/seco_lpc.h> + +#include <linux/sio_lpc_serial.h> + + + +#define SIO_W83627_REG_DEV_PWR 0x22 +#define SIO_W83627_REG_UART_TRI 0x25 +#define SIO_W83627_REG_MUX_A 0x29 +#define SIO_W83627_REG_MUX_B 0x2C + +#define SIO_W83627_PWR_UART_A 0x10 +#define SIO_W83627_PWR_UART_B 0x20 +#define SIO_W83627_TRI_UART_A 0x10 +#define SIO_W83627_TRI_UART_B 0x20 +#define SIO_W83627_MUX_A 0x08 +#define SIO_W83627_MUX_B 0x03 + +#define SIO_W83627_REG_UART_PWR 0x30 +#define SIO_W83627_REG_UART_ADDR_H 0x60 +#define SIO_W83627_REG_UART_ADDR_L 0x61 +#define SIO_W83627_REG_UART_IRQ_SRC 0x70 +#define SIO_W83627_REG_UART_IRQ_CTRL 0xF0 +#define SIO_W83627_REG_UART_IRQ_IR 0xF1 + +#define SIO_W83627_UART_ACTIVE 0x01 +#define SIO_W83627_UART_MAX_CLK 24000000 // 24 MHz + +#define sio_uart_read(sio_uart, addr, data) \ + (sio_uart)->sio_ops->read (addr, data, (sio_uart)->uart_ldev) + +#define sio_uart_write(sio_uart, addr, data) \ + (sio_uart)->sio_ops->write (addr, data, (sio_uart)->uart_ldev) + +#define sio_conf_reg(sio_uart, reg) \ + (sio_uart)->conf_reg_map[(reg)] + + + + +/* __________________________________________________________________________ +* | | +* | W83627DHG UART INIT | +* |__________________________________________________________________________| +*/ +static void w83627_uart_A_init (struct lpc_serial_port *info) { + uint8_t val = 0; + uint8_t clk_set = 0; + + /* Global Register */ + + info->sio_ops->g_read (SIO_W83627_REG_DEV_PWR, &val); + val |= SIO_W83627_PWR_UART_A; + info->sio_ops->g_write (SIO_W83627_REG_DEV_PWR, val); + + info->sio_ops->g_read (SIO_W83627_REG_UART_TRI, &val); + val &= ~SIO_W83627_TRI_UART_A; + info->sio_ops->g_write (SIO_W83627_REG_UART_TRI, val); + + info->sio_ops->g_read (SIO_W83627_REG_MUX_A, &val); + val &= ~SIO_W83627_MUX_A; + info->sio_ops->g_write (SIO_W83627_REG_MUX_A, val); + + /* UART Register */ + sio_uart_write (info, SIO_W83627_REG_UART_ADDR_H, (info->membase & 0xFF00) >> 8); + sio_uart_write (info, SIO_W83627_REG_UART_ADDR_L, info->membase & 0x00FF); + switch (info->uart_clk / SIO_W83627_UART_MAX_CLK) { + case 1: + clk_set = 0x02; + break; + case 12: + clk_set = 0x01; + break; + case 13: + clk_set = 0x00; + break; + default: + clk_set = 0x02; + } + sio_uart_write (info, SIO_W83627_REG_UART_IRQ_CTRL, clk_set); + sio_uart_write (info, SIO_W83627_REG_UART_PWR, SIO_W83627_UART_ACTIVE); +} + + +static void w83627_uart_B_init (struct lpc_serial_port *info) { + uint8_t val = 0; + uint8_t clk_set = 0; + + info->sio_ops->g_read (SIO_W83627_REG_DEV_PWR, &val); + val |= SIO_W83627_PWR_UART_B; + info->sio_ops->g_write (SIO_W83627_REG_DEV_PWR, val); + + info->sio_ops->g_read (SIO_W83627_REG_UART_TRI, &val); + val &= ~SIO_W83627_TRI_UART_B; + info->sio_ops->g_write (SIO_W83627_REG_UART_TRI, val); + + info->sio_ops->g_read (SIO_W83627_REG_MUX_B, &val); + val |= SIO_W83627_MUX_B; + info->sio_ops->g_write (SIO_W83627_REG_MUX_B, val); + + /* UART Register */ + sio_uart_write (info, SIO_W83627_REG_UART_ADDR_H, (info->membase & 0xFF00) >> 8); + sio_uart_write (info, SIO_W83627_REG_UART_ADDR_L, info->membase & 0x00FF); + switch (info->uart_clk / SIO_W83627_UART_MAX_CLK) { + case 1: + clk_set = 0x02; + break; + case 12: + clk_set = 0x01; + break; + case 13: + clk_set = 0x00; + break; + default: + clk_set = 0x02; + } + sio_uart_write (info, SIO_W83627_REG_UART_IRQ_CTRL, clk_set); + sio_uart_write (info, SIO_W83627_REG_UART_PWR, SIO_W83627_UART_ACTIVE); +} +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + + +/* __________________________________________________________________________ +* | | +* | W83627DHG UART COMMUNICATION | +* |__________________________________________________________________________| +*/ +unsigned int w83627_serial_in (struct uart_port *port, int offset) { + uint16_t data; + uint16_t addr = (uint16_t)(port->mapbase ) & 0xFFFF; + lpc_readw (addr + offset, &data); + return (int)data; +} + + +void w83627_serial_out (struct uart_port *port, int offset, int value) { + uint16_t addr = (uint16_t)(port->mapbase ) & 0xFFFF; + lpc_writew (addr + offset, value); +} +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + + +/* __________________________________________________________________________ +* | | +* | SYSFS INTERFACE | +* |__________________________________________________________________________| +*/ +static ssize_t sys_w83627_dump_uart_regs (struct device *dev, struct device_attribute *attr, + char *buf) +{ + struct lpc_serial_port *info = (struct lpc_serial_port *)dev_get_drvdata (dev); + unsigned char msg[500]; + unsigned char tmp[50]; + uint8_t value; + int i; + + sprintf (msg, "\n#\tvalue"); + for ( i = 0 ; i <= 7 ; i++) { + value = (uint16_t)w83627_serial_in (&info->port, i); + sprintf (tmp, "\n0x%02X\t0x%02X", i, value); + strcat (msg, tmp); + } + + return sprintf (buf, "%s\n", msg); +} + + +static ssize_t sys_w83627_store_uart_regs (struct device *dev, struct device_attribute *attr, + const char *buf, size_t count) +{ + struct lpc_serial_port *info = (struct lpc_serial_port *)dev_get_drvdata (dev); + uint8_t reg, value; + unsigned long val; + char *start = (char *)buf; + + while (*start == ' ') + start++; + + reg = (uint8_t)simple_strtoul (start, &start, 16); + + if ( reg < 0 || reg > 7 ) { + return -EINVAL; + } + + while (*start == ' ') + start++; + + if ( kstrtoul (start, 16, &val) ) { + return -EINVAL; + } + + value = (uint8_t)val; + + w83627_serial_out (&info->port, reg, value); + + return count; +} + + +static DEVICE_ATTR(dump_uart_regs, 0664, sys_w83627_dump_uart_regs, sys_w83627_store_uart_regs); + + +static ssize_t sys_w83627_payload_size_show (struct device *dev, struct device_attribute *attr, + char *buf) +{ + struct lpc_serial_port *info = (struct lpc_serial_port *)dev_get_drvdata (dev); + + return sprintf (buf, "%d\n", info->payload_size); +} + + +static DEVICE_ATTR(payload_size, 0444, sys_w83627_payload_size_show, NULL); + + +static struct attribute *w83627_uart_attrs[] = { + &dev_attr_dump_uart_regs.attr, + &dev_attr_payload_size.attr, + NULL, +}; + + +static struct attribute_group w83627_uart_attr_group = { + .attrs = w83627_uart_attrs, +}; + + +int lpc_w83627_sys_serial_setup (struct platform_device *pdev, struct lpc_serial_port *info) { + int err = 0; + switch ( info->uart_index ) { + case LPC_UART_TYPE_W83627_A: + case LPC_UART_TYPE_W83627_B: + err = sysfs_create_group (&pdev->dev.kobj, &w83627_uart_attr_group); + break; + default: + break; + } + return err; +} + +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + + +int lpc_w83627_platform_serial_setup (struct platform_device *pdev, + // int type, struct uart_port *port, + struct lpc_serial_port *info) +{ + int ret = 0; + + switch ( info->uart_index ) { + case LPC_UART_TYPE_W83627_A: + w83627_uart_A_init (info); + break; + case LPC_UART_TYPE_W83627_B: + w83627_uart_B_init (info); + break; + default: + ret = -1; + } + + if ( !ret) { + switch ( info->uart_index ) { + case LPC_UART_TYPE_W83627_A: + case LPC_UART_TYPE_W83627_B: + info->serial_in = w83627_serial_in; + info->serial_out = w83627_serial_out; + info->type = LPC_PORT_TYPE_W83627; + break; + default: + break; + } + } + + return ret; +} + diff --git a/drivers/seco/sio_xr28v382.c b/drivers/seco/sio_xr28v382.c new file mode 100644 index 00000000000000..4c6e1329060b32 --- /dev/null +++ b/drivers/seco/sio_xr28v382.c @@ -0,0 +1,807 @@ +#include <linux/kernel.h> +#include <linux/device.h> +#include <linux/mutex.h> +#include <linux/module.h> +#include <linux/gpio.h> +#include <linux/slab.h> +#include <linux/delay.h> +#include <asm/byteorder.h> +#include <linux/sysctl.h> +#include <linux/interrupt.h> +#include <linux/of_irq.h> +#include <linux/of_device.h> +#include <linux/of_platform.h> +#include <linux/seco_lpc.h> + +#include <linux/sio-xr28v382.h> +#include "sio_xr28v382_reg.h" + + +#define SIO_INFO(fmt, arg...) printk(KERN_INFO "XR28V382: " fmt "\n" , ## arg) +#define SIO_ERR(fmt, arg...) printk(KERN_ERR "%s: " fmt "\n" , __func__ , ## arg) +#define SIO_DBG(fmt, arg...) pr_debug("%s: " fmt "\n" , __func__ , ## arg) + +#define DRV_VERSION "1.0" + +#define XR_DEBUG 0 + + + + + + + + +// struct xr28v382_device { +// int num_devices; +// struct platform_device **pdevices; +// enum W83627DHG_P_DEVICE *devices_type; +// struct lpc_device *lpc_dev; +// }; + + +// struct xr28v382_device *xr28v382; + + + +static uint8_t reg_global_addr[] = { + REG_GBL_SREST, REG_GBL_LDN , REG_GBL_DEV_ID_M, + REG_GBL_DEV_ID_L, REG_GBL_VID_M, REG_GBL_VID_L, + REG_GBL_CLKSEL, REG_GBL_WDT +}; + + +static uint8_t reg_uartA_addr[] = { + REG_UART_EN, REG_UART_BADDR_H, REG_UART_BADDR_L, + REG_UART_IRQ_CH_SEL, REG_UART_ENH_MULTIFUN, REG_UART_IRC, + REG_UART_S_ADDR_MODE, REG_UART_S_ADDR_MODE_MASK, REG_UART_FIFO_MOD_SEL +}; + + +static uint8_t reg_uartB_addr[] = { + REG_UART_EN, REG_UART_BADDR_H, REG_UART_BADDR_L, + REG_UART_IRQ_CH_SEL, REG_UART_ENH_MULTIFUN, REG_UART_IRC, + REG_UART_S_ADDR_MODE, REG_UART_S_ADDR_MODE_MASK, REG_UART_FIFO_MOD_SEL +}; + + + + +/* __________________________________________________________________________ +* | | +* | BASIC FUNCTIONS | +* |__________________________________________________________________________| +*/ + +static inline void superio_outb (uint8_t addr, uint8_t value) { + uint16_t val16 = (uint16_t)value; + uint16_t addr16 = (uint16_t)addr; + lpc_writew (REG_EFER, addr16); + lpc_writew (REG_EFDR, val16); +} + + +static inline void superio_inb (uint8_t addr, uint8_t *data) { + uint16_t val16 = 0; + uint16_t addr16 = (uint16_t)addr; + lpc_writew (REG_EFER, addr16); + lpc_readw (REG_EFDR, &val16); + *data = (uint8_t)(val16); +} + + +int superio_readw (unsigned long addr, int offset) { + uint16_t data; + lpc_readw (((addr & 0xFFFF) >> 1) + offset, &data); + return (int)data; +} + + +void superio_writew (unsigned long addr, int offset, int value) { + lpc_writew (((addr & 0xFFFF) >> 1) + (unsigned long)offset, (int)value); +} + +static inline void superio_enter_ext_mode (void) { + lpc_writew (REG_EFER, ENTER_EXT_MODE_CODE); + lpc_writew (REG_EFER, ENTER_EXT_MODE_CODE); +} + + +static inline void superio_exit_ext_mode (void) { + lpc_writew (REG_EFER, EXIT_EXT_MODE_CODE); +} + + +static inline void superio_sw_reset (void) { + uint8_t data; + superio_inb (REG_GBL_SREST, &data); + superio_outb (REG_GBL_SREST, data | MASK_SRST); +} +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ +static uint16_t getID (uint8_t id_h, uint8_t id_l) { + uint8_t tmp = 0x0000; + uint8_t rev = 0x0000; + + superio_inb (id_h, &tmp); + superio_inb (id_l, &rev); + + return (uint16_t)(rev | tmp << 8); +} + + +static inline uint16_t getDeviceID (void) { + return getID (REG_GBL_DEV_ID_M, REG_GBL_DEV_ID_L); +} + + +static inline uint16_t getVendorID (void) { + return getID (REG_GBL_VID_M, REG_GBL_VID_L); +} + + +static inline int chipIDvalidate (uint16_t dev_id, uint16_t ven_id) { + return dev_id == ((DFL_DEV_ID_M << 8) | DFL_DEV_ID_L) && + ven_id == ((DFL_VEN_ID_M << 8) | DFL_VEN_ID_L) ? 1 : 0; +} + + +static int logicalDeviceValidate (enum XR28V382_DEVICE dev) { + int isValid = 0; + switch (dev) { + case UARTA: + case UARTB: + isValid = 1; + break; + default: + isValid = 0; + } + return isValid; +} + + +static inline int superio_select (enum XR28V382_DEVICE id) { + int ret = -1; + if (logicalDeviceValidate (id)) { + superio_outb (REG_GBL_LDN, (uint8_t)id); + ret = (int)id; + } else { + ret = -1; + } + return ret; +} + + +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ +static void superio_uart_read (uint8_t addr, uint8_t *data, uint8_t ldev_id) { + superio_enter_ext_mode (); + superio_select (ldev_id); + superio_inb (addr, data); + superio_exit_ext_mode (); +} + + +static void superio_uart_write (uint8_t addr, uint8_t value, uint8_t ldev_id) { + superio_enter_ext_mode (); + superio_select (ldev_id); + superio_outb (addr, value); + superio_exit_ext_mode (); +} + + +static void superio_global_read (uint8_t addr, uint8_t *data) { + superio_enter_ext_mode (); + superio_inb (addr, data); + superio_exit_ext_mode (); +} + + +static void superio_global_write (uint8_t addr, uint8_t value) { + superio_enter_ext_mode (); + superio_outb (addr, value); + superio_exit_ext_mode (); +} + + +static struct sio_xr28v382_ops uart_ops = { + .read = superio_uart_read, + .write = superio_uart_write, + .g_read = superio_global_read, + .g_write = superio_global_write +}; + + +static struct of_dev_auxdata sio_auxdata_lookup[] = { + OF_DEV_AUXDATA("MaxLinear,xr28v382_A_16550a", 0, "sio_uart_a_xr28v382", &uart_ops), + OF_DEV_AUXDATA("MaxLinear,xr28v382_B_16550a", 0, "sio_uart_b_xr28v382", &uart_ops), + { /* sentinel */ }, +}; + + +static int superio_xr28v382_driver_allocate (struct device *parent_dev, struct device_node *dp) { + int status; + + status = of_platform_populate (dp, NULL, sio_auxdata_lookup, parent_dev); + if ( status ) { + SIO_ERR ("failed to create device"); + } else { + SIO_INFO ("superio device created"); + } + + return status; +} + + + + + + + + + + + +// +// +////////////////////////////////////////////////////////////////// +//// UART FUNCTIONS // +////////////////////////////////////////////////////////////////// +// +// static void uart_a_irq_enable (void) { +// irq_slot_set (SLOT_UART_A, 1); +// } + + +// static void uart_a_irq_disable (void) { +// irq_slot_set (SLOT_UART_A, 0); +// } + + +// static void uart_b_irq_enable (void) { +// irq_slot_set (SLOT_UART_B, 1); +// } + + +// static void uart_b_irq_disable (void) { +// irq_slot_set (SLOT_UART_B, 0); +// } + + +// static void irq_after_handler (int irq, void *dev_id) { +// int value; +// struct plat_serial8250_port *pdata = ((struct device *)dev_id)->platform_data; +// if (pdata != NULL) { +// value = superio_readw (pdata[0].mapbase, 0x4); +// value |= 0x08; +// superio_writew (pdata[0].mapbase, 0x4, value); +// udelay (10); +// // value &= 0xF7; +// // superio_writew (pdata[0].mapbase, 0x4, value); +// } +// } + + +// static struct plat_serial8250_port xr28v382_uart_a_platform_data[] = { +// { +// .mapbase = (SUPERIO_UARTA_BASE << 1), +// .flags = UPF_BOOT_AUTOCONF | UPF_SKIP_TEST,// | UPF_IOREMAP, +// .iotype = UPIO_LPC, +// .regshift = 0, +// .uartclk = XR28V382_UART_CLOCK, +// .irq_management = NULL, // initialized by driver 8250 +// .irq_after_management = NULL, //irq_after_handler, +// .irq_data = NULL, // initialized by driver 8250 +// .irq_enable = uart_a_irq_enable, +// .irq_disable = uart_a_irq_disable, +// }, +// { +// .flags = 0, +// }, +// }; + + +// static struct plat_serial8250_port xr28v382_uart_b_platform_data[] = { +// { +// .mapbase = (SUPERIO_UARTB_BASE << 1), +// .flags = UPF_BOOT_AUTOCONF | UPF_SKIP_TEST,// | UPF_IOREMAP, +// .iotype = UPIO_LPC, +// .regshift = 0, +// .uartclk = XR28V382_UART_CLOCK, +// .irq_management = NULL, // initialized by driver 8250 +// .irq_after_management = NULL, //irq_after_handler, +// .irq_data = NULL, // initialized by driver 8250 +// .irq_enable = uart_b_irq_enable, +// .irq_disable = uart_b_irq_disable, + + +// }, +// { +// .flags = 0, +// }, +// }; + + +// static struct platform_device xr28v382_uart_a_device = { +// .name = "serial8250", +// .id = 0, +// .dev = { +// .platform_data = &xr28v382_uart_a_platform_data, +// }, +// }; + + +// static struct platform_device xr28v382_uart_b_device = { +// .name = "serial8250", +// .id = 1, +// .dev = { +// .platform_data = &xr28v382_uart_b_platform_data, +// }, +// }; + + + + +#if XR_DEBUG +static void uarta_stamp (void) { + uint16_t data; + + superio_enter_ext_mode (); + + superio_select (DEVICE_SEL_UARTA); + + superio_inb (REG_UART_EN, &data); + printk (KERN_INFO "XR28V382 REG_UART_EN %#X\n", data); + + superio_inb (REG_UART_BADDR_H, &data); + printk (KERN_INFO "XR28V382 REG_UART_BADDR_H %#X\n", data); + + superio_inb (REG_UART_BADDR_L, &data); + printk (KERN_INFO "XR28V382 REG_UART_BADDR_L %#X\n", data); + + superio_inb (REG_UART_IRQ_CH_SEL, &data); + printk (KERN_INFO "XR28V382 REG_UART_IRQ_CH_SEL %#X\n", data); + + superio_inb (REG_UART_ENH_MULTIFUN, &data); + printk (KERN_INFO "XR28V382 REG_UART_ENH_MULTIFUN %#X\n", data); + + superio_inb (REG_UART_IRC, &data); + printk (KERN_INFO "XR28V382 REG_UART_IRC %#X\n", data); + + superio_inb (REG_UART_S_ADDR_MODE, &data); + printk (KERN_INFO "XR28V382 REG_UART_S_ADDR_MODE %#X\n", data); + + superio_inb (REG_UART_S_ADDR_MODE_MASK, &data); + printk (KERN_INFO "XR28V382 REG_UART_S_ADDR_MODE_MASK %#X\n", data); + + superio_inb (REG_UART_FIFO_MOD_SEL, &data); + printk (KERN_INFO "XR28V382 REG_UART_FIFO_MOD_SEL %#X\n", data); + + superio_exit_ext_mode (); +} + + +static void uartb_stamp (void) { + uint16_t data; + + superio_enter_ext_mode (); + + superio_select (DEVICE_SEL_UARTB); + + superio_inb (REG_UART_EN, &data); + printk (KERN_INFO "XR28V382 REG_UART_EN %#X\n", data); + + superio_inb (REG_UART_BADDR_H, &data); + printk (KERN_INFO "XR28V382 REG_UART_BADDR_H %#X\n", data); + + superio_inb (REG_UART_BADDR_L, &data); + printk (KERN_INFO "XR28V382 REG_UART_BADDR_L %#X\n", data); + + superio_inb (REG_UART_IRQ_CH_SEL, &data); + printk (KERN_INFO "XR28V382 REG_UART_IRQ_CH_SEL %#X\n", data); + + superio_inb (REG_UART_ENH_MULTIFUN, &data); + printk (KERN_INFO "XR28V382 REG_UART_ENH_MULTIFUN %#X\n", data); + + superio_inb (REG_UART_IRC, &data); + printk (KERN_INFO "XR28V382 REG_UART_IRC %#X\n", data); + + superio_inb (REG_UART_S_ADDR_MODE, &data); + printk (KERN_INFO "XR28V382 REG_UART_S_ADDR_MODE %#X\n", data); + + superio_inb (REG_UART_S_ADDR_MODE_MASK, &data); + printk (KERN_INFO "XR28V382 REG_UART_S_ADDR_MODE_MASK %#X\n", data); + + superio_inb (REG_UART_FIFO_MOD_SEL, &data); + printk (KERN_INFO "XR28V382 REG_UART_FIFO_MOD_SEL %#X\n", data); + + superio_exit_ext_mode (); + +} + + + +static ssize_t uarta_state_show (struct device *dev, + struct device_attribute *attr, char *buf) { + int i; + ssize_t status; + unsigned char msg[500]; + unsigned char tmp[50]; + + uint16_t data; + uint16_t reg= (SUPERIO_UARTA_BASE << 1); + + for (i = 0 ; i < 7 ; i++) { +// superio_outb (reg, &data); + data = superio_readw (reg, i); + sprintf (tmp, "%#02X : %#02X\n", ((reg & 0xFFFF) >> 1) + i, data); + strcat (msg, tmp); + } + +// superio_inb (0x03f8, 0xC); + + status = sprintf (buf, "%s\n", msg); + return status; +} + +static ssize_t uarta_reg_store (struct device *dev, + struct device_attribute *attr, const char *buf, size_t count) { + + int rc; + unsigned long data; + + rc = strict_strtoul (buf, 0, &data); + + if (rc) + return rc; + + superio_writew ((SUPERIO_UARTA_BASE << 1), + data & 0x0000F, + (uint16_t)((data >> 4) & 0xFFFF)); + + + return rc; +} + + + + +static DEVICE_ATTR (uarta_state, 0666, uarta_state_show, uarta_reg_store); + + +static ssize_t uartb_state_show (struct device *dev, + struct device_attribute *attr, char *buf) { + int i; + ssize_t status; + unsigned char msg[500]; + unsigned char tmp[50]; + uint16_t data; + uint16_t reg= (SUPERIO_UARTB_BASE << 1); + for (i = 0 ; i < 7 ; i++) { + data = superio_readw (reg, i); + sprintf (tmp, "%#02X : %#02X\n", ((reg & 0xFFFF) >> 1) + i, data); + strcat (msg, tmp); + } + status = sprintf (buf, "%s\n", msg); + return status; +} + +static ssize_t uartb_reg_store (struct device *dev, + struct device_attribute *attr, const char *buf, size_t count) { + + int rc; + unsigned long data; + + rc = strict_strtoul (buf, 0, &data); + + if (rc) + return rc; + superio_writew ((unsigned long)(SUPERIO_UARTB_BASE << 1), + data & 0x0000F, + (int)((data >> 4) & 0xFFFF)); + + rc = count; + return rc; +} + + +static DEVICE_ATTR (uartb_state, 0666, uartb_state_show, uartb_reg_store); + + +#endif + + + + + +/* __________________________________________________________________________ +* | | +* | SYSFS INTERFACE | +* |__________________________________________________________________________| +*/ +static ssize_t sys_superio_revision (struct device *dev, struct device_attribute *attr, + char *buf) +{ + uint16_t dev_id, ven_id; + + superio_enter_ext_mode (); + dev_id = getDeviceID (); + ven_id = getVendorID (); + superio_exit_ext_mode (); + + return sprintf(buf, "vendorID: 0x%04X deviceID: 0x%04X\n",ven_id, dev_id); +} + +static DEVICE_ATTR(superio_ver, S_IRUGO, sys_superio_revision, NULL); + + + +static ssize_t sys_dump_regs (const uint8_t *reg_array, int a_size, char *buf, uint8_t ldev) { + unsigned char msg[500]; + unsigned char tmp[50]; + uint8_t value; + int i; + + superio_enter_ext_mode (); + if ( ldev < 0xD ) { + superio_select (ldev); + } + sprintf (msg, "\n#\tvalue"); + for ( i = 0 ; i < a_size ; i++ ) { + superio_inb (reg_array[i], &value); + sprintf (tmp, "\n0x%02X\t0x%02X", reg_array[i], value); + strcat (msg, tmp); + } + superio_exit_ext_mode (); + + return sprintf (buf, "%s\n", msg); +} + + +static ssize_t sys_superio_dump_global_regs (struct device *dev, struct device_attribute *attr, + char *buf) +{ + return sys_dump_regs (reg_global_addr, ARRAY_SIZE (reg_global_addr), buf, (uint8_t)-1); +} + +static DEVICE_ATTR(dump_global_regs, S_IRUGO, sys_superio_dump_global_regs, NULL); + + +static ssize_t sys_superio_dump_uartA_regs (struct device *dev, struct device_attribute *attr, + char *buf) +{ + return sys_dump_regs (reg_uartA_addr, ARRAY_SIZE (reg_uartA_addr), buf, (uint8_t)DEVICE_SEL_UARTA); +} + +static DEVICE_ATTR(dump_uartA_regs, S_IRUGO, sys_superio_dump_uartA_regs, NULL); + + +static ssize_t sys_superio_dump_uartB_regs (struct device *dev, struct device_attribute *attr, + char *buf) +{ + return sys_dump_regs (reg_uartB_addr, ARRAY_SIZE (reg_uartB_addr), buf, (uint8_t)DEVICE_SEL_UARTB); +} + +static DEVICE_ATTR(dump_uartB_regs, S_IRUGO, sys_superio_dump_uartB_regs, NULL); + + + + + +static struct attribute *superio_attrs[] = { + &dev_attr_superio_ver.attr, + &dev_attr_dump_global_regs.attr, + &dev_attr_dump_uartA_regs.attr, + &dev_attr_dump_uartB_regs.attr, + NULL, +}; + +static struct attribute_group superio_attr_group = { + .attrs = superio_attrs, +}; + +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ +static int superio_xr28v382_probe (struct platform_device *pdev) { + struct device_node *dp = pdev->dev.of_node; + uint16_t dev_id, ven_id; + int ret, err; + // struct seco_xr28v382_platform_data *pdata; + // struct lpc_device *lpc_dev; + // int i; + // enum XR28V382_DEVICE *dev_list; + + // struct device_node *dp = pdev->dev.of_node; + // int err = 0; + // uint16_t rev = 0; + + + // pdata = pdev->dev.platform_data; + // if (pdata == NULL) { + // XR_ERR ("no platform_data!"); + // return -EINVAL; + // } + + // xr28v382 = kzalloc (sizeof(struct xr28v382_device), GFP_KERNEL); + // if (xr28v382 == NULL) { + // XR_ERR ("no device data!"); + // err = -EINVAL; + // goto err_device; + // } + + /* device software restetting */ + superio_outb (REG_GBL_SREST, 0x01); + udelay (10); + + /* validate chip through device and vendor ID */ + superio_enter_ext_mode (); + + dev_id = getDeviceID (); + ven_id = getVendorID (); + + ret = chipIDvalidate (dev_id, ven_id); + if (ret == 1) { + dev_info (&pdev->dev, "EXAR chip ID: %#04X, vendor ID: %#04X\n", dev_id, ven_id); + } else { + dev_err (&pdev->dev, "SuperIO invalid chip ID: %#04X - %#04X\n", dev_id, ven_id); + superio_exit_ext_mode (); + err = -EINVAL; + goto err_rev_inval; + } + + superio_exit_ext_mode (); + + + err = sysfs_create_group (&pdev->dev.kobj, &superio_attr_group); + if ( err ) { + SIO_ERR ("cannot create sysfs interface"); + goto err_sysfs; + } + + err = superio_xr28v382_driver_allocate (&pdev->dev, dp); + if ( err ) { + SIO_ERR ("cannot allocat superIO sub-devices: %#X", err); + goto err_device_allocate; + } + + + SIO_INFO ("LPC SuperIO driver ver %s probed!!!", DRV_VERSION); + return 0; +err_device_allocate: + sysfs_remove_group(&pdev->dev.kobj, &superio_attr_group); +err_sysfs: +err_rev_inval: + return err; +} + +// /* add driver for the superio's devices */ +// if (pdata->num_devices < 1) { +// XR_INFO ("No devices associated to Winbond"); +// goto dev_err_out; +// } else { +// xr28v382->num_devices = pdata->num_devices; +// xr28v382->pdevices = kzalloc(sizeof(struct platform_device *) * pdata->num_devices, GFP_KERNEL); +// xr28v382->lpc_dev = kzalloc(sizeof(struct lpc_device) * pdata->num_devices, GFP_KERNEL); +// if (xr28v382->pdevices == NULL || xr28v382->lpc_dev == NULL) { +// XR_ERR ("Error in devices allocation"); +// } else { +// for (i = 0, dev_list = pdata->devices ; i < pdata->num_devices ; i++, dev_list++) { +// switch (*dev_list) { +// case UARTA: +// XR_INFO ("UART_A device selected"); +// xr28v382_uart_a_platform_data[0].mapbase += lpc_getMemBase(); +// xr28v382_uart_a_platform_data[0].irq = lpc_getIRQ(0); +// xr28v382_uart_a_platform_data[0].irqflags = lpc_getIRQ_flags(0) | IRQF_LPCSTYLE; +// uart_a_init (); + +// xr28v382->pdevices[i] = &xr28v382_uart_a_device; +// xr28v382->lpc_dev[i].lpc_slot = 3; +// xr28v382->lpc_dev[i].dev = &xr28v382->pdevices[i]->dev; + +// xr28v382->lpc_dev[i].handler = &xr28v382_uart_a_platform_data[0].irq_management; +// xr28v382->lpc_dev[i].after_handler = irq_after_handler; +// xr28v382->lpc_dev[i].irq_dev_id = xr28v382_uart_a_platform_data[0].irq_data; +// xr28v382->lpc_dev[i].maskable = LPC_IRQ_MASKABLE; + +// break; +// case UARTB: +// XR_INFO ("UART_B device selected"); +// xr28v382_uart_b_platform_data[0].mapbase += lpc_getMemBase(); +// xr28v382_uart_b_platform_data[0].irq = lpc_getIRQ(0); +// xr28v382_uart_b_platform_data[0].irqflags = lpc_getIRQ_flags(0) | IRQF_LPCSTYLE; +// uart_b_init (); + +// xr28v382->pdevices[i] = &xr28v382_uart_b_device; +// xr28v382->lpc_dev[i].lpc_slot = 4; +// xr28v382->lpc_dev[i].dev = &xr28v382->pdevices[i]->dev; + +// xr28v382->lpc_dev[i].handler = &xr28v382_uart_b_platform_data[0].irq_management; +// xr28v382->lpc_dev[i].after_handler = irq_after_handler; +// xr28v382->lpc_dev[i].irq_dev_id = xr28v382_uart_b_platform_data[0].irq_data; +// xr28v382->lpc_dev[i].maskable = LPC_IRQ_MASKABLE; +// break; + +// default: +// XR_ERR ("Device not supported by SuperIO"); +// } +// } +// } +// } +// superio_exit_ext_mode (); + +// /* device registration */ +// platform_add_devices (xr28v382->pdevices, xr28v382->num_devices); + +// lpc_dev = xr28v382->lpc_dev; +// for (i = 0 ; i < xr28v382->num_devices ; i++, lpc_dev++) { +// if (lpc_dev->lpc_slot >= 0) +// lpc_add_device (lpc_dev); +// } + +// #if XR_DEBUG + +// uarta_stamp (); +// uartb_stamp (); +// ret = device_create_file (&pdev->dev, &dev_attr_uarta_state); +// ret = device_create_file (&pdev->dev, &dev_attr_uartb_state); +// #endif + +// return 0; +// probe_failed: +// err_device: +// dev_err_out: +// return err; + +// } + + +static int superio_xr28v382_remove (struct platform_device *pdev) { + + platform_device_unregister (pdev); + kfree (pdev); + + return 0; +} + + +static const struct of_device_id seco_superio_match[] = { + { .compatible = "MaxLinear,xr28v382" }, + { /* sentinel */ } +}; + +MODULE_DEVICE_TABLE(of, seco_superio_match); + + +static struct platform_driver seco_xr28v382_driver = { + .driver = { + .name = "sio_xr28v382", + .owner = THIS_MODULE, + .of_match_table = seco_superio_match, + }, + .probe = superio_xr28v382_probe, + .remove = superio_xr28v382_remove, +}; + + + +static int __init seco_xr28v382_init (void) { + return platform_driver_register (&seco_xr28v382_driver); +} + +subsys_initcall (seco_xr28v382_init); + + +static void __exit seco_xr28v382_exit (void) { + return platform_driver_unregister (&seco_xr28v382_driver); +} + +module_exit (seco_xr28v382_exit); + + +MODULE_AUTHOR("DC SECO"); +MODULE_DESCRIPTION("SECO SuperIO XR28V382"); +MODULE_LICENSE("GPL"); +MODULE_VERSION(DRV_VERSION); \ No newline at end of file diff --git a/drivers/seco/sio_xr28v382_reg.h b/drivers/seco/sio_xr28v382_reg.h new file mode 100644 index 00000000000000..711a51bd297920 --- /dev/null +++ b/drivers/seco/sio_xr28v382_reg.h @@ -0,0 +1,146 @@ +#ifndef __SIO_XR28V382_DEVICE__ +#define __SIO_XR28V382_DEVICE__ + +/* GLOBAL REGISTERs */ +#define REG_GBL_SREST 0x02 /* Software Reset */ +#define REG_GBL_LDN 0x07 /* Logic Device Number Register */ +#define REG_GBL_DEV_ID_M 0x20 /* Device ID MSB Register */ +#define REG_GBL_DEV_ID_L 0x21 /* Device ID LSB Register */ +#define REG_GBL_VID_M 0x23 /* Vendor ID MSB Register */ +#define REG_GBL_VID_L 0x24 /* Vendor ID LSB Register */ +#define REG_GBL_CLKSEL 0x25 /* Clock Select Register */ +#define REG_GBL_WDT 0x26 /* Watchdog Timer Control Register */ +#define REG_GBL_PSEL 0x27 /* Port Select Register */ + + +/* UART REGISTERs */ +#define REG_UART_EN 0x30 /* UART Enable Register */ +#define REG_UART_BADDR_H 0x60 /* Base Address High Register */ +#define REG_UART_BADDR_L 0x61 /* Base Address Low Register */ +#define REG_UART_IRQ_CH_SEL 0x70 /* IRQ Channel Select Register */ +#define REG_UART_ENH_MULTIFUN 0xF0 /* Enhanced Multifunction Register */ +#define REG_UART_IRC 0xF1 /* IR Control Register */ +#define REG_UART_S_ADDR_MODE 0xF4 /* 9-bit Mode Slave Address Register */ +#define REG_UART_S_ADDR_MODE_MASK 0xF5 /* 9-bit Mode Slave Address Mask Regiser */ +#define REG_UART_FIFO_MOD_SEL 0xF6 /* FIFO Mode Select Register */ + + +/* WDT REGISTERs */ +#define REG_WDT_EN 0x30 /* Watchdog Enable Register */ +#define REG_WDT_BADDR_H 0x60 /* Base Address High Regiser */ +#define REG_WDT_BADDR_L 0x61 /* Base Address Low Register */ +#define REG_WDT_IRQ_CH_SEL 0x70 /* IRQ Channel Select Register */ +#define REG_WDT_T_STATUS_CTRL 0xF0 /* Timer Status And Control Register */ +#define REG_WDT_TMR_COUNT 0xF1 /* Timer Count Numner Register */ + + + +/* MASKs */ +#define MASK_SRST 0x01 /* Software Reset */ +#define MASK_LDN 0xFF /* Logic Device Number Register */ +#define MASK_DEV_ID 0xFF /* Device ID Registers */ +#define MASK_VID 0xFF /* Vendor ID Registers */ +#define MASK_CLKSEL 0x01 /* Clock Select Register */ +#define MASK_WDT_ASSERT 0x01 /* Watchdog Timer - Assert a low pulse from WDTOUT# pin */ +#define MASK_WDT_RST_TIME 0x02 /* Watchdog Timer - Reset timer */ +#define MASK_PSEL_SEL_CONF_KEY 0x03 /* Port Select Register - Select configuration entry key */ +#define MASK_PSEL_SEL_CONF_PORT 0x10 /* Port Select Register - Select configuration port */ +#define MASK_UART_EN 0x01 /* UART Enable Register - Enable/Disable */ +#define MASK_UART_BADDR 0xFF /* Base Address Register */ +#define MASK_UART_IRQ_SEL 0x0F /* IRQ Channel Select Register - Select IRQ channel */ +#define MASK_UART_IRQ_EN 0x10 /* IRQ Channel Select Register - Enable/Disable */ +#define MASK_UART_IRQ_SHARING_MOD 0x60 /* IRQ Channel Select Register - Sharing Mode */ +#define MASK_UART_ENH_CLK_FREQ 0x03 /* Enhanced Multifunction Register - Internal Clock frequency */ +#define MASK_UART_ENH_IR_TX_DELAY 0x04 /* Enhanced Multifunction Register - IR mode TX Delay */ +#define MASK_UART_ENH_IR_RX_DELAY 0x08 /* Enhanced Multifunction Register - IR mode RX Delay */ +#define MASK_UART_ENH_EN_AUTO_485 0x10 /* Enhanced Multifunction Register - Enable/Disable Auto RS-485 Half-Duplex Control mode */ +#define MASK_UART_ENH_INVERT_POL_485 0x20 /* Enhanced Multifunction Register - Invert the RTS#/RS485 signal polarity for RS485 Half-Duplex mode */ +#define MASK_UART_ENH_AUTO_ADDR_DETECT 0x40 /* Enhanced Multifunction Register - Auto Address Detection */ +#define MASK_UART_ENH_ENABLE_9BIT_MOD 0x80 /* Enhanced Multifunction Register - Enable/Disable the 9-bit mode */ +#define MASK_UART_IRC_IRRXA_INVERT 0x01 /* IR Control Register - IR mode IRRXA# invert */ +#define MASK_UART_IRC_IRTXA_INVERT 0x02 /* IR Control Register - IR mode IRTXA# invert */ +#define MASK_UART_IRC_HALF_DUPLEX 0x04 /* IR Control Register - IR mode Half-Duplex */ +#define MASK_UART_IRC_EN 0x18 /* IR Control Register - IR mode Enable */ +#define MASK_UART_FIFO_MOD_SEL_SIZE 0x02 /* FIFO Mode Select Register - FIFO size for TX/RX */ +#define MASK_UART_FIFO_MOD_SEL_RX_TRG_L 0x20 /* FIFO Mode Select Register - RX trigger level */ +#define MASK_UART_FIFO_MOD_SEL_TX_TRG_L 0x80 /* FIFO Mode Select Register - TX trigger level */ +#define MASK_WDT_EN 0x01 /* Timer Count Numner Register - WDT Enable/Disable */ +#define MASK_WDT_BADDR 0xFF /* Timer Count Numner Register - Base Address High/Low Regisers */ +#define MASK_WDT_IRQ_CH_SEL_WDT 0x0F /* IRQ Channel Select Register - Select the IRQ channel for watchdog timer */ +#define MASK_WDT_IRQ_CH_SEL_EN 0x10 /* IRQ Channel Select Register - Enable/Disable the watchdog time IRQ */ +#define MASK_WDT_T_STATUS_TIME_OUT_EVN 0x01 /* Timer Status And Control Register - Time Out Event */ +#define MASK_WDT_T_STATUS_WDT_INTERVAL 0x06 /* Timer Status And Control Register - WDT Interval */ +#define MASK_WDT_TMR_COUNT 0xFF /* Timer Count Numner Register */ + + + + +#define DEVICE_SEL_UARTA 0x00 +#define DEVICE_SEL_UARTB 0x01 +#define DEVICE_SEL_WDT 0x08 + +#define DFL_DEV_ID_M 0x03 +#define DFL_DEV_ID_L 0x82 + +#define DFL_VEN_ID_M 0x13 +#define DFL_VEN_ID_L 0xA8 + +#define CLK_SEL_24MHZ 0x00 +#define CLK_SEL_48MHZ 0x01 + +#define PORT_ENTRY_KEY_77 0x00 +#define PORT_ENTRY_KEY_A0 0x01 +#define PORT_ENTRY_KEY_87 0x02 +#define PORT_ENTRY_KEY_67 0x03 + +#define SEL_CONF_PORT_0 0x00 /* The configuration port is 0x2E/0x2F */ +#define SEL_CONF_PORT_1 0x01 /* The configuration port is 0x4E/0x4F */ + +#define UART_DISABLE 0x00 +#define UART_ENABLE 0x01 + +#define IRQ_SHARING_DISPLAY 0x00 +#define IRQ_SHARING_ENABLE 0x01 + +#define FIFO_TXRX_SIZE_16 0x00 +#define FIFO_TXRX_SIZE_32 0x01 +#define FIFO_TXRX_SIZE_64 0x02 +#define FIFO_TXRX_SIZE_128 0x03 + +#define RX_TRIGGER_LEVEL_X1 0x00 +#define RX_TRIGGER_LEVEL_X2 0x01 +#define RX_TRIGGER_LEVEL_X4 0x02 +#define RX_TRIGGER_LEVEL_X8 0x03 + +#define TX_HOLDING_NO_DELAY 0x00 +#define TX_HOLDING_DELAY_1TX 0x01 + +#define WDT_DISABLE 0x00 +#define WDT_ENABLE 0x01 + +#define WDT_IRQ_DISABLE 0x00 +#define WDT_IRQ_ENABLE 0x01 + +#define WDT_INTERVAL_10MSEC 0x00 +#define WDT_INTERVAL_1SEC 0x01 +#define WDT_INTERVAL_1MIN 0x02 + + +#define REG_EFER 0x2E // Extended Function Enable/Index Register +#define REG_EFDR 0x2F // Extended Function Data Register + +#define ENTER_EXT_MODE_CODE 0x67 +#define EXIT_EXT_MODE_CODE 0xAA + + +#define XR28V382_UART_CLOCK 1843200 /* frequency of 24MHz with prescaler */ +#define SUPERIO_UARTA_BASE 0x3F8 +#define SUPERIO_UARTB_BASE 0x2F8 + + + +#define SLOT_UART_A 3 +#define SLOT_UART_B 4 + + +#endif /* __SIO_XR28V382_DEVICE__ */ \ No newline at end of file diff --git a/drivers/seco/sio_xr28v382_serial.c b/drivers/seco/sio_xr28v382_serial.c new file mode 100644 index 00000000000000..8fc835ecd5d5af --- /dev/null +++ b/drivers/seco/sio_xr28v382_serial.c @@ -0,0 +1,244 @@ +#include <linux/module.h> +#include <linux/slab.h> +#include <linux/delay.h> +#include <linux/serial_core.h> +#include <linux/serial_reg.h> +#include <linux/of_address.h> +#include <linux/of_irq.h> +#include <linux/of_platform.h> +#include <linux/clk.h> +#include <linux/sio-w83627.h> +#include <linux/seco_cpld.h> +#include <linux/seco_lpc.h> + +#include <linux/sio_lpc_serial.h> +#include "sio_xr28v382_reg.h" + + + +#define sio_uart_read(sio_uart, addr, data) \ + (sio_uart)->sio_ops->read (addr, data, (sio_uart)->uart_ldev) + +#define sio_uart_write(sio_uart, addr, data) \ + (sio_uart)->sio_ops->write (addr, data, (sio_uart)->uart_ldev) + +#define sio_conf_reg(sio_uart, reg) \ + (sio_uart)->conf_reg_map[(reg)] + + + +/* __________________________________________________________________________ +* | | +* | XR28V382 UART INIT | +* |__________________________________________________________________________| +*/ +static void xr28v382_uart_A_init (struct lpc_serial_port *info) { + uint16_t data; + uint16_t addr; + + sio_uart_write (info, REG_UART_BADDR_H, (info->membase >> 8) & 0xFF ); + sio_uart_write (info, REG_UART_BADDR_L, info->membase & 0xFF ); + + sio_uart_write (info, REG_UART_FIFO_MOD_SEL, RX_TRIGGER_LEVEL_X1 | + FIFO_TXRX_SIZE_16 | + TX_HOLDING_NO_DELAY); + + + addr = (uint16_t)(info->membase ) & 0xFFFF; + lpc_readw (addr + 3, &data); + data |= 0x80; + lpc_writew (addr + 3, data); + + lpc_writew (addr + 0, 0x01); + lpc_writew (addr + 1, 0x00); + + data &= 0x7F; + lpc_writew (addr + 3, data); + + /* Enable UARTA */ + sio_uart_write (info, REG_UART_EN, UART_ENABLE); +} + + +static void xr28v382_uart_B_init (struct lpc_serial_port *info) { + uint16_t data; + uint16_t addr; + + sio_uart_write (info, REG_UART_BADDR_H, (info->membase >> 8) & 0xFF ); + sio_uart_write (info, REG_UART_BADDR_L, info->membase & 0xFF ); + + sio_uart_write (info, REG_UART_FIFO_MOD_SEL, RX_TRIGGER_LEVEL_X1 | + FIFO_TXRX_SIZE_16 | + TX_HOLDING_NO_DELAY); + + + addr = (uint16_t)(info->membase ) & 0xFFFF; + lpc_readw (addr + 3, &data); + data |= 0x80; + lpc_writew (addr + 3, data); + + lpc_writew (addr + 0, 0x01); + lpc_writew (addr + 1, 0x00); + + data &= 0x7F; + lpc_writew (addr + 3, data); + + /* Enable UARTB */ + sio_uart_write (info, REG_UART_EN, UART_ENABLE); +} + + +/* __________________________________________________________________________ +* | | +* | XR28V382 UART COMMUNICATION | +* |__________________________________________________________________________| +*/ +unsigned int xr28v382_serial_in (struct uart_port *port, int offset) { + uint16_t data; + uint16_t addr = (uint16_t)(port->mapbase ) & 0xFFFF; + lpc_readw (addr + offset, &data); + return (int)data; +} + + +void xr28v382_serial_out (struct uart_port *port, int offset, int value) { + uint16_t addr = (uint16_t)(port->mapbase ) & 0xFFFF; + lpc_writew (addr + offset, value); +} +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + +/* __________________________________________________________________________ +* | | +* | SYSFS INTERFACE | +* |__________________________________________________________________________| +*/ +static ssize_t sys_xr28v382_dump_uart_regs (struct device *dev, struct device_attribute *attr, + char *buf) +{ + struct lpc_serial_port *info = (struct lpc_serial_port *)dev_get_drvdata (dev); + unsigned char msg[500]; + unsigned char tmp[50]; + uint8_t value; + int i; + + sprintf (msg, "\n#\tvalue"); + for ( i = 0 ; i <= 7 ; i++) { + value = (uint16_t)xr28v382_serial_in (&info->port, i); + sprintf (tmp, "\n0x%02X\t0x%02X", i, value); + strcat (msg, tmp); + } + + return sprintf (buf, "%s\n", msg); +} + + +static ssize_t sys_xr28v382_store_uart_regs (struct device *dev, struct device_attribute *attr, + const char *buf, size_t count) +{ + struct lpc_serial_port *info = (struct lpc_serial_port *)dev_get_drvdata (dev); + uint8_t reg, value; + unsigned long val; + char *start = (char *)buf; + + while (*start == ' ') + start++; + + reg = (uint8_t)simple_strtoul (start, &start, 16); + + if ( reg < 0 || reg > 7 ) { + return -EINVAL; + } + + while (*start == ' ') + start++; + + if ( kstrtoul (start, 16, &val) ) { + return -EINVAL; + } + + value = (uint8_t)val; + + xr28v382_serial_out (&info->port, reg, value); + + return count; +} + + +static DEVICE_ATTR(dump_uart_regs, 0664, sys_xr28v382_dump_uart_regs, sys_xr28v382_store_uart_regs); + + +static ssize_t sys_xr28v382_payload_size_show (struct device *dev, struct device_attribute *attr, + char *buf) +{ + struct lpc_serial_port *info = (struct lpc_serial_port *)dev_get_drvdata (dev); + + return sprintf (buf, "%d\n", info->payload_size); +} + + +static DEVICE_ATTR(payload_size, 0444, sys_xr28v382_payload_size_show, NULL); + + +static struct attribute *xr28v382_uart_attrs[] = { + &dev_attr_dump_uart_regs.attr, + &dev_attr_payload_size.attr, + NULL, +}; + + +static struct attribute_group xr28v382_uart_attr_group = { + .attrs = xr28v382_uart_attrs, +}; + +int lpc_xr28v382_sys_serial_setup (struct platform_device *pdev, struct lpc_serial_port *info) { +int err = 0; + switch ( info->uart_index ) { + case LPC_UART_TYPE_XR28V382_A: + case LPC_UART_TYPE_XR28V382_B: + err = sysfs_create_group (&pdev->dev.kobj, &xr28v382_uart_attr_group); + break; + default: + break; + } + return err; +} + +/* __________________________________________________________________________ +* |__________________________________________________________________________| +*/ + + +int lpc_xr28v382_platform_serial_setup (struct platform_device *pdev, + // int type, struct uart_port *port, + struct lpc_serial_port *info) +{ + int ret = 0; + + switch ( info->uart_index ) { + case LPC_UART_TYPE_XR28V382_A: + xr28v382_uart_A_init (info); + break; + case LPC_UART_TYPE_XR28V382_B: + xr28v382_uart_B_init (info); + break; + default: + ret = -1; + } + + if ( !ret) { + switch ( info->uart_index ) { + case LPC_UART_TYPE_XR28V382_A: + case LPC_UART_TYPE_XR28V382_B: + info->serial_in = xr28v382_serial_in; + info->serial_out = xr28v382_serial_out; + info->type = LPC_PORT_TYPE_XR28V382; + break; + default: + break; + } + } + + return ret; +} \ No newline at end of file diff --git a/drivers/tty/serial/serial_core.c b/drivers/tty/serial/serial_core.c index 68a0ff6054761a..81a98a18dd9409 100644 --- a/drivers/tty/serial/serial_core.c +++ b/drivers/tty/serial/serial_core.c @@ -2333,6 +2333,10 @@ uart_report_port(struct uart_driver *drv, struct uart_port *port) snprintf(address, sizeof(address), "MMIO 0x%llx", (unsigned long long)port->mapbase); break; + case UPIO_LPC: + snprintf(address, sizeof(address), + "LPC 0x%llx", (unsigned long long)port->mapbase); + break; default: strlcpy(address, "*unknown*", sizeof(address)); break; diff --git a/include/linux/seco_cpld.h b/include/linux/seco_cpld.h new file mode 100644 index 00000000000000..70a816db895f2b --- /dev/null +++ b/include/linux/seco_cpld.h @@ -0,0 +1,61 @@ +#ifndef __LINUX_SECO_CPLD_H +#define __LINUX_SEC0_CPLD_H + +#include <linux/of.h> +#include <linux/device.h> + +#define NREG 11 +#define CPLD_OFFSET_BASE 0xF000 + +#define CPLD_REG_0 (uint8_t)0x0 +#define CPLD_REG_1 (uint8_t)0x1 +#define CPLD_REG_2 (uint8_t)0x2 +#define CPLD_REG_3 (uint8_t)0x3 +#define CPLD_REG_4 (uint8_t)0x4 +#define CPLD_REG_5 (uint8_t)0x5 +#define CPLD_REG_6 (uint8_t)0x6 +#define CPLD_REG_7 (uint8_t)0x7 +#define CPLD_REG_8 (uint8_t)0x8 +#define CPLD_REG_9 (uint8_t)0x9 +#define CPLD_REG_10 (uint8_t)0xa + +#define REG_REVISION CPLD_REG_0 + + +struct cpld_data { + const char *name; + resource_size_t mem_addr_base; + unsigned long long mem_size; + void __iomem *virt; + struct mutex bus_lock; +}; + +#define CPLD_NAME_SIZE 50 + +struct cpld_client { + char name[CPLD_NAME_SIZE]; + struct device dev; +}; + +extern void cpld_reg_read (unsigned int addr, uint16_t *data); + +extern void cpld_reg_write (unsigned int addr, uint16_t value); + +extern void cpld_read (unsigned int addr, uint16_t *data); + +extern void cpld_write (unsigned int addr, uint16_t value); + +extern int cpld_get_membase (void); + +extern int __cpld_init (struct device_node *dp, struct resource *resource); + +extern int cpld_get_revision (void); + +extern int cpld_is_gpio (void); + +extern int cpld_is_lpc (void); + +//extern void cpld_remove (void); + +extern void dump_reg (void); +#endif /* __LINUX_SECO_CPLD_H */ diff --git a/include/linux/seco_lpc.h b/include/linux/seco_lpc.h new file mode 100644 index 00000000000000..d346f7bbc2f6c7 --- /dev/null +++ b/include/linux/seco_lpc.h @@ -0,0 +1,32 @@ +#ifndef __LINUX_SECO_LPC_BRIDGE_H +#define __LINUX_SEC0_LPC_BRIDGE_H + +#include <linux/of.h> +#include <linux/device.h> + +struct lpc_device { + int lpc_slot; + struct device *dev; + irqreturn_t (**handler)(int irq, void *dev_id); + void (*after_handler)(int irq, void *dev_id); + void **irq_dev_id; + int maskable; +}; + + +extern int lpc_readw (unsigned long mem_addr, uint16_t *data); + +extern int lpc_writew (unsigned long mem_addr, uint16_t value); + +extern unsigned long lpc_getIRQ_flags (int irq); + +extern int lpc_getIRQ (int irq); + +extern unsigned long lpc_getMemBase (void); + +extern int lpc_add_device (struct lpc_device *lpc_dev); + +extern void irq_slot_set (int slot, int en); + + +#endif /* __LINUX_SECO_LPC_BRIDGE_H */ diff --git a/include/linux/serial_core.h b/include/linux/serial_core.h index ff63c2963359d2..2d0607d890a112 100644 --- a/include/linux/serial_core.h +++ b/include/linux/serial_core.h @@ -152,6 +152,7 @@ struct uart_port { #define UPIO_TSI (SERIAL_IO_TSI) /* Tsi108/109 type IO */ #define UPIO_MEM32BE (SERIAL_IO_MEM32BE) /* 32b big endian */ #define UPIO_MEM16 (SERIAL_IO_MEM16) /* 16b little endian */ +#define UPIO_LPC (SERIAL_IO_LPC) /* SECO LPC serial */ /* quirks must be updated while holding port mutex */ #define UPQ_NO_TXEN_TEST BIT(0) diff --git a/include/linux/sio-w83627.h b/include/linux/sio-w83627.h new file mode 100644 index 00000000000000..bfab6a6825dec8 --- /dev/null +++ b/include/linux/sio-w83627.h @@ -0,0 +1,20 @@ +#ifndef __LINUX_SIO_W83627_H__ +#define __LINUX_SIO_W83627_H__ + + +enum W83627_DEVICE { + FDC, PARALLEL_PORT, UARTA, UARTB, NONE, KEYBOARD_CRTL, + SPI, GPIO6, WDTO_PLED, GPIO2, GPIO3, GPIO4, GPIO5, ACPI, HWMON, PECI_SST +}; + + +struct sio_w83627_ops { + void (*read) (uint8_t addr, uint8_t *data, uint8_t ldev_id); + void (*write) (uint8_t addr, uint8_t value, uint8_t ldev_id); + void (*g_read) (uint8_t addr, uint8_t *data); + void (*g_write) (uint8_t addr, uint8_t value); + +}; + + +#endif /* __LINUX_SIO_W83627_H__ */ diff --git a/include/linux/sio-xr28v382.h b/include/linux/sio-xr28v382.h new file mode 100644 index 00000000000000..bcb4af58efeae1 --- /dev/null +++ b/include/linux/sio-xr28v382.h @@ -0,0 +1,19 @@ +#ifndef __LINUX_SIO_XR28V382_H__ +#define __LINUX_SIO_XR28V382_H__ + + +enum XR28V382_DEVICE { + UARTA, UARTB +}; + + +struct sio_xr28v382_ops { + void (*read) (uint8_t addr, uint8_t *data, uint8_t ldev_id); + void (*write) (uint8_t addr, uint8_t value, uint8_t ldev_id); + void (*g_read) (uint8_t addr, uint8_t *data); + void (*g_write) (uint8_t addr, uint8_t value); + +}; + + +#endif /* __LINUX_SIO_XR28V382_H__ */ diff --git a/include/linux/sio_lpc_serial.h b/include/linux/sio_lpc_serial.h new file mode 100644 index 00000000000000..fcc51cda89f1de --- /dev/null +++ b/include/linux/sio_lpc_serial.h @@ -0,0 +1,68 @@ +#ifndef _LINUX_SIO_LPC_SERIAL_H_ +#define _LINUX_SIO_LPC_SERIAL_H_ + + +#include <linux/serial_core.h> +#include <linux/serial.h> +#include <linux/sio-w83627.h> + + +struct lpc_serial_port { + struct uart_port port; + int type; + struct sio_w83627_ops *sio_ops; + int uart_ldev; + int uart_index; + int uart_reg[8]; + int payload_size; + unsigned char rx_lsr; + int boudrate; + int is_rs485; + int is_half_duplex; + int tx_mode; + + struct tasklet_struct tasklet; + struct delayed_work work_tx; + struct delayed_work work_rx; + + struct clk *clk; + int line; + unsigned int memoffset; + int membase; + unsigned int uart_clk; + int port_type; + +// struct uart_8250_port port8250; + + unsigned int (*serial_in)(struct uart_port *, int); + void (*serial_out)(struct uart_port *, int, int); + +}; + + + +struct serial_data { + int uart_index; + int port_type; +}; + + +#define LPC_UART_TYPE_W83627_A 0 +#define LPC_UART_TYPE_W83627_B 1 +#define LPC_UART_TYPE_XR28V382_A 0 +#define LPC_UART_TYPE_XR28V382_B 1 + + +#define LPC_PORT_TYPE_W83627 0 +#define LPC_PORT_TYPE_XR28V382 1 + + +extern int lpc_w83627_platform_serial_setup (struct platform_device *pdev, struct lpc_serial_port *info); +extern int lpc_xr28v382_platform_serial_setup (struct platform_device *pdev, struct lpc_serial_port *info); + +extern int lpc_w83627_sys_serial_setup (struct platform_device *pdev, struct lpc_serial_port *info); +extern int lpc_xr28v382_sys_serial_setup (struct platform_device *pdev, struct lpc_serial_port *info); + + + +#endif /* _LINUX_SIO_LPC_SERIAL_H_ */ diff --git a/include/uapi/linux/serial.h b/include/uapi/linux/serial.h index 93eb3c496ff1e8..384d3ad6472b88 100644 --- a/include/uapi/linux/serial.h +++ b/include/uapi/linux/serial.h @@ -71,6 +71,7 @@ struct serial_struct { #define SERIAL_IO_TSI 5 #define SERIAL_IO_MEM32BE 6 #define SERIAL_IO_MEM16 7 +#define SERIAL_IO_LPC 8 #define UART_CLEAR_FIFO 0x01 #define UART_USE_FIFO 0x02 diff --git a/include/uapi/linux/serial_core.h b/include/uapi/linux/serial_core.h index 851b982f8c4b82..eb287945ba4a11 100644 --- a/include/uapi/linux/serial_core.h +++ b/include/uapi/linux/serial_core.h @@ -43,6 +43,8 @@ #define PORT_ALTR_16550_F128 28 /* Altera 16550 UART with 128 FIFOs */ #define PORT_RT2880 29 /* Ralink RT2880 internal UART */ #define PORT_16550A_FSL64 30 /* Freescale 16550 UART with 64 FIFOs */ +#define PORT_LPC 123 /* SECO LPC UART */ + /* * ARM specific type numbers. These are not currently guaranteed -- GitLab