Page Menu
Home
FreeBSD
Search
Configure Global Search
Log In
Files
F131878291
D36559.diff
No One
Temporary
Actions
View File
Edit File
Delete File
View Transforms
Subscribe
Mute Notifications
Flag For Later
Award Token
Size
40 KB
Referenced Files
None
Subscribers
None
D36559.diff
View Options
diff --git a/sys/arm64/conf/std.marvell b/sys/arm64/conf/std.marvell
--- a/sys/arm64/conf/std.marvell
+++ b/sys/arm64/conf/std.marvell
@@ -12,6 +12,7 @@
# I2C
device a37x0_iic # Armada 37x0 I2C controller
+device tca64xx # I2C gpio expander
device twsi # Allwinner/Marvell I2C controller
# Interrupt controllers
diff --git a/sys/arm64/conf/std.nxp b/sys/arm64/conf/std.nxp
--- a/sys/arm64/conf/std.nxp
+++ b/sys/arm64/conf/std.nxp
@@ -8,7 +8,7 @@
# I2C
device pca954x # NPX I2C bus multiplexer / switches
device pcf8563 # NXP Real-time clock/calendar
-device tca6408 # NXP I2C gpio expander
+device tca64xx # NXP I2C gpio expander
device pcf85063 # NXP Real-time clock
# Serial (COM) ports
diff --git a/sys/conf/files b/sys/conf/files
--- a/sys/conf/files
+++ b/sys/conf/files
@@ -1878,8 +1878,7 @@
dev/iicbus/s35390a.c optional s35390a
dev/iicbus/sy8106a.c optional sy8106a fdt
dev/iicbus/syr827.c optional syr827 fdt
-dev/iicbus/gpio/tca6408.c optional tca6408 fdt gpio
-dev/iicbus/gpio/tca6416.c optional tca6416 fdt
+dev/iicbus/gpio/tca64xx.c optional tca64xx fdt gpio
dev/iicbus/pmic/fan53555.c optional fan53555 fdt
dev/igc/if_igc.c optional igc iflib pci
dev/igc/igc_api.c optional igc iflib pci
diff --git a/sys/dev/iicbus/gpio/tca6408.c b/sys/dev/iicbus/gpio/tca6408.c
deleted file mode 100644
--- a/sys/dev/iicbus/gpio/tca6408.c
+++ /dev/null
@@ -1,375 +0,0 @@
-/*-
- * SPDX-License-Identifier: BSD-2-Clause-FreeBSD
- *
- * Copyright (c) 2021 Alstom Group.
- * Copyright (c) 2021 Semihalf.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- *
- * THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND
- * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE
- * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
- * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
- * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
- * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
- * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
- * SUCH DAMAGE.
- */
-
-#include <sys/cdefs.h>
-__FBSDID("$FreeBSD$");
-
-#include "opt_platform.h"
-
-#include <sys/param.h>
-#include <sys/bus.h>
-#include <sys/gpio.h>
-#include <sys/kernel.h>
-#include <sys/module.h>
-
-#include <dev/ofw/ofw_bus.h>
-
-#include <dev/iicbus/iicbus.h>
-#include <dev/iicbus/iiconf.h>
-
-#include <dev/gpio/gpiobusvar.h>
-
-#define BIT(x) (1UL << (x))
-
-#define TCA6408_READ_REG 0x0
-#define TCA6408_WRITE_REG 0x1
-#define TCA6408_POLARITY_REG 0x2
-#define TCA6408_CONFIG_REG 0x3
-
-#define PINS_NUM 8
-
-#define PIN_CAPS (GPIO_PIN_INPUT | GPIO_PIN_OUTPUT \
- | GPIO_PIN_INVIN)
-
-struct tca6408_softc {
- device_t dev;
- device_t bus_dev;
- struct mtx mtx;
-};
-
-static int tca6408_read1(device_t dev, uint8_t offset, uint8_t *data);
-static int tca6408_write1(device_t dev, uint8_t offset, uint8_t data);
-static int tca6408_probe(device_t dev);
-static int tca6408_attach(device_t dev);
-static int tca6408_detach(device_t dev);
-static device_t tca6408_get_bus(device_t dev);
-static int tca6408_pin_max(device_t dev, int *pin);
-static int tca6408_pin_getflags(device_t dev, uint32_t pin, uint32_t *flags);
-static int tca6408_pin_setflags(device_t dev, uint32_t pin, uint32_t flags);
-static int tca6408_pin_getname(device_t dev, uint32_t pin, char *name);
-static int tca6408_pin_get(device_t dev, uint32_t pin, unsigned int *val);
-static int tca6408_pin_set(device_t dev, uint32_t pin, unsigned int val);
-static int tca6408_pin_toggle(device_t dev, uint32_t pin);
-static int tca6408_pin_getcaps(device_t dev, uint32_t pin, uint32_t *caps);
-
-static device_method_t tca6408_methods[] = {
- DEVMETHOD(device_probe, tca6408_probe),
- DEVMETHOD(device_attach, tca6408_attach),
- DEVMETHOD(device_detach, tca6408_detach),
-
- DEVMETHOD(gpio_get_bus, tca6408_get_bus),
- DEVMETHOD(gpio_pin_max, tca6408_pin_max),
- DEVMETHOD(gpio_pin_getflags, tca6408_pin_getflags),
- DEVMETHOD(gpio_pin_setflags, tca6408_pin_setflags),
- DEVMETHOD(gpio_pin_getname, tca6408_pin_getname),
- DEVMETHOD(gpio_pin_get, tca6408_pin_get),
- DEVMETHOD(gpio_pin_set, tca6408_pin_set),
- DEVMETHOD(gpio_pin_toggle, tca6408_pin_toggle),
- DEVMETHOD(gpio_pin_getcaps, tca6408_pin_getcaps),
-
- DEVMETHOD_END
-};
-
-static driver_t tca6408_driver = {
- "gpio",
- tca6408_methods,
- sizeof(struct tca6408_softc)
-};
-
-static struct ofw_compat_data tca6408_compat_data[] = {
- { "ti,tca6408", 1 },
- { NULL, 0}
-};
-
-DRIVER_MODULE(tca6408, iicbus, tca6408_driver, 0, 0);
-IICBUS_FDT_PNP_INFO(tca6408_compat_data);
-
-static int
-tca6408_read1(device_t dev, uint8_t offset, uint8_t *data)
-{
- int error;
-
- error = iicdev_readfrom(dev, offset, (void *) data, 1, IIC_WAIT);
- if (error != 0)
- device_printf(dev, "Failed to read from device\n");
-
- return (error);
-}
-
-static int
-tca6408_write1(device_t dev, uint8_t offset, uint8_t data)
-{
- int error;
-
- error = iicdev_writeto(dev, offset, (void *) &data, 1, IIC_WAIT);
- if (error != 0)
- device_printf(dev, "Failed to write to device\n");
-
- return (error);
-}
-
-static int
-tca6408_probe(device_t dev)
-{
-
- if (!ofw_bus_status_okay(dev))
- return (ENXIO);
-
- if (!ofw_bus_search_compatible(dev, tca6408_compat_data)->ocd_data)
- return (ENXIO);
-
- device_set_desc(dev, "TCA6408 GPIO expander");
-
- return (BUS_PROBE_DEFAULT);
-}
-
-static int
-tca6408_attach(device_t dev)
-{
- struct tca6408_softc *sc;
-
- sc = device_get_softc(dev);
- sc->dev = dev;
-
- mtx_init(&sc->mtx, "tca6408 gpio", "gpio", MTX_DEF);
-
- sc->bus_dev = gpiobus_attach_bus(dev);
- if (sc->bus_dev == NULL) {
- device_printf(dev, "Could not create busdev child\n");
- return (ENXIO);
- }
-
- OF_device_register_xref(OF_xref_from_node(ofw_bus_get_node(dev)), dev);
-
- return (0);
-}
-
-static int
-tca6408_detach(device_t dev)
-{
- struct tca6408_softc *sc;
-
- sc = device_get_softc(dev);
-
- if (sc->bus_dev != NULL)
- gpiobus_detach_bus(sc->bus_dev);
-
- mtx_destroy(&sc->mtx);
-
- return (0);
-}
-
-static device_t
-tca6408_get_bus(device_t dev)
-{
- struct tca6408_softc *sc;
-
- sc = device_get_softc(dev);
-
- return (sc->bus_dev);
-}
-
-static int
-tca6408_pin_max(device_t dev, int *pin)
-{
-
- if (pin == NULL)
- return (EINVAL);
-
- *pin = PINS_NUM - 1;
-
- return (0);
-}
-
-static int
-tca6408_pin_getflags(device_t dev, uint32_t pin, uint32_t *flags)
-{
- uint8_t buffer;
- int error;
-
- if (pin >= PINS_NUM || flags == NULL)
- return (EINVAL);
-
- error = tca6408_read1(dev, TCA6408_CONFIG_REG, &buffer);
- if (error != 0)
- return (error);
-
- *flags = (buffer & BIT(pin)) ? GPIO_PIN_INPUT : GPIO_PIN_OUTPUT;
-
- error = tca6408_read1(dev, TCA6408_POLARITY_REG, &buffer);
- if (error != 0)
- return (error);
-
- if (buffer & BIT(pin))
- *flags |= ((*flags & GPIO_PIN_INPUT)
- ? GPIO_PIN_INVIN : GPIO_PIN_INVOUT);
-
- return (0);
-}
-
-static int
-tca6408_pin_setflags(device_t dev, uint32_t pin, unsigned int flags)
-{
- uint8_t config_buf, inv_buf;
- struct tca6408_softc *sc;
- int error;
-
- if (pin >= PINS_NUM)
- return (EINVAL);
-
- sc = device_get_softc(dev);
- mtx_lock(&sc->mtx);
-
- error = tca6408_read1(dev, TCA6408_CONFIG_REG, &config_buf);
- if (error != 0)
- goto fail;
-
- error = tca6408_read1(dev, TCA6408_POLARITY_REG, &inv_buf);
- if (error != 0)
- goto fail;
-
- if (flags & GPIO_PIN_INPUT)
- config_buf |= BIT(pin);
- else if (flags & GPIO_PIN_OUTPUT)
- config_buf &= ~BIT(pin);
-
- if (flags & GPIO_PIN_INVIN)
- inv_buf |= BIT(pin);
- else if (flags & GPIO_PIN_INVOUT)
- inv_buf &= ~BIT(pin);
-
- error = tca6408_write1(dev, TCA6408_CONFIG_REG, config_buf);
- if (error != 0)
- goto fail;
-
- error = tca6408_write1(dev, TCA6408_POLARITY_REG, inv_buf);
-
-fail:
- mtx_unlock(&sc->mtx);
-
- return (error);
-}
-
-static int
-tca6408_pin_getname(device_t dev, uint32_t pin, char *name)
-{
-
- if (pin >= PINS_NUM)
- return (EINVAL);
-
- snprintf(name, GPIOMAXNAME, "tca6408_gpio_pin%d\n", pin);
-
- return (0);
-}
-
-static int
-tca6408_pin_get(device_t dev, uint32_t pin, unsigned int *val)
-{
- uint8_t buffer;
- int error;
-
- if (pin >= PINS_NUM || val == NULL)
- return (EINVAL);
-
- error = tca6408_read1(dev, TCA6408_READ_REG, &buffer);
- if (error != 0)
- return (error);
-
- *val = buffer & BIT(pin);
-
- return (0);
-}
-
-static int
-tca6408_pin_set(device_t dev, uint32_t pin, uint32_t val)
-{
- struct tca6408_softc *sc;
- uint8_t buffer;
- int error;
-
- if (pin >= PINS_NUM)
- return (EINVAL);
-
- sc = device_get_softc(dev);
- mtx_lock(&sc->mtx);
-
- error = tca6408_read1(dev, TCA6408_WRITE_REG, &buffer);
- if (error != 0)
- goto fail;
-
- if (val != 0)
- buffer |= BIT(pin);
- else
- buffer &= ~BIT(pin);
-
- error = tca6408_write1(dev, TCA6408_WRITE_REG, buffer);
-
-fail:
- mtx_unlock(&sc->mtx);
-
- return (error);
-}
-
-static int
-tca6408_pin_toggle(device_t dev, uint32_t pin)
-{
- struct tca6408_softc *sc;
- uint8_t buffer;
- int error;
-
- if (pin >= PINS_NUM)
- return (EINVAL);
-
- sc = device_get_softc(dev);
- mtx_lock(&sc->mtx);
-
- error = tca6408_read1(dev, TCA6408_WRITE_REG, &buffer);
- if (error)
- goto fail;
-
- buffer ^= BIT(pin);
- error = tca6408_write1(dev, TCA6408_WRITE_REG, buffer);
-
-fail:
- mtx_unlock(&sc->mtx);
-
- return (error);
-}
-
-static int
-tca6408_pin_getcaps(device_t dev, uint32_t pin, uint32_t *caps)
-{
-
- if (pin >= PINS_NUM)
- return (EINVAL);
-
- *caps = PIN_CAPS;
-
- return (0);
-}
-
diff --git a/sys/dev/iicbus/gpio/tca6416.c b/sys/dev/iicbus/gpio/tca6416.c
deleted file mode 100644
--- a/sys/dev/iicbus/gpio/tca6416.c
+++ /dev/null
@@ -1,524 +0,0 @@
-/*-
- * SPDX-License-Identifier: BSD-2-Clause-FreeBSD
- *
- * Copyright (c) 2020 Alstom Group.
- * Copyright (c) 2020 Semihalf.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- *
- * THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND
- * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE
- * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
- * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
- * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
- * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
- * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
- * SUCH DAMAGE.
- */
-
-/*
- * Driver for TI TCA6416 I2C GPIO expander module.
- *
- * This driver only supports basic functionality
- * (interrupt handling and polarity inversion were omitted).
- */
-
-#include <sys/cdefs.h>
-__FBSDID("$FreeBSD$");
-
-#include <sys/param.h>
-#include <sys/bus.h>
-#include <sys/gpio.h>
-#include <sys/kernel.h>
-#include <sys/module.h>
-#include <sys/proc.h>
-#include <sys/systm.h>
-#include <sys/sysctl.h>
-
-#include <machine/bus.h>
-
-#include <dev/ofw/openfirm.h>
-#include <dev/ofw/ofw_bus.h>
-#include <dev/ofw/ofw_bus_subr.h>
-
-#include <dev/iicbus/iicbus.h>
-#include <dev/iicbus/iiconf.h>
-
-#include <dev/gpio/gpiobusvar.h>
-
-#include "gpio_if.h"
-
-/* Base addresses of registers. LSB omitted. */
-#define IN_PORT_REG 0x00
-#define OUT_PORT_REG 0x02
-#define POLARITY_INV_REG 0x04
-#define CONF_REG 0x06
-
-#define NUM_PINS 16
-#define PINS_PER_REG 8
-#define PIN_CAPS \
- (GPIO_PIN_OUTPUT | GPIO_PIN_INPUT \
- | GPIO_PIN_PUSHPULL | GPIO_PIN_INVIN)
-
-#ifdef DEBUG
-#define dbg_dev_printf(dev, fmt, args...) \
- device_printf(dev, fmt, ##args)
-#else
-#define dbg_dev_printf(dev, fmt, args...)
-#endif
-
-#define TCA6416_BIT_FROM_PIN(pin) (pin % PINS_PER_REG)
-#define TCA6416_REG_ADDR(pin, baseaddr) (baseaddr | (pin / PINS_PER_REG))
-
-struct tca6416_softc {
- device_t dev;
- device_t busdev;
- struct mtx mtx;
- uint32_t addr;
-};
-
-static int tca6416_read(device_t, uint8_t, uint8_t*);
-static int tca6416_write(device_t, uint8_t, uint8_t);
-static int tca6416_probe(device_t);
-static int tca6416_attach(device_t);
-static int tca6416_detach(device_t);
-static device_t tca6416_get_bus(device_t);
-static int tca6416_pin_max(device_t, int*);
-static int tca6416_pin_getcaps(device_t, uint32_t, uint32_t*);
-static int tca6416_pin_getflags(device_t, uint32_t, uint32_t*);
-static int tca6416_pin_setflags(device_t, uint32_t, uint32_t);
-static int tca6416_pin_getname(device_t, uint32_t, char*);
-static int tca6416_pin_get(device_t, uint32_t, unsigned int*);
-static int tca6416_pin_set(device_t, uint32_t, unsigned int);
-static int tca6416_pin_toggle(device_t, uint32_t);
-#ifdef DEBUG
-static void tca6416_regdump_setup(device_t dev);
-static int tca6416_regdump_sysctl(SYSCTL_HANDLER_ARGS);
-#endif
-
-static device_method_t tca6416_methods[] = {
- DEVMETHOD(device_probe, tca6416_probe),
- DEVMETHOD(device_attach, tca6416_attach),
- DEVMETHOD(device_detach, tca6416_detach),
-
- /* GPIO methods */
- DEVMETHOD(gpio_get_bus, tca6416_get_bus),
- DEVMETHOD(gpio_pin_max, tca6416_pin_max),
- DEVMETHOD(gpio_pin_getcaps, tca6416_pin_getcaps),
- DEVMETHOD(gpio_pin_getflags, tca6416_pin_getflags),
- DEVMETHOD(gpio_pin_setflags, tca6416_pin_setflags),
- DEVMETHOD(gpio_pin_getname, tca6416_pin_getname),
- DEVMETHOD(gpio_pin_get, tca6416_pin_get),
- DEVMETHOD(gpio_pin_set, tca6416_pin_set),
- DEVMETHOD(gpio_pin_toggle, tca6416_pin_toggle),
-
- DEVMETHOD_END
-};
-
-static driver_t tca6416_driver = {
- "gpio",
- tca6416_methods,
- sizeof(struct tca6416_softc)
-};
-
-DRIVER_MODULE(tca6416, iicbus, tca6416_driver, 0, 0);
-MODULE_VERSION(tca6416, 1);
-
-static struct ofw_compat_data compat_data[] = {
- {"ti,tca6416", 1},
- {"ti,tca9539", 1},
- {0,0}
-};
-
-static int
-tca6416_read(device_t dev, uint8_t reg, uint8_t *data)
-{
- struct iic_msg msgs[2];
- struct tca6416_softc *sc;
- int error;
-
- sc = device_get_softc(dev);
- if (data == NULL)
- return (EINVAL);
-
- msgs[0].slave = sc->addr;
- msgs[0].flags = IIC_M_WR | IIC_M_NOSTOP;
- msgs[0].len = 1;
- msgs[0].buf = ®
-
- msgs[1].slave = sc->addr;
- msgs[1].flags = IIC_M_RD;
- msgs[1].len = 1;
- msgs[1].buf = data;
-
- error = iicbus_transfer_excl(dev, msgs, 2, IIC_WAIT);
- return (iic2errno(error));
-}
-
-static int
-tca6416_write(device_t dev, uint8_t reg, uint8_t val)
-{
- struct iic_msg msg;
- struct tca6416_softc *sc;
- int error;
- uint8_t buffer[2] = {reg, val};
-
- sc = device_get_softc(dev);
-
- msg.slave = sc->addr;
- msg.flags = IIC_M_WR;
- msg.len = 2;
- msg.buf = buffer;
-
- error = iicbus_transfer_excl(dev, &msg, 1, IIC_WAIT);
- return (iic2errno(error));
-}
-
-static int
-tca6416_probe(device_t dev)
-{
-
- if (!ofw_bus_status_okay(dev))
- return (ENXIO);
-
- if (ofw_bus_search_compatible(dev, compat_data)->ocd_data == 0)
- return (ENXIO);
-
- device_set_desc(dev, "TCA6416 I/O expander");
- return (BUS_PROBE_DEFAULT);
-}
-
-static int
-tca6416_attach(device_t dev)
-{
- struct tca6416_softc *sc;
-
- sc = device_get_softc(dev);
- sc->dev = dev;
- sc->addr = iicbus_get_addr(dev);
-
- mtx_init(&sc->mtx, "tca6416 gpio", "gpio", MTX_DEF);
-
- sc->busdev = gpiobus_attach_bus(dev);
- if (sc->busdev == NULL) {
- device_printf(dev, "Could not create busdev child\n");
- return (ENXIO);
- }
-
-#ifdef DEBUG
- tca6416_regdump_setup(dev);
-#endif
-
- return (0);
-}
-
-static int
-tca6416_detach(device_t dev)
-{
- struct tca6416_softc *sc;
-
- sc = device_get_softc(dev);
-
- if (sc->busdev != NULL)
- gpiobus_detach_bus(sc->busdev);
-
- mtx_destroy(&sc->mtx);
-
- return (0);
-}
-
-static device_t
-tca6416_get_bus(device_t dev)
-{
- struct tca6416_softc *sc;
-
- sc = device_get_softc(dev);
-
- return (sc->busdev);
-}
-
-static int
-tca6416_pin_max(device_t dev __unused, int *maxpin)
-{
-
- if (maxpin == NULL)
- return (EINVAL);
-
- *maxpin = NUM_PINS - 1;
- return (0);
-}
-
-static int
-tca6416_pin_getcaps(device_t dev, uint32_t pin, uint32_t *caps)
-{
-
- if (pin >= NUM_PINS || caps == NULL)
- return (EINVAL);
-
- *caps = PIN_CAPS;
- return (0);
-}
-
-static int
-tca6416_pin_getflags(device_t dev, uint32_t pin, uint32_t *pflags)
-{
- int error;
- uint8_t reg_addr, reg_bit, val;
-
- if (pin >= NUM_PINS || pflags == NULL)
- return (EINVAL);
-
- reg_addr = TCA6416_REG_ADDR(pin, CONF_REG);
- reg_bit = TCA6416_BIT_FROM_PIN(pin);
-
- error = tca6416_read(dev, reg_addr, &val);
- if (error != 0)
- return (error);
-
- *pflags = (val & (1 << reg_bit))
- ? GPIO_PIN_INPUT : GPIO_PIN_OUTPUT;
-
- reg_addr = TCA6416_REG_ADDR(pin, POLARITY_INV_REG);
-
- error = tca6416_read(dev, reg_addr, &val);
- if (error != 0)
- return (error);
-
- if (val & (1 << reg_bit))
- *pflags |= GPIO_PIN_INVIN;
-
- return (0);
-}
-
-static int
-tca6416_pin_setflags(device_t dev, uint32_t pin, uint32_t flags)
-{
- uint8_t reg_addr, inv_reg_addr, reg_bit, val, inv_val;
- struct tca6416_softc *sc;
- int error;
-
- sc = device_get_softc(dev);
-
- if (pin >= NUM_PINS)
- return (EINVAL);
-
- reg_addr = TCA6416_REG_ADDR(pin, CONF_REG);
- inv_reg_addr = TCA6416_REG_ADDR(pin, POLARITY_INV_REG);
- reg_bit = TCA6416_BIT_FROM_PIN(pin);
-
- mtx_lock(&sc->mtx);
-
- error = tca6416_read(dev, reg_addr, &val);
- if (error != 0)
- goto fail;
- error = tca6416_read(dev, inv_reg_addr, &inv_val);
- if (error != 0)
- goto fail;
-
- if (flags & GPIO_PIN_INPUT)
- val |= (1 << reg_bit);
- else if (flags & GPIO_PIN_OUTPUT)
- val &= ~(1 << reg_bit);
-
- if (flags & GPIO_PIN_INVIN)
- inv_val |= (1 << reg_bit);
- else
- inv_val &= ~(1 << reg_bit);
-
- error = tca6416_write(dev, reg_addr, val);
- if (error != 0)
- goto fail;
- error = tca6416_write(dev, inv_reg_addr, val);
-
-fail:
- mtx_unlock(&sc->mtx);
- return (error);
-}
-
-static int
-tca6416_pin_getname(device_t dev, uint32_t pin, char *name)
-{
-
- if (pin >= NUM_PINS || name == NULL)
- return (EINVAL);
-
- snprintf(name, GPIOMAXNAME, "gpio_P%d%d", pin / PINS_PER_REG,
- pin % PINS_PER_REG);
-
- return (0);
-}
-
-static int
-tca6416_pin_get(device_t dev, uint32_t pin, unsigned int *pval)
-{
- uint8_t reg_bit, reg_addr, reg_pvalue;
- int error;
-
- if (pin >= NUM_PINS || pval == NULL)
- return (EINVAL);
-
- reg_bit = TCA6416_BIT_FROM_PIN(pin);
- reg_addr = TCA6416_REG_ADDR(pin, IN_PORT_REG);
-
- dbg_dev_printf(dev, "Reading pin %u pvalue.", pin);
-
- error = tca6416_read(dev, reg_addr, ®_pvalue);
- if (error != 0)
- return (error);
-
- *pval = reg_pvalue & (1 << reg_bit) ? 1 : 0;
-
- return (0);
-}
-
-static int
-tca6416_pin_set(device_t dev, uint32_t pin, unsigned int val)
-{
- struct tca6416_softc *sc;
- uint8_t reg_addr, reg_bit, reg_value;
- int error;
-
- sc = device_get_softc(dev);
-
- if (pin >= NUM_PINS)
- return (EINVAL);
-
- reg_addr = TCA6416_REG_ADDR(pin , OUT_PORT_REG);
- reg_bit = TCA6416_BIT_FROM_PIN(pin);
-
- dbg_dev_printf(dev, "Setting pin: %u to %u\n", pin, val);
-
- mtx_lock(&sc->mtx);
-
- error = tca6416_read(dev, reg_addr, ®_value);
- if (error != 0) {
- dbg_dev_printf(dev, "Failed to read from register.\n");
- mtx_unlock(&sc->mtx);
- return (error);
- }
-
- if (val != 0)
- reg_value |= (1 << reg_bit);
- else
- reg_value &= ~(1 << reg_bit);
-
-
- error = tca6416_write(dev, reg_addr, reg_value);
- if (error != 0) {
- dbg_dev_printf(dev, "Could not write to register.\n");
- mtx_unlock(&sc->mtx);
- return (error);
- }
-
- mtx_unlock(&sc->mtx);
-
- return (0);
-}
-
-static int
-tca6416_pin_toggle(device_t dev, uint32_t pin)
-{
- struct tca6416_softc *sc;
- int error;
- uint8_t reg_addr, reg_bit, reg_value;
-
- sc = device_get_softc(dev);
-
- if (pin >= NUM_PINS)
- return (EINVAL);
-
- reg_addr = TCA6416_REG_ADDR(pin, OUT_PORT_REG);
- reg_bit = TCA6416_BIT_FROM_PIN(pin);
-
- dbg_dev_printf(dev, "Toggling pin: %d\n", pin);
-
- mtx_lock(&sc->mtx);
-
- error = tca6416_read(dev, reg_addr, ®_value);
- if (error != 0) {
- mtx_unlock(&sc->mtx);
- dbg_dev_printf(dev, "Cannot read from register.\n");
- return (error);
- }
-
- reg_value ^= (1 << reg_bit);
-
- error = tca6416_write(dev, reg_addr, reg_value);
- if (error != 0)
- dbg_dev_printf(dev, "Cannot write to register.\n");
-
- mtx_unlock(&sc->mtx);
-
- return (error);
-}
-
-#ifdef DEBUG
-static void
-tca6416_regdump_setup(device_t dev)
-{
- struct sysctl_ctx_list *ctx;
- struct sysctl_oid *node;
-
- ctx = device_get_sysctl_ctx(dev);
- node = device_get_sysctl_tree(dev);
-
- SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "in_reg_1",
- CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev, IN_PORT_REG,
- tca6416_regdump_sysctl, "A", "Input port 1");
- SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "in_reg_2",
- CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
- IN_PORT_REG | 1, tca6416_regdump_sysctl, "A", "Input port 2");
- SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "out_reg_1",
- CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev, OUT_PORT_REG,
- tca6416_regdump_sysctl, "A", "Output port 1");
- SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "out_reg_2",
- CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev, OUT_PORT_REG
- | 1, tca6416_regdump_sysctl, "A", "Output port 2");
- SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "pol_inv_1",
- CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
- POLARITY_INV_REG, tca6416_regdump_sysctl, "A", "Polarity inv 1");
- SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "pol_inv_2",
- CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
- POLARITY_INV_REG | 1, tca6416_regdump_sysctl, "A",
- "Polarity inv 2");
- SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "conf_reg_1",
- CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
- CONF_REG, tca6416_regdump_sysctl, "A", "Configuration 1");
- SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "conf_reg_2",
- CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
- CONF_REG | 1, tca6416_regdump_sysctl, "A", "Configuration 2");
-}
-
-static int
-tca6416_regdump_sysctl(SYSCTL_HANDLER_ARGS)
-{
- device_t dev;
- char buf[5];
- int len, error;
- uint8_t reg, regval;
-
- dev = (device_t)arg1;
- reg = (uint8_t)arg2;
-
- error = tca6416_read(dev, reg, ®val);
- if (error != 0) {
- return (error);
- }
-
- len = snprintf(buf, 5, "0x%02x", regval);
-
- error = sysctl_handle_string(oidp, buf, len, req);
-
- return (error);
-}
-#endif
diff --git a/sys/dev/iicbus/gpio/tca64xx.c b/sys/dev/iicbus/gpio/tca64xx.c
new file mode 100644
--- /dev/null
+++ b/sys/dev/iicbus/gpio/tca64xx.c
@@ -0,0 +1,642 @@
+/*-
+ * SPDX-License-Identifier: BSD-2-Clause-FreeBSD
+ *
+ * Copyright (c) 2020 Alstom Group.
+ * Copyright (c) 2020 Semihalf.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
+ * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
+ * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
+ * SUCH DAMAGE.
+ */
+
+/*
+ * Driver for TI TCA64XX I2C GPIO expander module.
+ *
+ * This driver only supports basic functionality
+ * (interrupt handling and polarity inversion were omitted).
+ */
+
+#include <sys/cdefs.h>
+__FBSDID("$FreeBSD$");
+
+#include <sys/param.h>
+#include <sys/bus.h>
+#include <sys/gpio.h>
+#include <sys/kernel.h>
+#include <sys/module.h>
+#include <sys/proc.h>
+#include <sys/systm.h>
+#include <sys/sysctl.h>
+
+#include <machine/bus.h>
+
+#include <dev/ofw/openfirm.h>
+#include <dev/ofw/ofw_bus.h>
+#include <dev/ofw/ofw_bus_subr.h>
+
+#include <dev/iicbus/iicbus.h>
+#include <dev/iicbus/iiconf.h>
+
+#include <dev/gpio/gpiobusvar.h>
+
+#include "gpio_if.h"
+
+/* Base addresses of registers. LSB omitted. */
+
+#define TCA64XX_PINS_PER_REG 8
+
+#define TCA64XX_BIT_FROM_PIN(pin) (pin % TCA64XX_PINS_PER_REG)
+#define TCA64XX_REG_ADDR(pin, baseaddr) (baseaddr | (pin / \
+ TCA64XX_PINS_PER_REG))
+#define TCA64XX_PIN_CAPS (GPIO_PIN_OUTPUT | GPIO_PIN_INPUT \
+ | GPIO_PIN_PUSHPULL | GPIO_PIN_INVIN)
+
+#define TCA6416_IN_PORT_REG 0x0
+#define TCA6416_OUT_PORT_REG 0x2
+#define TCA6416_POLARITY_INV_REG 0x4
+#define TCA6416_CONF_REG 0x6
+#define TCA6416_NUM_PINS 16
+
+#define TCA6408_IN_PORT_REG 0x0
+#define TCA6408_OUT_PORT_REG 0x1
+#define TCA6408_POLARITY_INV_REG 0x2
+#define TCA6408_CONF_REG 0x3
+#define TCA6408_NUM_PINS 8
+
+#ifdef DEBUG
+#define dbg_dev_printf(dev, fmt, args...) \
+ device_printf(dev, fmt, ##args)
+#else
+#define dbg_dev_printf(dev, fmt, args...)
+#endif
+
+enum chip_type{
+ TCA6416_TYPE = 1,
+ TCA6408_TYPE
+};
+
+struct tca64xx_softc {
+ device_t dev;
+ device_t busdev;
+ enum chip_type chip;
+ struct mtx mtx;
+ uint32_t addr;
+ uint8_t num_pins;
+ uint8_t in_port_reg;
+ uint8_t out_port_reg;
+ uint8_t polarity_inv_reg;
+ uint8_t conf_reg;
+ uint8_t pin_caps;
+};
+
+static int tca64xx_read(device_t, uint8_t, uint8_t *);
+static int tca64xx_write(device_t, uint8_t, uint8_t);
+static int tca64xx_probe(device_t);
+static int tca64xx_attach(device_t);
+static int tca64xx_detach(device_t);
+static device_t tca64xx_get_bus(device_t);
+static int tca64xx_pin_max(device_t, int *);
+static int tca64xx_pin_getcaps(device_t, uint32_t, uint32_t *);
+static int tca64xx_pin_getflags(device_t, uint32_t, uint32_t *);
+static int tca64xx_pin_setflags(device_t, uint32_t, uint32_t);
+static int tca64xx_pin_getname(device_t, uint32_t, char *);
+static int tca64xx_pin_get(device_t, uint32_t, unsigned int *);
+static int tca64xx_pin_set(device_t, uint32_t, unsigned int);
+static int tca64xx_pin_toggle(device_t, uint32_t);
+#ifdef DEBUG
+static void tca6408_regdump_setup(device_t dev);
+static void tca6416_regdump_setup(device_t dev);
+static int tca64xx_regdump_sysctl(SYSCTL_HANDLER_ARGS);
+#endif
+
+static device_method_t tca64xx_methods[] = {
+ DEVMETHOD(device_probe, tca64xx_probe),
+ DEVMETHOD(device_attach, tca64xx_attach),
+ DEVMETHOD(device_detach, tca64xx_detach),
+
+ /* GPIO methods */
+ DEVMETHOD(gpio_get_bus, tca64xx_get_bus),
+ DEVMETHOD(gpio_pin_max, tca64xx_pin_max),
+ DEVMETHOD(gpio_pin_getcaps, tca64xx_pin_getcaps),
+ DEVMETHOD(gpio_pin_getflags, tca64xx_pin_getflags),
+ DEVMETHOD(gpio_pin_setflags, tca64xx_pin_setflags),
+ DEVMETHOD(gpio_pin_getname, tca64xx_pin_getname),
+ DEVMETHOD(gpio_pin_get, tca64xx_pin_get),
+ DEVMETHOD(gpio_pin_set, tca64xx_pin_set),
+ DEVMETHOD(gpio_pin_toggle, tca64xx_pin_toggle),
+
+ DEVMETHOD_END
+};
+
+static driver_t tca64xx_driver = {
+ "gpio",
+ tca64xx_methods,
+ sizeof(struct tca64xx_softc)
+};
+
+DRIVER_MODULE(tca64xx, iicbus, tca64xx_driver, 0, 0);
+MODULE_VERSION(tca64xx, 1);
+
+static struct ofw_compat_data compat_data[] = {
+ {"nxp,pca9555", TCA6416_TYPE},
+ {"ti,tca6408", TCA6408_TYPE},
+ {"ti,tca6416", TCA6416_TYPE},
+ {"ti,tca9539", TCA6416_TYPE},
+ {0,0}
+};
+
+static int
+tca64xx_read(device_t dev, uint8_t reg, uint8_t *data)
+{
+ struct iic_msg msgs[2];
+ struct tca64xx_softc *sc;
+ int error;
+
+ sc = device_get_softc(dev);
+ if (data == NULL)
+ return (EINVAL);
+
+ msgs[0].slave = sc->addr;
+ msgs[0].flags = IIC_M_WR | IIC_M_NOSTOP;
+ msgs[0].len = 1;
+ msgs[0].buf = ®
+
+ msgs[1].slave = sc->addr;
+ msgs[1].flags = IIC_M_RD;
+ msgs[1].len = 1;
+ msgs[1].buf = data;
+
+ error = iicbus_transfer_excl(dev, msgs, 2, IIC_WAIT);
+ return (iic2errno(error));
+}
+
+static int
+tca64xx_write(device_t dev, uint8_t reg, uint8_t val)
+{
+ struct iic_msg msg;
+ struct tca64xx_softc *sc;
+ int error;
+ uint8_t buffer[2] = {reg, val};
+
+ sc = device_get_softc(dev);
+
+ msg.slave = sc->addr;
+ msg.flags = IIC_M_WR;
+ msg.len = 2;
+ msg.buf = buffer;
+
+ error = iicbus_transfer_excl(dev, &msg, 1, IIC_WAIT);
+ return (iic2errno(error));
+}
+
+static int
+tca64xx_probe(device_t dev)
+{
+ const struct ofw_compat_data *compat_ptr;
+
+ if (!ofw_bus_status_okay(dev))
+ return (ENXIO);
+
+ compat_ptr = ofw_bus_search_compatible(dev, compat_data);
+
+ switch (compat_ptr->ocd_data) {
+ case TCA6416_TYPE:
+ device_set_desc(dev, "TCA6416 I/O expander");
+ break;
+ case TCA6408_TYPE:
+ device_set_desc(dev, "TCA6408 I/O expander");
+ break;
+ default:
+ return (ENXIO);
+ }
+
+ return (BUS_PROBE_DEFAULT);
+}
+
+static int
+tca64xx_attach(device_t dev)
+{
+ struct tca64xx_softc *sc;
+ const struct ofw_compat_data *compat_ptr;
+
+ sc = device_get_softc(dev);
+ compat_ptr = ofw_bus_search_compatible(dev, compat_data);
+
+ switch (compat_ptr->ocd_data) {
+ case TCA6416_TYPE:
+ sc->in_port_reg = TCA6416_IN_PORT_REG;
+ sc->out_port_reg = TCA6416_OUT_PORT_REG;
+ sc->polarity_inv_reg = TCA6416_POLARITY_INV_REG;
+ sc->conf_reg = TCA6416_CONF_REG;
+ sc->num_pins = TCA6416_NUM_PINS;
+ break;
+ case TCA6408_TYPE:
+ sc->in_port_reg = TCA6408_IN_PORT_REG;
+ sc->out_port_reg = TCA6408_OUT_PORT_REG;
+ sc->polarity_inv_reg = TCA6408_POLARITY_INV_REG;
+ sc->conf_reg = TCA6408_CONF_REG;
+ sc->num_pins = TCA6408_NUM_PINS;
+ break;
+ default:
+ __assert_unreachable();
+ }
+
+ sc->pin_caps = TCA64XX_PIN_CAPS;
+ sc->chip = compat_ptr->ocd_data;
+ sc->dev = dev;
+ sc->addr = iicbus_get_addr(dev);
+
+ mtx_init(&sc->mtx, "tca64xx gpio", "gpio", MTX_DEF);
+ sc->busdev = gpiobus_attach_bus(dev);
+ if (sc->busdev == NULL) {
+ device_printf(dev, "Could not create busdev child\n");
+ return (ENXIO);
+ }
+
+ OF_device_register_xref(OF_xref_from_node(ofw_bus_get_node(dev)), dev);
+
+#ifdef DEBUG
+ switch (sc->chip) {
+ case TCA6416_TYPE:
+ tca6416_regdump_setup(dev);
+ break;
+ case TCA6408_TYPE:
+ tca6408_regdump_setup(dev);
+ break;
+ default:
+ __assert_unreachable();
+ }
+#endif
+
+ return (0);
+}
+
+static int
+tca64xx_detach(device_t dev)
+{
+ struct tca64xx_softc *sc;
+
+ sc = device_get_softc(dev);
+
+ if (sc->busdev != NULL)
+ gpiobus_detach_bus(sc->busdev);
+
+ mtx_destroy(&sc->mtx);
+
+ return (0);
+}
+
+static device_t
+tca64xx_get_bus(device_t dev)
+{
+ struct tca64xx_softc *sc;
+
+ sc = device_get_softc(dev);
+
+ return (sc->busdev);
+}
+
+static int
+tca64xx_pin_max(device_t dev __unused, int *maxpin)
+{
+ struct tca64xx_softc *sc;
+
+ sc = device_get_softc(dev);
+
+ if (maxpin == NULL)
+ return (EINVAL);
+
+ *maxpin = sc->num_pins-1;
+
+ return (0);
+}
+
+static int
+tca64xx_pin_getcaps(device_t dev, uint32_t pin, uint32_t *caps)
+{
+ struct tca64xx_softc *sc;
+
+ sc = device_get_softc(dev);
+
+ if (pin >= sc->num_pins || caps == NULL)
+ return (EINVAL);
+ *caps = sc->pin_caps;
+
+ return (0);
+}
+
+static int
+tca64xx_pin_getflags(device_t dev, uint32_t pin, uint32_t *pflags)
+{
+ int error;
+ uint8_t bit, val, addr;
+ struct tca64xx_softc *sc;
+
+ sc = device_get_softc(dev);
+
+ bit = TCA64XX_BIT_FROM_PIN(pin);
+
+ if (pin >= sc->num_pins || pflags == NULL)
+ return (EINVAL);
+
+ addr = TCA64XX_REG_ADDR(pin, sc->conf_reg);
+ error = tca64xx_read(dev, addr, &val);
+ if (error != 0)
+ return (error);
+
+ *pflags = (val & (1 << bit)) ? GPIO_PIN_INPUT : GPIO_PIN_OUTPUT;
+
+ addr = TCA64XX_REG_ADDR(pin, sc->polarity_inv_reg);
+ error = tca64xx_read(dev, addr, &val);
+ if (error != 0)
+ return (error);
+
+ if (val & (1 << bit))
+ *pflags |= GPIO_PIN_INVIN;
+
+ return (0);
+}
+
+static int
+tca64xx_pin_setflags(device_t dev, uint32_t pin, uint32_t flags)
+{
+ uint8_t bit, val, addr, pins, inv_val;
+ int error;
+ struct tca64xx_softc *sc;
+
+ sc = device_get_softc(dev);
+
+ pins = sc->num_pins;
+ bit = TCA64XX_BIT_FROM_PIN(pin);
+
+ if (pin >= pins)
+ return (EINVAL);
+ mtx_lock(&sc->mtx);
+
+ addr = TCA64XX_REG_ADDR(pin, sc->conf_reg);
+ error = tca64xx_read(dev, addr, &val);
+ if (error != 0)
+ goto fail;
+
+ addr = TCA64XX_REG_ADDR(pin, sc->polarity_inv_reg);
+ error = tca64xx_read(dev, addr, &inv_val);
+ if (error != 0)
+ goto fail;
+
+ if (flags & GPIO_PIN_INPUT)
+ val |= (1 << bit);
+ else if (flags & GPIO_PIN_OUTPUT)
+ val &= ~(1 << bit);
+
+ if (flags & GPIO_PIN_INVIN)
+ inv_val |= (1 << bit);
+ else
+ inv_val &= ~(1 << bit);
+
+ addr = TCA64XX_REG_ADDR(pin, sc->conf_reg);
+ error = tca64xx_write(dev, addr, val);
+ if (error != 0)
+ goto fail;
+
+ addr = TCA64XX_REG_ADDR(pin, sc->polarity_inv_reg);
+ error = tca64xx_write(dev, addr, val);
+
+fail:
+ mtx_unlock(&sc->mtx);
+ return (error);
+}
+
+static int
+tca64xx_pin_getname(device_t dev, uint32_t pin, char *name)
+{
+ struct tca64xx_softc *sc;
+
+ sc = device_get_softc(dev);
+
+ if (pin >= sc->num_pins || name == NULL)
+ return (EINVAL);
+
+ snprintf(name, GPIOMAXNAME, "gpio_P%d%d", pin / TCA64XX_PINS_PER_REG,
+ pin % TCA64XX_PINS_PER_REG);
+
+ return (0);
+}
+
+static int
+tca64xx_pin_get(device_t dev, uint32_t pin, unsigned int *pval)
+{
+ uint8_t bit, addr, pins, reg_pvalue;
+ int error;
+ struct tca64xx_softc *sc;
+
+ sc = device_get_softc(dev);
+
+ pins = sc->num_pins;
+ addr = TCA64XX_REG_ADDR(pin, sc->in_port_reg);
+ bit = TCA64XX_BIT_FROM_PIN(pin);
+
+ if (pin >= pins || pval == NULL)
+ return (EINVAL);
+
+ dbg_dev_printf(dev, "Reading pin %u pvalue.", pin);
+
+ error = tca64xx_read(dev, addr, ®_pvalue);
+ if (error != 0)
+ return (error);
+ *pval = reg_pvalue & (1 << bit) ? 1 : 0;
+
+ return (0);
+}
+
+static int
+tca64xx_pin_set(device_t dev, uint32_t pin, unsigned int val)
+{
+ uint8_t bit, addr, pins, value;
+ int error;
+ struct tca64xx_softc *sc;
+
+ sc = device_get_softc(dev);
+
+ pins = sc->num_pins;
+ addr = TCA64XX_REG_ADDR(pin, sc->out_port_reg);
+ bit = TCA64XX_BIT_FROM_PIN(pin);
+
+ if (pin >= pins)
+ return (EINVAL);
+
+ dbg_dev_printf(dev, "Setting pin: %u to %u\n", pin, val);
+
+ mtx_lock(&sc->mtx);
+
+ error = tca64xx_read(dev, addr, &value);
+ if (error != 0) {
+ mtx_unlock(&sc->mtx);
+ dbg_dev_printf(dev, "Failed to read from register.\n");
+ return (error);
+ }
+
+ if (val != 0)
+ value |= (1 << bit);
+ else
+ value &= ~(1 << bit);
+
+ error = tca64xx_write(dev, addr, value);
+ if (error != 0) {
+ mtx_unlock(&sc->mtx);
+ dbg_dev_printf(dev, "Could not write to register.\n");
+ return (error);
+ }
+
+ mtx_unlock(&sc->mtx);
+
+ return (0);
+}
+
+static int
+tca64xx_pin_toggle(device_t dev, uint32_t pin)
+{
+ int error;
+ uint8_t bit, addr, pins, value;
+ struct tca64xx_softc *sc;
+
+ sc = device_get_softc(dev);
+
+ pins = sc->num_pins;
+ addr = TCA64XX_REG_ADDR(pin, sc->out_port_reg);
+ bit = TCA64XX_BIT_FROM_PIN(pin);
+
+ if (pin >= pins)
+ return (EINVAL);
+
+ dbg_dev_printf(dev, "Toggling pin: %d\n", pin);
+
+ mtx_lock(&sc->mtx);
+
+ error = tca64xx_read(dev, addr, &value);
+ if (error != 0) {
+ mtx_unlock(&sc->mtx);
+ dbg_dev_printf(dev, "Cannot read from register.\n");
+ return (error);
+ }
+
+ value ^= (1 << bit);
+
+ error = tca64xx_write(dev, addr, value);
+ if (error != 0) {
+ mtx_unlock(&sc->mtx);
+ dbg_dev_printf(dev, "Cannot write to register.\n");
+ return (error);
+ }
+
+ mtx_unlock(&sc->mtx);
+
+ return (0);
+}
+
+#ifdef DEBUG
+static void
+tca6416_regdump_setup(device_t dev)
+{
+ struct sysctl_ctx_list *ctx;
+ struct sysctl_oid *node;
+
+ ctx = device_get_sysctl_ctx(dev);
+ node = device_get_sysctl_tree(dev);
+
+ SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "in_reg_1",
+ CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
+ TCA6416_IN_PORT_REG, tca64xx_regdump_sysctl, "A", "Input port 1");
+ SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "in_reg_2",
+ CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
+ TCA6416_IN_PORT_REG | 1, tca64xx_regdump_sysctl, "A",
+ "Input port 2");
+ SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "out_reg_1",
+ CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
+ TCA6416_OUT_PORT_REG, tca64xx_regdump_sysctl, "A",
+ "Output port 1");
+ SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "out_reg_2",
+ CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
+ TCA6416_OUT_PORT_REG | 1, tca64xx_regdump_sysctl, "A",
+ "Output port 2");
+ SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "pol_inv_1",
+ CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
+ TCA6416_POLARITY_INV_REG, tca64xx_regdump_sysctl, "A",
+ "Polarity inv 1");
+ SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "pol_inv_2",
+ CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
+ TCA6416_POLARITY_INV_REG | 1, tca64xx_regdump_sysctl, "A",
+ "Polarity inv 2");
+ SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "conf_reg_1",
+ CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
+ TCA6416_CONF_REG, tca64xx_regdump_sysctl, "A", "Configuration 1");
+ SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "conf_reg_2",
+ CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
+ TCA6416_CONF_REG | 1, tca64xx_regdump_sysctl, "A",
+ "Configuration 2");
+}
+
+static void
+tca6408_regdump_setup(device_t dev)
+{
+ struct sysctl_ctx_list *ctx;
+ struct sysctl_oid *node;
+
+ ctx = device_get_sysctl_ctx(dev);
+ node = device_get_sysctl_tree(dev);
+
+ SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "in_reg_1",
+ CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
+ TCA6408_IN_PORT_REG, tca64xx_regdump_sysctl, "A", "Input port 1");
+ SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "out_reg_1",
+ CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
+ TCA6408_OUT_PORT_REG, tca64xx_regdump_sysctl, "A",
+ "Output port 1");
+ SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "pol_inv_1",
+ CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
+ TCA6408_POLARITY_INV_REG, tca64xx_regdump_sysctl,
+ "A", "Polarity inv 1");
+ SYSCTL_ADD_PROC(ctx, SYSCTL_CHILDREN(node), OID_AUTO, "conf_reg_1",
+ CTLTYPE_STRING | CTLFLAG_RD | CTLFLAG_MPSAFE, dev,
+ TCA6408_CONF_REG, tca64xx_regdump_sysctl, "A", "Configuration 1");
+}
+
+static int
+tca64xx_regdump_sysctl(SYSCTL_HANDLER_ARGS)
+{
+ device_t dev;
+ char buf[5];
+ int len, error;
+ uint8_t reg, regval;
+
+ dev = (device_t)arg1;
+ reg = (uint8_t)arg2;
+
+ error = tca64xx_read(dev, reg, ®val);
+ if (error != 0) {
+ return (error);
+ }
+
+ len = snprintf(buf, 5, "0x%02x", regval);
+
+ error = sysctl_handle_string(oidp, buf, len, req);
+
+ return (error);
+}
+#endif
diff --git a/sys/modules/i2c/Makefile b/sys/modules/i2c/Makefile
--- a/sys/modules/i2c/Makefile
+++ b/sys/modules/i2c/Makefile
@@ -30,7 +30,7 @@
.if !empty(OPT_FDT)
SUBDIR += rx8803 \
- tca6416 \
+ tca64xx \
tmp461
.endif
diff --git a/sys/modules/i2c/tca6416/Makefile b/sys/modules/i2c/tca6416/Makefile
--- a/sys/modules/i2c/tca6416/Makefile
+++ b/sys/modules/i2c/tca6416/Makefile
@@ -1,7 +0,0 @@
-# $FreeBSD$
-
-.PATH: ${SRCTOP}/sys/dev/iicbus/gpio/
-KMOD = tca6416
-SRCS = tca6416.c opt_platform.h gpio_if.h
-
-.include <bsd.kmod.mk>
diff --git a/sys/modules/i2c/tca64xx/Makefile b/sys/modules/i2c/tca64xx/Makefile
new file mode 100644
--- /dev/null
+++ b/sys/modules/i2c/tca64xx/Makefile
@@ -0,0 +1,5 @@
+.PATH: ${SRCTOP}/sys/dev/iicbus/gpio/
+KMOD = tca64xx
+SRCS = tca64xx.c opt_platform.h gpio_if.h device_if.h bus_if.h ofw_bus_if.h
+
+.include <bsd.kmod.mk>
File Metadata
Details
Attached
Mime Type
text/plain
Expires
Sun, Oct 12, 10:07 PM (6 h, 48 m)
Storage Engine
blob
Storage Format
Raw Data
Storage Handle
23643161
Default Alt Text
D36559.diff (40 KB)
Attached To
Mode
D36559: Merge TCA6416 & TCA6408 modules into TCA64XX
Attached
Detach File
Event Timeline
Log In to Comment