driver: gpio: mcp23xxx: Refactor to generic.

Refactor the mcp230xx driver to generically also support
SPI IO expanders, renaming it to mcp23xxx in the process.

Signed-off-by: Peter Johanson <peter@peterjohanson.com>
This commit is contained in:
Peter Johanson 2021-11-23 21:40:48 -05:00 committed by Christopher Friedt
commit a5ad94f20f
14 changed files with 677 additions and 403 deletions

View file

@ -13,6 +13,8 @@ zephyr_library_sources_ifdef(CONFIG_GPIO_GECKO gpio_gecko.c)
zephyr_library_sources_ifdef(CONFIG_GPIO_IMX gpio_imx.c)
zephyr_library_sources_ifdef(CONFIG_GPIO_ITE_IT8XXX2 gpio_ite_it8xxx2.c)
zephyr_library_sources_ifdef(CONFIG_GPIO_MCP23S17 gpio_mcp23s17.c)
zephyr_library_sources_ifdef(CONFIG_GPIO_MCP23XXX gpio_mcp23xxx.c)
zephyr_library_sources_ifdef(CONFIG_GPIO_MCP23SXX gpio_mcp23sxx.c)
zephyr_library_sources_ifdef(CONFIG_GPIO_MCP230XX gpio_mcp230xx.c)
zephyr_library_sources_ifdef(CONFIG_GPIO_MCUX gpio_mcux.c)
zephyr_library_sources_ifdef(CONFIG_GPIO_MCUX_IGPIO gpio_mcux_igpio.c)

View file

@ -35,7 +35,7 @@ source "drivers/gpio/Kconfig.pca95xx"
source "drivers/gpio/Kconfig.mcp23s17"
source "drivers/gpio/Kconfig.mcp230xx"
source "drivers/gpio/Kconfig.mcp23xxx"
source "drivers/gpio/Kconfig.mcux"

View file

@ -1,26 +0,0 @@
# MCP23S17 GPIO configuration options
# Copyright (c) 2021 metraTec GmbH
# SPDX-License-Identifier: Apache-2.0
# Workaround for not being able to have commas in macro arguments
DT_COMPAT_MICROCHIP_MCP23008 := microchip,mcp23008
DT_COMPAT_MICROCHIP_MCP23017 := microchip,mcp23017
menuconfig GPIO_MCP230XX
bool "MCP230XX I2C-based GPIO chip"
default $(dt_compat_enabled,$(DT_COMPAT_MICROCHIP_MCP23008)) || \
$(dt_compat_enabled,$(DT_COMPAT_MICROCHIP_MCP23017))
depends on I2C
help
Enable driver for MCP230XX I2C-based GPIO chip.
if GPIO_MCP230XX
config GPIO_MCP230XX_INIT_PRIORITY
int "Init priority"
default 75
help
Device driver initialization priority.
endif #GPIO_MCP230XX

View file

@ -0,0 +1,50 @@
# MCP23S17 GPIO configuration options
# Copyright (c) 2021 metraTec GmbH
# SPDX-License-Identifier: Apache-2.0
# Workaround for not being able to have commas in macro arguments
DT_COMPAT_MICROCHIP_MCP230xx := microchip,mcp230xx
DT_COMPAT_MICROCHIP_MCP23Sxx := microchip,mcp23sxx
config GPIO_MCP23XXX
bool
help
Enable support for the Microchip 23xxx I2C/SPI IO
expanders.
menuconfig GPIO_MCP230XX
bool "MCP230XX I2C-based GPIO chip"
default $(dt_compat_enabled,$(DT_COMPAT_MICROCHIP_MCP230xx))
depends on I2C
select GPIO_MCP23XXX
help
Enable driver for MCP230XX I2C-based GPIO chip.
if GPIO_MCP230XX
config GPIO_MCP230XX_INIT_PRIORITY
int "MCP230XX GPIO expander init priority"
default 75
help
Device driver initialization priority.
endif #GPIO_MCP230XX
menuconfig GPIO_MCP23SXX
bool "MCP23SXX SPI-based GPIO chip"
default $(dt_compat_enabled,$(DT_COMPAT_MICROCHIP_MCP23Sxx))
depends on SPI
select GPIO_MCP23XXX
help
Enable driver for MCP23SXX SPI-based GPIO chip.
if GPIO_MCP23SXX
config GPIO_MCP23SXX_INIT_PRIORITY
int "MCP23SXX GPIO expander init priority"
default 75
help
Device driver initialization priority.
endif #GPIO_MCP23SXX

View file

@ -1,5 +1,7 @@
/*
*
* Copyright (c) 2021 metraTec GmbH
* Copyright (c) 2021 Peter Johanson
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -16,34 +18,22 @@
#include <drivers/i2c.h>
#include "gpio_utils.h"
#include "gpio_mcp230xx.h"
#include "gpio_mcp23xxx.h"
#define LOG_LEVEL CONFIG_GPIO_LOG_LEVEL
#include <logging/log.h>
LOG_MODULE_REGISTER(gpio_mcp230xx);
/**
* @brief Reads given register from mcp230xx.
*
* The registers of the mcp23008 consist of one 8 bit port.
* The registers of the mcp23017 consist of two 8 bit ports.
*
* @param dev The mcp230xx device.
* @param reg The register to be read.
* @param buf The buffer to read data to.
* @return 0 if successful.
* Otherwise <0 will be returned.
*/
static int read_port_regs(const struct device *dev, uint8_t reg, uint16_t *buf)
static int mcp230xx_read_port_regs(const struct device *dev, uint8_t reg, uint16_t *buf)
{
const struct mcp230xx_config *config = dev->config;
const struct mcp23xxx_config *config = dev->config;
uint16_t port_data = 0;
int ret;
uint8_t nread = (config->ngpios == 8) ? 1 : 2;
ret = i2c_burst_read(config->i2c.bus, config->i2c.addr, reg, (uint8_t *)&port_data, nread);
if (ret) {
ret = i2c_burst_read_dt(&config->bus.i2c, reg, (uint8_t *)&port_data, nread);
if (ret < 0) {
LOG_ERR("i2c_read failed!");
return ret;
}
@ -53,29 +43,16 @@ static int read_port_regs(const struct device *dev, uint8_t reg, uint16_t *buf)
return 0;
}
/**
* @brief Writes registers of the mcp230xx.
*
* On the mcp23008 one 8 bit port will be written.
* On the mcp23017 two 8 bit ports will be written.
*
* @param dev The mcp230xx device.
* @param reg Register to be written.
* @param buf The new register value.
*
* @return 0 if successful. Otherwise <0 will be returned.
*/
static int write_port_regs(const struct device *dev, uint8_t reg, uint16_t value)
static int mcp230xx_write_port_regs(const struct device *dev, uint8_t reg, uint16_t value)
{
const struct mcp230xx_config *config = dev->config;
const struct mcp23xxx_config *config = dev->config;
int ret;
uint8_t nwrite = (config->ngpios == 8) ? 1 : 2;
uint16_t port_data = sys_cpu_to_le16(value);
ret = i2c_burst_write(config->i2c.bus, config->i2c.addr, reg, (uint8_t *)&port_data,
nwrite);
if (ret) {
ret = i2c_burst_write_dt(&config->bus.i2c, reg, (uint8_t *)&port_data, nwrite);
if (ret < 0) {
LOG_ERR("i2c_write failed!");
return ret;
}
@ -83,259 +60,44 @@ static int write_port_regs(const struct device *dev, uint8_t reg, uint16_t value
return 0;
}
/**
* @brief Setup the pin direction.
*
* @param dev The mcp230xx device.
* @param pin The pin number.
* @param flags Flags of pin or port.
* @return 0 if successful. Otherwise <0 will be returned.
*/
static int setup_pin_dir(const struct device *dev, uint32_t pin, int flags)
static int mcp230xx_bus_is_ready(const struct device *dev)
{
struct mcp230xx_drv_data *drv_data = (struct mcp230xx_drv_data *)dev->data;
uint16_t dir = drv_data->reg_cache.iodir;
uint16_t output = drv_data->reg_cache.gpio;
int ret;
const struct mcp23xxx_config *config = dev->config;
if ((flags & GPIO_OUTPUT) != 0U) {
if ((flags & GPIO_OUTPUT_INIT_HIGH) != 0U) {
output |= BIT(pin);
} else if ((flags & GPIO_OUTPUT_INIT_LOW) != 0U) {
output &= ~BIT(pin);
}
dir &= ~BIT(pin);
} else {
dir |= BIT(pin);
}
ret = write_port_regs(dev, REG_GPIO, output);
if (ret != 0) {
return ret;
}
drv_data->reg_cache.gpio = output;
ret = write_port_regs(dev, REG_IODIR, dir);
if (ret == 0) {
drv_data->reg_cache.iodir = dir;
}
return ret;
}
/**
* @brief Setup pin pull up/pull down.
*
* @param dev The mcp230xx device.
* @param pin The pin number.
* @param flags Flags of pin or port.
* @return 0 if successful. Otherwise <0 will be returned.
*/
static int setup_pin_pull(const struct device *dev, uint32_t pin, int flags)
{
struct mcp230xx_drv_data *drv_data = (struct mcp230xx_drv_data *)dev->data;
uint16_t port;
int ret;
port = drv_data->reg_cache.gppu;
if ((flags & GPIO_PULL_DOWN) != 0U) {
return -ENOTSUP;
}
WRITE_BIT(port, pin, (flags & GPIO_PULL_UP) != 0);
ret = write_port_regs(dev, REG_GPPU, port);
if (ret == 0) {
drv_data->reg_cache.gppu = port;
}
return ret;
}
static int mcp230xx_pin_cfg(const struct device *dev, gpio_pin_t pin, gpio_flags_t flags)
{
struct mcp230xx_drv_data *drv_data = (struct mcp230xx_drv_data *)dev->data;
int ret;
if (k_is_in_isr()) {
return -EWOULDBLOCK;
}
k_sem_take(&drv_data->lock, K_FOREVER);
if ((flags & GPIO_SINGLE_ENDED) != 0U) {
ret = -ENOTSUP;
goto done;
}
ret = setup_pin_dir(dev, pin, flags);
if (ret) {
LOG_ERR("Error setting pin direction (%d)", ret);
goto done;
}
ret = setup_pin_pull(dev, pin, flags);
if (ret) {
LOG_ERR("Error setting pin pull up/pull down (%d)", ret);
goto done;
}
done:
k_sem_give(&drv_data->lock);
return ret;
}
static int mcp230xx_port_get_raw(const struct device *dev, uint32_t *value)
{
struct mcp230xx_drv_data *drv_data = (struct mcp230xx_drv_data *)dev->data;
uint16_t buf;
int ret;
if (k_is_in_isr()) {
return -EWOULDBLOCK;
}
k_sem_take(&drv_data->lock, K_FOREVER);
ret = read_port_regs(dev, REG_GPIO, &buf);
if (ret == 0) {
*value = buf;
}
k_sem_give(&drv_data->lock);
return ret;
}
static int mcp230xx_port_set_masked_raw(const struct device *dev, uint32_t mask, uint32_t value)
{
struct mcp230xx_drv_data *drv_data = (struct mcp230xx_drv_data *)dev->data;
uint16_t buf;
int ret;
if (k_is_in_isr()) {
return -EWOULDBLOCK;
}
k_sem_take(&drv_data->lock, K_FOREVER);
buf = drv_data->reg_cache.gpio;
buf = (buf & ~mask) | (mask & value);
ret = write_port_regs(dev, REG_GPIO, buf);
if (ret == 0) {
drv_data->reg_cache.gpio = buf;
}
k_sem_give(&drv_data->lock);
return ret;
}
static int mcp230xx_port_set_bits_raw(const struct device *dev, uint32_t mask)
{
return mcp230xx_port_set_masked_raw(dev, mask, mask);
}
static int mcp230xx_port_clear_bits_raw(const struct device *dev, uint32_t mask)
{
return mcp230xx_port_set_masked_raw(dev, mask, 0);
}
static int mcp230xx_port_toggle_bits(const struct device *dev, uint32_t mask)
{
struct mcp230xx_drv_data *drv_data = (struct mcp230xx_drv_data *)dev->data;
uint16_t buf;
int ret;
if (k_is_in_isr()) {
return -EWOULDBLOCK;
}
k_sem_take(&drv_data->lock, K_FOREVER);
buf = drv_data->reg_cache.gpio;
buf ^= mask;
ret = write_port_regs(dev, REG_GPIO, buf);
if (ret == 0) {
drv_data->reg_cache.gpio = buf;
}
k_sem_give(&drv_data->lock);
return ret;
}
static int mcp230xx_pin_interrupt_configure(const struct device *dev, gpio_pin_t pin,
enum gpio_int_mode mode, enum gpio_int_trig trig)
{
return -ENOTSUP;
}
static const struct gpio_driver_api api_table = {
.pin_configure = mcp230xx_pin_cfg,
.port_get_raw = mcp230xx_port_get_raw,
.port_set_masked_raw = mcp230xx_port_set_masked_raw,
.port_set_bits_raw = mcp230xx_port_set_bits_raw,
.port_clear_bits_raw = mcp230xx_port_clear_bits_raw,
.port_toggle_bits = mcp230xx_port_toggle_bits,
.pin_interrupt_configure = mcp230xx_pin_interrupt_configure,
};
/**
* @brief Initialization function of MCP230XX
*
* @param dev Device struct.
* @return 0 if successful. Otherwise <0 is returned.
*/
static int mcp230xx_init(const struct device *dev)
{
const struct mcp230xx_config *config = dev->config;
struct mcp230xx_drv_data *drv_data = (struct mcp230xx_drv_data *)dev->data;
if (config->ngpios != 8 && config->ngpios != 16) {
LOG_ERR("Invalid value ngpios=%u. Expected 8 or 16!", config->ngpios);
return -EINVAL;
}
if (!device_is_ready(config->i2c.bus)) {
LOG_ERR("%s is not ready", config->i2c.bus->name);
if (!device_is_ready(config->bus.i2c.bus)) {
LOG_ERR("I2C bus %s not ready", config->bus.i2c.bus->name);
return -ENODEV;
}
k_sem_init(&drv_data->lock, 1, 1);
return 0;
}
#define MCP230XX_INIT(inst) \
static struct mcp230xx_config mcp230xx_##inst##_config = { \
.config = { \
.port_pin_mask = \
GPIO_PORT_PIN_MASK_FROM_DT_INST(inst), \
}, \
.i2c = I2C_DT_SPEC_INST_GET(inst), \
.ngpios = DT_INST_PROP(inst, ngpios), \
}; \
\
static struct mcp230xx_drv_data mcp230xx_##inst##_drvdata = { \
#define DT_DRV_COMPAT microchip_mcp230xx
#define GPIO_MCP230XX_DEVICE(n) \
static struct mcp23xxx_drv_data mcp230xx_##inst##_drvdata = { \
/* Default for registers according to datasheet */ \
.reg_cache.iodir = 0xFFFF, .reg_cache.ipol = 0x0, .reg_cache.gpinten = 0x0, \
.reg_cache.defval = 0x0, .reg_cache.intcon = 0x0, .reg_cache.iocon = 0x0, \
.reg_cache.gppu = 0x0, .reg_cache.intf = 0x0, .reg_cache.intcap = 0x0, \
.reg_cache.gpio = 0x0, .reg_cache.olat = 0x0, \
}; \
\
/* This has to init after SPI master */ \
DEVICE_DT_INST_DEFINE(inst, mcp230xx_init, NULL, &mcp230xx_##inst##_drvdata, \
static struct mcp23xxx_config mcp230xx_##inst##_config = { \
.config = { \
.port_pin_mask = \
GPIO_PORT_PIN_MASK_FROM_DT_NODE(DT_DRV_INST(n)), \
}, \
.bus = \
{ \
.i2c = I2C_DT_SPEC_GET(DT_DRV_INST(n)) \
}, \
.ngpios = DT_PROP(DT_DRV_INST(n), ngpios), \
.read_fn = mcp230xx_read_port_regs, \
.write_fn = mcp230xx_write_port_regs, \
.bus_fn = mcp230xx_bus_is_ready \
}; \
DEVICE_DT_INST_DEFINE(n, gpio_mcp23xxx_init, NULL, &mcp230xx_##inst##_drvdata, \
&mcp230xx_##inst##_config, POST_KERNEL, \
CONFIG_GPIO_MCP230XX_INIT_PRIORITY, &api_table);
CONFIG_GPIO_MCP230XX_INIT_PRIORITY, &gpio_mcp23xxx_api_table);
#undef DT_DRV_COMPAT
#define DT_DRV_COMPAT microchip_mcp23008
DT_INST_FOREACH_STATUS_OKAY(MCP230XX_INIT)
#undef DT_DRV_COMPAT
#define DT_DRV_COMPAT microchip_mcp23017
DT_INST_FOREACH_STATUS_OKAY(MCP230XX_INIT)
DT_INST_FOREACH_STATUS_OKAY(GPIO_MCP230XX_DEVICE)

View file

@ -1,72 +0,0 @@
/*
* Copyright (c) 2021 metraTec GmbH
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file Header file for the MCP230xx driver.
*/
#ifndef ZEPHYR_DRIVERS_GPIO_GPIO_MCP230XX_H_
#define ZEPHYR_DRIVERS_GPIO_GPIO_MCP230XX_H_
#include <kernel.h>
#include <drivers/gpio.h>
#include <drivers/i2c.h>
#ifdef __cplusplus
extern "C" {
#endif
/* Register definitions */
#define REG_IODIR 0x00
#define REG_IPOL 0x01
#define REG_GPINTEN 0x02
#define REG_DEFVAL 0x03
#define REG_INTCON 0x04
#define REG_IOCON 0x05
#define REG_GPPU 0x06
#define REG_INTF 0x07
#define REG_INTCAP 0x08
#define REG_GPIO 0x09
#define REG_IKAT 0x0A
/** Configuration data */
struct mcp230xx_config {
/* gpio_driver_config needs to be first */
struct gpio_driver_config config;
/** I2C device */
const struct i2c_dt_spec i2c;
uint8_t ngpios;
};
/** Runtime driver data */
struct mcp230xx_drv_data {
/* gpio_driver_data needs to be first */
struct gpio_driver_data data;
struct k_sem lock;
struct {
uint16_t iodir;
uint16_t ipol;
uint16_t gpinten;
uint16_t defval;
uint16_t intcon;
uint16_t iocon;
uint16_t gppu;
uint16_t intf;
uint16_t intcap;
uint16_t gpio;
uint16_t olat;
} reg_cache;
};
#ifdef __cplusplus
}
#endif
#endif /* ZEPHYR_DRIVERS_GPIO_GPIO_MCP230XX_H_ */

View file

@ -0,0 +1,142 @@
/*
*
* Copyright (c) 2021 metraTec GmbH
* Copyright (c) 2021 Peter Johanson
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file Driver for MPC23Sxx SPI-based GPIO driver.
*/
#include <errno.h>
#include <kernel.h>
#include <device.h>
#include <sys/byteorder.h>
#include <drivers/gpio.h>
#include <drivers/spi.h>
#include "gpio_utils.h"
#include "gpio_mcp23xxx.h"
#define LOG_LEVEL CONFIG_GPIO_LOG_LEVEL
#include <logging/log.h>
LOG_MODULE_REGISTER(gpio_mcp23sxx);
static int mcp23sxx_read_port_regs(const struct device *dev, uint8_t reg, uint16_t *buf)
{
const struct mcp23xxx_config *config = dev->config;
uint16_t port_data = 0;
int ret;
uint8_t nread = (config->ngpios == 8) ? 1 : 2;
uint8_t addr = MCP23SXX_ADDR | MCP23SXX_READBIT;
uint8_t buffer_tx[4] = { addr, reg, 0, 0 };
const struct spi_buf tx_buf = {
.buf = buffer_tx,
.len = 4,
};
const struct spi_buf_set tx = {
.buffers = &tx_buf,
.count = 1,
};
const struct spi_buf rx_buf[2] = { { .buf = NULL, .len = 2 },
{ .buf = (uint8_t *)&port_data, .len = nread } };
const struct spi_buf_set rx = {
.buffers = rx_buf,
.count = ARRAY_SIZE(rx_buf),
};
ret = spi_transceive_dt(&config->bus.spi, &tx, &rx);
if (ret < 0) {
LOG_ERR("spi_transceive FAIL %d\n", ret);
return ret;
}
*buf = sys_le16_to_cpu(port_data);
return 0;
}
static int mcp23sxx_write_port_regs(const struct device *dev, uint8_t reg, uint16_t value)
{
const struct mcp23xxx_config *config = dev->config;
int ret;
uint8_t nwrite = (config->ngpios == 8) ? 1 : 2;
uint16_t port_data = sys_cpu_to_le16(value);
port_data = sys_cpu_to_le16(value);
uint8_t addr = MCP23SXX_ADDR;
uint8_t buffer_tx[2] = { addr, reg };
const struct spi_buf tx_buf[2] = {
{
.buf = buffer_tx,
.len = 2,
},
{
.buf = (uint8_t *)&port_data,
.len = nwrite,
}
};
const struct spi_buf_set tx = {
.buffers = tx_buf,
.count = ARRAY_SIZE(tx_buf),
};
ret = spi_write_dt(&config->bus.spi, &tx);
if (ret < 0) {
LOG_ERR("spi_write FAIL %d\n", ret);
return ret;
}
return 0;
}
static int mcp23sxx_bus_is_ready(const struct device *dev)
{
const struct mcp23xxx_config *config = dev->config;
if (!spi_is_ready(&config->bus.spi)) {
LOG_ERR("SPI bus %s not ready", config->bus.spi.bus->name);
return -ENODEV;
}
return 0;
}
#define DT_DRV_COMPAT microchip_mcp23sxx
#define GPIO_MCP23SXX_DEVICE(n) \
static struct mcp23xxx_drv_data mcp23sxx_##inst##_drvdata = { \
/* Default for registers according to datasheet */ \
.reg_cache.iodir = 0xFFFF, .reg_cache.ipol = 0x0, .reg_cache.gpinten = 0x0, \
.reg_cache.defval = 0x0, .reg_cache.intcon = 0x0, .reg_cache.iocon = 0x0, \
.reg_cache.gppu = 0x0, .reg_cache.intf = 0x0, .reg_cache.intcap = 0x0, \
.reg_cache.gpio = 0x0, .reg_cache.olat = 0x0, \
}; \
static struct mcp23xxx_config mcp23sxx_##inst##_config = { \
.config = { \
.port_pin_mask = \
GPIO_PORT_PIN_MASK_FROM_DT_NODE(DT_DRV_INST(n)), \
}, \
.bus = { \
.spi = SPI_DT_SPEC_INST_GET(n, \
SPI_OP_MODE_MASTER | SPI_MODE_CPOL | \
SPI_MODE_CPHA | SPI_WORD_SET(8), 0) \
}, \
.ngpios = DT_INST_PROP(n, ngpios), \
.read_fn = mcp23sxx_read_port_regs, \
.write_fn = mcp23sxx_write_port_regs, \
.bus_fn = mcp23sxx_bus_is_ready \
}; \
DEVICE_DT_INST_DEFINE(n, gpio_mcp23xxx_init, NULL, &mcp23sxx_##inst##_drvdata, \
&mcp23sxx_##inst##_config, POST_KERNEL, \
CONFIG_GPIO_MCP23SXX_INIT_PRIORITY, &gpio_mcp23xxx_api_table);
DT_INST_FOREACH_STATUS_OKAY(GPIO_MCP23SXX_DEVICE)

View file

@ -0,0 +1,296 @@
/*
*
* Copyright (c) 2021 metraTec GmbH
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file Driver for MPC23xxx I2C/SPI-based GPIO driver.
*/
#include <errno.h>
#include <kernel.h>
#include <device.h>
#include <sys/byteorder.h>
#include <drivers/gpio.h>
#include "gpio_utils.h"
#include "gpio_mcp23xxx.h"
#define LOG_LEVEL CONFIG_GPIO_LOG_LEVEL
#include <logging/log.h>
LOG_MODULE_REGISTER(gpio_mcp23xxx);
/**
* @brief Reads given register from mcp23xxx.
*
* The registers of the mcp23x0x consist of one 8 bit port.
* The registers of the mcp23x1x consist of two 8 bit ports.
*
* @param dev The mcp23xxx device.
* @param reg The register to be read.
* @param buf The buffer to read data to.
* @return 0 if successful.
* Otherwise <0 will be returned.
*/
static int read_port_regs(const struct device *dev, uint8_t reg, uint16_t *buf)
{
const struct mcp23xxx_config *config = dev->config;
if (config->ngpios == 16U) {
reg *= 2;
}
return config->read_fn(dev, reg, buf);
}
/**
* @brief Writes registers of the mcp23xxx.
*
* On the mcp23x08 one 8 bit port will be written.
* On the mcp23x17 two 8 bit ports will be written.
*
* @param dev The mcp23xxx device.
* @param reg Register to be written.
* @param buf The new register value.
*
* @return 0 if successful. Otherwise <0 will be returned.
*/
static int write_port_regs(const struct device *dev, uint8_t reg, uint16_t value)
{
const struct mcp23xxx_config *config = dev->config;
if (config->ngpios == 16U) {
reg *= 2;
}
return config->write_fn(dev, reg, value);
}
/**
* @brief Setup the pin direction.
*
* @param dev The mcp23xxx device.
* @param pin The pin number.
* @param flags Flags of pin or port.
* @return 0 if successful. Otherwise <0 will be returned.
*/
static int setup_pin_dir(const struct device *dev, uint32_t pin, int flags)
{
struct mcp23xxx_drv_data *drv_data = (struct mcp23xxx_drv_data *)dev->data;
uint16_t dir = drv_data->reg_cache.iodir;
uint16_t output = drv_data->reg_cache.gpio;
int ret;
if ((flags & GPIO_OUTPUT) != 0U) {
if ((flags & GPIO_OUTPUT_INIT_HIGH) != 0U) {
output |= BIT(pin);
} else if ((flags & GPIO_OUTPUT_INIT_LOW) != 0U) {
output &= ~BIT(pin);
}
dir &= ~BIT(pin);
} else {
dir |= BIT(pin);
}
ret = write_port_regs(dev, REG_GPIO, output);
if (ret != 0) {
return ret;
}
drv_data->reg_cache.gpio = output;
ret = write_port_regs(dev, REG_IODIR, dir);
if (ret == 0) {
drv_data->reg_cache.iodir = dir;
}
return ret;
}
/**
* @brief Setup pin pull up/pull down.
*
* @param dev The mcp23xxx device.
* @param pin The pin number.
* @param flags Flags of pin or port.
* @return 0 if successful. Otherwise <0 will be returned.
*/
static int setup_pin_pull(const struct device *dev, uint32_t pin, int flags)
{
struct mcp23xxx_drv_data *drv_data = (struct mcp23xxx_drv_data *)dev->data;
uint16_t port;
int ret;
port = drv_data->reg_cache.gppu;
if ((flags & GPIO_PULL_DOWN) != 0U) {
return -ENOTSUP;
}
WRITE_BIT(port, pin, (flags & GPIO_PULL_UP) != 0);
ret = write_port_regs(dev, REG_GPPU, port);
if (ret == 0) {
drv_data->reg_cache.gppu = port;
}
return ret;
}
static int mcp23xxx_pin_cfg(const struct device *dev, gpio_pin_t pin, gpio_flags_t flags)
{
struct mcp23xxx_drv_data *drv_data = (struct mcp23xxx_drv_data *)dev->data;
int ret;
if (k_is_in_isr()) {
return -EWOULDBLOCK;
}
k_sem_take(&drv_data->lock, K_FOREVER);
if ((flags & GPIO_SINGLE_ENDED) != 0U) {
ret = -ENOTSUP;
goto done;
}
ret = setup_pin_dir(dev, pin, flags);
if (ret < 0) {
LOG_ERR("Error setting pin direction (%d)", ret);
goto done;
}
ret = setup_pin_pull(dev, pin, flags);
if (ret < 0) {
LOG_ERR("Error setting pin pull up/pull down (%d)", ret);
goto done;
}
done:
k_sem_give(&drv_data->lock);
return ret;
}
static int mcp23xxx_port_get_raw(const struct device *dev, uint32_t *value)
{
struct mcp23xxx_drv_data *drv_data = (struct mcp23xxx_drv_data *)dev->data;
uint16_t buf;
int ret;
if (k_is_in_isr()) {
return -EWOULDBLOCK;
}
k_sem_take(&drv_data->lock, K_FOREVER);
ret = read_port_regs(dev, REG_GPIO, &buf);
if (ret == 0) {
*value = buf;
}
k_sem_give(&drv_data->lock);
return ret;
}
static int mcp23xxx_port_set_masked_raw(const struct device *dev, uint32_t mask, uint32_t value)
{
struct mcp23xxx_drv_data *drv_data = (struct mcp23xxx_drv_data *)dev->data;
uint16_t buf;
int ret;
if (k_is_in_isr()) {
return -EWOULDBLOCK;
}
k_sem_take(&drv_data->lock, K_FOREVER);
buf = drv_data->reg_cache.gpio;
buf = (buf & ~mask) | (mask & value);
ret = write_port_regs(dev, REG_GPIO, buf);
if (ret == 0) {
drv_data->reg_cache.gpio = buf;
}
k_sem_give(&drv_data->lock);
return ret;
}
static int mcp23xxx_port_set_bits_raw(const struct device *dev, uint32_t mask)
{
return mcp23xxx_port_set_masked_raw(dev, mask, mask);
}
static int mcp23xxx_port_clear_bits_raw(const struct device *dev, uint32_t mask)
{
return mcp23xxx_port_set_masked_raw(dev, mask, 0);
}
static int mcp23xxx_port_toggle_bits(const struct device *dev, uint32_t mask)
{
struct mcp23xxx_drv_data *drv_data = (struct mcp23xxx_drv_data *)dev->data;
uint16_t buf;
int ret;
if (k_is_in_isr()) {
return -EWOULDBLOCK;
}
k_sem_take(&drv_data->lock, K_FOREVER);
buf = drv_data->reg_cache.gpio;
buf ^= mask;
ret = write_port_regs(dev, REG_GPIO, buf);
if (ret == 0) {
drv_data->reg_cache.gpio = buf;
}
k_sem_give(&drv_data->lock);
return ret;
}
static int mcp23xxx_pin_interrupt_configure(const struct device *dev, gpio_pin_t pin,
enum gpio_int_mode mode, enum gpio_int_trig trig)
{
return -ENOTSUP;
}
const struct gpio_driver_api gpio_mcp23xxx_api_table = {
.pin_configure = mcp23xxx_pin_cfg,
.port_get_raw = mcp23xxx_port_get_raw,
.port_set_masked_raw = mcp23xxx_port_set_masked_raw,
.port_set_bits_raw = mcp23xxx_port_set_bits_raw,
.port_clear_bits_raw = mcp23xxx_port_clear_bits_raw,
.port_toggle_bits = mcp23xxx_port_toggle_bits,
.pin_interrupt_configure = mcp23xxx_pin_interrupt_configure,
};
/**
* @brief Initialization function of MCP23XXX
*
* @param dev Device struct.
* @return 0 if successful. Otherwise <0 is returned.
*/
int gpio_mcp23xxx_init(const struct device *dev)
{
const struct mcp23xxx_config *config = dev->config;
struct mcp23xxx_drv_data *drv_data = (struct mcp23xxx_drv_data *)dev->data;
int err;
if (config->ngpios != 8U && config->ngpios != 16U) {
LOG_ERR("Invalid value ngpios=%u. Expected 8 or 16!", config->ngpios);
return -EINVAL;
}
err = config->bus_fn(dev);
if (err < 0) {
return err;
}
k_sem_init(&drv_data->lock, 1, 1);
return 0;
}

View file

@ -0,0 +1,90 @@
/*
* Copyright (c) 2021 metraTec GmbH
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file Header file for the MCP23Xxx driver.
*/
#ifndef ZEPHYR_DRIVERS_GPIO_GPIO_MCP23XXX_H_
#define ZEPHYR_DRIVERS_GPIO_GPIO_MCP23XXX_H_
#include <kernel.h>
#include <drivers/gpio.h>
#ifdef CONFIG_GPIO_MCP230XX
#include <drivers/i2c.h>
#endif /* CONFIG_GPIO_MCP230XX */
#ifdef CONFIG_GPIO_MCP23SXX
#include <drivers/spi.h>
#endif /* CONFIG_GPIO_MCP23SXX */
/* Register definitions */
#define REG_IODIR 0x00
#define REG_IPOL 0x01
#define REG_GPINTEN 0x02
#define REG_DEFVAL 0x03
#define REG_INTCON 0x04
#define REG_IOCON 0x05
#define REG_GPPU 0x06
#define REG_INTF 0x07
#define REG_INTCAP 0x08
#define REG_GPIO 0x09
#define REG_IKAT 0x0A
#define MCP23SXX_ADDR 0x40
#define MCP23SXX_READBIT 0x01
typedef int (*mcp23xxx_read_port_regs)(const struct device *dev, uint8_t reg, uint16_t *buf);
typedef int (*mcp23xxx_write_port_regs)(const struct device *dev, uint8_t reg, uint16_t value);
typedef int (*mcp23xxx_bus_is_ready)(const struct device *dev);
/** Configuration data */
struct mcp23xxx_config {
/* gpio_driver_config needs to be first */
struct gpio_driver_config config;
/** I2C device */
union {
#ifdef CONFIG_GPIO_MCP230XX
struct i2c_dt_spec i2c;
#endif /* CONFIG_GPIO_MCP230XX */
#ifdef CONFIG_GPIO_MCP23SXX
struct spi_dt_spec spi;
#endif /* CONFIG_GPIO_MCP23SXX */
} bus;
uint8_t ngpios;
mcp23xxx_read_port_regs read_fn;
mcp23xxx_write_port_regs write_fn;
mcp23xxx_bus_is_ready bus_fn;
};
/** Runtime driver data */
struct mcp23xxx_drv_data {
/* gpio_driver_data needs to be first */
struct gpio_driver_data data;
struct k_sem lock;
struct {
uint16_t iodir;
uint16_t ipol;
uint16_t gpinten;
uint16_t defval;
uint16_t intcon;
uint16_t iocon;
uint16_t gppu;
uint16_t intf;
uint16_t intcap;
uint16_t gpio;
uint16_t olat;
} reg_cache;
};
extern const struct gpio_driver_api gpio_mcp23xxx_api_table;
int gpio_mcp23xxx_init(const struct device *dev);
#endif /* ZEPHYR_DRIVERS_GPIO_GPIO_MCP23XXX_H_ */

View file

@ -1,26 +0,0 @@
#
# Copyright (c) 2021 metraTec GmbH
#
# SPDX-License-Identifier: Apache-2.0
#
description: |
This is a representation of the Microchip MCP23017 I2C Gpio Expander.
compatible: "microchip,mcp23017"
include: [gpio-controller.yaml, i2c-device.yaml]
properties:
label:
required: true
ngpios:
const: 16
required: true
description: |
Number of gpios supported by the chip.
gpio-cells:
- pin
- flags

View file

@ -5,9 +5,9 @@
#
description: |
This is a representation of the Microchip MCP23008 I2C Gpio Expander.
This is a representation of the Microchip MCP230xx I2C Gpio Expander.
compatible: "microchip,mcp23008"
compatible: "microchip,mcp230xx"
include: [gpio-controller.yaml, i2c-device.yaml]
@ -16,7 +16,10 @@ properties:
required: true
ngpios:
const: 8
type: int
enum:
- 8
- 16
required: true
description: |
Number of gpios supported by the chip.

View file

@ -0,0 +1,32 @@
#
# Copyright (c) 2020 Geanix ApS
# Copyright (c) 2021 Peter Johanson
#
# SPDX-License-Identifier: Apache-2.0
#
description: |
This is a representation of the Microchip MCP23SXX SPI Gpio Expander.
compatible: "microchip,mcp23sxx"
include: [gpio-controller.yaml, spi-device.yaml]
properties:
label:
required: true
"#gpio-cells":
const: 2
ngpios:
type: int
required: true
enum:
- 8
- 16
description: Number of gpios supported
gpio-cells:
- pin
- flags

View file

@ -72,6 +72,15 @@
nint-gpios = <&test_gpio 0 0>;
};
test_i2c_mcp230xx: mcp230xx@0 {
compatible = "microchip,mcp230xx";
label = "MCP230XX";
reg = <0x0>;
gpio-controller;
#gpio-cells = <2>;
ngpios = <16>;
};
test_i2c_fxl6408: fxl6408@43 {
status = "okay";
compatible = "fcs,fxl6408";
@ -160,7 +169,7 @@
clock-frequency = <2000000>;
/* one entry for every devices at spi.dtsi */
cs-gpios = <&test_gpio 0 0>;
cs-gpios = <&test_gpio 0 0 &test_gpio 0 0>;
test_spi_mcp23s17: mcp23s17@0 {
compatible = "microchip,mcp23s17";
@ -171,6 +180,16 @@
#gpio-cells = <2>;
ngpios = <16>;
};
test_spi_mcp23sxx: mcp23sxx@0 {
compatible = "microchip,mcp23sxx";
label = "GPIO_E1";
spi-max-frequency = <0>;
reg = <0x0>;
gpio-controller;
#gpio-cells = <2>;
ngpios = <16>;
};
};
};
};

View file

@ -9,3 +9,5 @@ CONFIG_GPIO_FXL6408=y
CONFIG_SPI=y
CONFIG_GPIO_MCP23S17=y
CONFIG_GPIO_NCT38XX=y
CONFIG_GPIO_MCP230XX=y
CONFIG_GPIO_MCP23SXX=y