drivers: gpio: Add MAX14906 industrial input/output

MAX14906 in 4 channel I/O with advanced diagnostic.
In SPI communication diagnostic status transmitted on every
READ/WRITE which includes generic status of chip.
Configuration both on global level and on per channel bases.
Diagnostics includes :
 * Thermal overload
 * current limit
 * open wire detection
 * short to VDD
 * Above VDD
 * Safe DEmagnitization fault
 * VDD warning
 * VDD low
 * SPI/CRC Error
 * WDog Error
 * Loss GND

Add app.overlay for MAX14906 driver.

Tested with adopted basic/button and basic/blinky sample.

Signed-off-by: Stoyan Bogdanov <sbogdanov@baylibre.com>
This commit is contained in:
Stoyan Bogdanov 2024-06-14 17:41:13 +03:00 committed by Carles Cufí
commit 71149fd47a
7 changed files with 1016 additions and 0 deletions

View file

@ -40,6 +40,7 @@ zephyr_library_sources_ifdef(CONFIG_GPIO_KSCAN_ITE_IT8XXX2 gpio_kscan_ite_it8xxx
zephyr_library_sources_ifdef(CONFIG_GPIO_LITEX gpio_litex.c)
zephyr_library_sources_ifdef(CONFIG_GPIO_LMP90XXX gpio_lmp90xxx.c)
zephyr_library_sources_ifdef(CONFIG_GPIO_LPC11U6X gpio_lpc11u6x.c)
zephyr_library_sources_ifdef(CONFIG_GPIO_MAX14906 gpio_max14906.c)
zephyr_library_sources_ifdef(CONFIG_GPIO_MAX32 gpio_max32.c)
zephyr_library_sources_ifdef(CONFIG_GPIO_MCHP_MSS gpio_mchp_mss.c)
zephyr_library_sources_ifdef(CONFIG_GPIO_MCP230XX gpio_mcp230xx.c)

View file

@ -131,6 +131,7 @@ source "drivers/gpio/Kconfig.it8xxx2"
source "drivers/gpio/Kconfig.litex"
source "drivers/gpio/Kconfig.lmp90xxx"
source "drivers/gpio/Kconfig.lpc11u6x"
source "drivers/gpio/Kconfig.max14906"
source "drivers/gpio/Kconfig.max32"
source "drivers/gpio/Kconfig.mchp_mss"
source "drivers/gpio/Kconfig.mcp23xxx"

View file

@ -0,0 +1,20 @@
# Copyright (c) 2024 Analog Devices Inc.
# Copyright (c) 2024 BayLibre SAS
# SPDX-License-Identifier: Apache-2.0
# MAX14906 GPIO configuration options
menuconfig GPIO_MAX14906
bool "MAX14906 GPIO driver"
default y
depends on DT_HAS_ADI_MAX14906_GPIO_ENABLED && SPI
help
Enabe MAX14906 quad industrial digital
input/output with diagnostics
config GPIO_MAX14906_INIT_PRIORITY
int "Driver init priority"
default 99
depends on GPIO_MAX14906
help
Device driver initialization priority.

View file

@ -0,0 +1,495 @@
/*
* Copyright (c) 2024 Analog Devices Inc.
* Copyright (c) 2024 Baylibre SAS
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <zephyr/drivers/gpio.h>
#include <zephyr/drivers/spi.h>
#include <zephyr/kernel.h>
#include <zephyr/sys/byteorder.h>
#define LOG_LEVEL CONFIG_GPIO_LOG_LEVEL
#include <zephyr/logging/log.h>
LOG_MODULE_REGISTER(gpio_max14906);
#include <zephyr/drivers/gpio/gpio_utils.h>
#include "gpio_max14906.h"
#include "gpio_max149x6.h"
#define DT_DRV_COMPAT adi_max14906_gpio
static int gpio_max14906_diag_chan_get(const struct device *dev);
static int max14906_pars_spi_diag(const struct device *dev, uint8_t *rx_diag_buff, uint8_t rw)
{
struct max14906_data *data = dev->data;
int ret = 0;
if (rx_diag_buff[0]) {
LOG_ERR("[DIAG] MAX14906 in SPI diag - error detected\n");
data->glob.interrupt.reg_bits.SHT_VDD_FAULT = MAX149X6_GET_BIT(rx_diag_buff[0], 5);
data->glob.interrupt.reg_bits.ABOVE_VDD_FAULT =
MAX149X6_GET_BIT(rx_diag_buff[0], 4);
data->glob.interrupt.reg_bits.OW_OFF_FAULT = MAX149X6_GET_BIT(rx_diag_buff[0], 3);
data->glob.interrupt.reg_bits.CURR_LIM = MAX149X6_GET_BIT(rx_diag_buff[0], 2);
data->glob.interrupt.reg_bits.OVER_LD_FAULT = MAX149X6_GET_BIT(rx_diag_buff[0], 1);
uint8_t globlf = MAX149X6_GET_BIT(rx_diag_buff[0], 0);
ret = -EIO;
PRINT_ERR(data->glob.interrupt.reg_bits.SHT_VDD_FAULT);
PRINT_ERR(data->glob.interrupt.reg_bits.ABOVE_VDD_FAULT);
PRINT_ERR(data->glob.interrupt.reg_bits.OW_OFF_FAULT);
PRINT_ERR(data->glob.interrupt.reg_bits.CURR_LIM);
PRINT_ERR(data->glob.interrupt.reg_bits.OVER_LD_FAULT);
PRINT_ERR(globlf);
}
if (rw == MAX149x6_WRITE && (rx_diag_buff[1] & 0x0f)) {
/* +-----------------------------------------------------------------------+
* | LSB BYTE 2 MSB |
* +--------+--------+--------+--------+--------+--------+--------+--------+
* | BIT0 | BIT1 | BIT2 | BIT3 | BIT4 | BIT5 | BIT6 | BIT7 |
* +--------+--------+--------+--------+--------+--------+--------+--------+
* | Fault1 | Fault2 | Fault3 | Fault4 | DiLvl1 | DiLvl2 | DiLvl3 | DiLvl4 |
* +--------+--------+--------+--------+--------+--------+--------+--------+
*/
LOG_ERR("[DIAG] Flt1[%x] Flt2[%x] Flt3[%x] Flt4[%x]",
MAX149X6_GET_BIT(rx_diag_buff[1], 0), MAX149X6_GET_BIT(rx_diag_buff[1], 1),
MAX149X6_GET_BIT(rx_diag_buff[1], 2), MAX149X6_GET_BIT(rx_diag_buff[1], 3));
if (rx_diag_buff[1] & 0x0f) {
LOG_ERR("[DIAG] gpio_max14906_diag_chan_get(%x)\n", rx_diag_buff[1] & 0x0f);
ret = gpio_max14906_diag_chan_get(dev);
}
}
return ret;
}
static int max14906_reg_trans_spi_diag(const struct device *dev, uint8_t addr, uint8_t tx,
uint8_t rw)
{
const struct max14906_config *config = dev->config;
uint8_t rx_diag_buff[2];
if (!gpio_pin_get_dt(&config->fault_gpio)) {
LOG_ERR("[FAULT] pin triggered");
}
uint8_t ret = max149x6_reg_transceive(dev, addr, tx, rx_diag_buff, rw);
if (max14906_pars_spi_diag(dev, rx_diag_buff, rw)) {
ret = -EIO;
}
return ret;
}
#define MAX14906_REG_READ(dev, addr) max14906_reg_trans_spi_diag(dev, addr, 0, MAX149x6_READ)
#define MAX14906_REG_WRITE(dev, addr, val) \
max14906_reg_trans_spi_diag(dev, addr, val, MAX149x6_WRITE)
/*
* @brief Register update function for MAX14906
*
* @param dev - MAX149x6 device.
* @param addr - Register valueto wich data is updated.
* @param mask - Corresponding mask to the data that will be updated.
* @param val - Updated value to be written in the register at update.
* @return 0 in case of success, negative error code otherwise.
*/
static int max14906_reg_update(const struct device *dev, uint8_t addr, uint8_t mask, uint8_t val)
{
int ret;
uint32_t reg_val = 0;
ret = MAX14906_REG_READ(dev, addr);
reg_val = ret;
reg_val &= ~mask;
reg_val |= mask & val;
return MAX14906_REG_WRITE(dev, addr, reg_val);
}
static int gpio_max14906_diag_chan_get(const struct device *dev)
{
const struct max14906_config *config = dev->config;
struct max14906_data *data = dev->data;
int ret;
if (!gpio_pin_get_dt(&config->fault_gpio)) {
LOG_ERR("[DIAG] FAULT flag is rised");
}
data->glob.interrupt.reg_raw =
max149x6_reg_transceive(dev, MAX14906_INT_REG, 0, NULL, MAX149x6_READ);
if (data->glob.interrupt.reg_raw) {
if (data->glob.interrupt.reg_bits.OVER_LD_FAULT ||
data->glob.interrupt.reg_bits.CURR_LIM) {
data->chan.ovr_ld.reg_raw = max149x6_reg_transceive(
dev, MAX14906_OVR_LD_REG, 0, NULL, MAX149x6_READ);
}
if (data->glob.interrupt.reg_bits.OW_OFF_FAULT ||
data->glob.interrupt.reg_bits.ABOVE_VDD_FAULT) {
data->chan.opn_wir.reg_raw = max149x6_reg_transceive(
dev, MAX14906_OPN_WIR_FLT_REG, 0, NULL, MAX149x6_READ);
}
if (data->glob.interrupt.reg_bits.SHT_VDD_FAULT) {
data->chan.sht_vdd.reg_raw = max149x6_reg_transceive(
dev, MAX14906_SHT_VDD_FLT_REG, 0, NULL, MAX149x6_READ);
}
if (data->glob.interrupt.reg_bits.DE_MAG_FAULT) {
data->chan.doi_level.reg_raw = max149x6_reg_transceive(
dev, MAX14906_DOILEVEL_REG, 0, NULL, MAX149x6_READ);
if (data->chan.doi_level.reg_raw) {
PRINT_ERR(data->chan.doi_level.reg_bits.VDDOK_FAULT1);
PRINT_ERR(data->chan.doi_level.reg_bits.VDDOK_FAULT2);
PRINT_ERR(data->chan.doi_level.reg_bits.VDDOK_FAULT3);
PRINT_ERR(data->chan.doi_level.reg_bits.VDDOK_FAULT4);
PRINT_ERR(data->chan.doi_level.reg_bits.SAFE_DAMAGE_F1);
PRINT_ERR(data->chan.doi_level.reg_bits.SAFE_DAMAGE_F2);
PRINT_ERR(data->chan.doi_level.reg_bits.SAFE_DAMAGE_F3);
PRINT_ERR(data->chan.doi_level.reg_bits.SAFE_DAMAGE_F4);
}
}
if (data->glob.interrupt.reg_bits.SUPPLY_ERR) {
data->glob.glob_err.reg_raw = max149x6_reg_transceive(
dev, MAX14906_GLOB_ERR_REG, 0, NULL, MAX149x6_READ);
PRINT_ERR(data->glob.glob_err.reg_bits.VINT_UV);
PRINT_ERR(data->glob.glob_err.reg_bits.V5_UVLO);
PRINT_ERR(data->glob.glob_err.reg_bits.VDD_LOW);
PRINT_ERR(data->glob.glob_err.reg_bits.VDD_WARN);
PRINT_ERR(data->glob.glob_err.reg_bits.VDD_UVLO);
PRINT_ERR(data->glob.glob_err.reg_bits.THRMSHUTD);
PRINT_ERR(data->glob.glob_err.reg_bits.LOSSGND);
PRINT_ERR(data->glob.glob_err.reg_bits.WDOG_ERR);
}
if (data->glob.interrupt.reg_bits.COM_ERR) {
LOG_ERR("[DIAG] MAX14906 Communication Error");
}
}
ret = data->chan.doi_level.reg_raw | data->chan.ovr_ld.reg_raw |
data->chan.opn_wir.reg_raw | data->chan.sht_vdd.reg_raw;
return ret;
}
/**
* @brief Configure a channel's function.
* @param desc - device descriptor for the MAX14906
* @param ch - channel index (0 based).
* @param function - channel configuration (input, output or high-z).
* @return 0 in case of success, negative error code otherwise
*/
static int max14906_ch_func(const struct device *dev, uint32_t ch, enum max14906_function function)
{
uint8_t setout_reg_val;
switch (function) {
case MAX14906_HIGH_Z:
setout_reg_val = MAX14906_IN;
max14906_reg_update(dev, MAX14906_CONFIG_DO_REG, MAX14906_DO_MASK(ch),
FIELD_PREP(MAX14906_DO_MASK(ch), MAX14906_PUSH_PULL));
break;
case MAX14906_IN:
setout_reg_val = MAX14906_IN;
max14906_reg_update(dev, MAX14906_CONFIG_DO_REG, MAX14906_DO_MASK(ch),
FIELD_PREP(MAX14906_DO_MASK(ch), MAX14906_HIGH_SIDE));
break;
case MAX14906_OUT:
setout_reg_val = MAX14906_OUT;
break;
default:
return -EINVAL;
}
return max14906_reg_update(dev, MAX14906_SETOUT_REG, MAX14906_CH_DIR_MASK(ch),
FIELD_PREP(MAX14906_CH_DIR_MASK(ch), setout_reg_val));
}
static int gpio_max14906_port_set_bits_raw(const struct device *dev, gpio_port_pins_t pins)
{
int ret;
uint32_t reg_val = 0;
ret = MAX14906_REG_READ(dev, MAX14906_SETOUT_REG);
reg_val = ret | (pins & 0x0f);
return MAX14906_REG_WRITE(dev, MAX14906_SETOUT_REG, reg_val);
}
static int gpio_max14906_port_clear_bits_raw(const struct device *dev, gpio_port_pins_t pins)
{
int ret;
uint32_t reg_val = 0;
ret = MAX14906_REG_READ(dev, MAX14906_SETOUT_REG);
reg_val = ret & (0xf0 & ~pins);
return MAX14906_REG_WRITE(dev, MAX14906_SETOUT_REG, reg_val);
}
static int gpio_max14906_config(const struct device *dev, gpio_pin_t pin, gpio_flags_t flags)
{
int err = 0;
if ((flags & (GPIO_INPUT | GPIO_OUTPUT)) == GPIO_DISCONNECTED) {
return -ENOTSUP;
}
if ((flags & GPIO_SINGLE_ENDED) != 0) {
return -ENOTSUP;
}
if ((flags & (GPIO_PULL_UP | GPIO_PULL_DOWN)) != 0) {
return -ENOTSUP;
}
if (flags & GPIO_INT_ENABLE) {
return -ENOTSUP;
}
switch (flags & GPIO_DIR_MASK) {
case GPIO_INPUT:
max14906_ch_func(dev, (uint32_t)pin, MAX14906_IN);
LOG_DBG("SETUP AS INPUT %d", pin);
break;
case GPIO_OUTPUT:
max14906_ch_func(dev, (uint32_t)pin, MAX14906_OUT);
LOG_DBG("SETUP AS OUTPUT %d", pin);
break;
default:
LOG_ERR("On MAX14906 only input option is available!");
err = -ENOTSUP;
break;
}
return err;
}
static int gpio_max14906_port_get_raw(const struct device *dev, gpio_port_value_t *value)
{
/* We care only for first 4 bits of the reg.
* Next set of bits is for direction.
* NOTE : in case and only if pin is INPUT DOILEVEL reg bits 0-4 shows PIN state.
* In case PIN is OUTPUT same bits show VDDOKFault state.
*/
*value = (0x0f & MAX14906_REG_READ(dev, MAX14906_DOILEVEL_REG));
return 0;
}
static int gpio_max14906_port_toggle_bits(const struct device *dev, gpio_port_pins_t pins)
{
int ret;
uint32_t reg_val, direction, state, new_reg_val;
ret = MAX14906_REG_READ(dev, MAX14906_SETOUT_REG);
direction = ret & 0xf0;
state = ret & 0x0f;
reg_val = state ^ pins;
new_reg_val = direction | (0x0f & state);
return MAX14906_REG_WRITE(dev, MAX14906_SETOUT_REG, new_reg_val);
}
static int gpio_max14906_clean_on_power(const struct device *dev)
{
int ret;
/* Clear the latched faults generated at power up */
ret = MAX14906_REG_READ(dev, MAX14906_OPN_WIR_FLT_REG);
if (ret < 0) {
LOG_ERR("Error reading MAX14906_OPN_WIR_FLT_REG");
goto err_clean_on_power_max14906;
}
ret = MAX14906_REG_READ(dev, MAX14906_OVR_LD_REG);
if (ret < 0) {
LOG_ERR("Error reading MAX14906_OVR_LD_REG");
goto err_clean_on_power_max14906;
}
ret = MAX14906_REG_READ(dev, MAX14906_SHT_VDD_FLT_REG);
if (ret < 0) {
LOG_ERR("Error reading MAX14906_SHD_VDD_FLT_REG");
goto err_clean_on_power_max14906;
}
ret = MAX14906_REG_READ(dev, MAX14906_GLOB_ERR_REG);
if (ret < 0) {
LOG_ERR("Error reading MAX14906_GLOBAL_FLT_REG");
goto err_clean_on_power_max14906;
}
err_clean_on_power_max14906:
return ret;
}
static int gpio_max14906_config_diag(const struct device *dev)
{
const struct max14906_data *data = dev->data;
const struct max14906_config *config = dev->config;
/* Set Config1 and Config2 regs */
MAX14906_REG_WRITE(dev, MAX14906_CONFIG1_REG, config->config1.reg_raw);
MAX14906_REG_WRITE(dev, MAX14906_CONFIG2_REG, config->config2.reg_raw);
/* Configure per channel diagnostics */
MAX14906_REG_WRITE(dev, MAX14906_OPN_WR_EN_REG, data->chan_en.opn_wr_en.reg_raw);
MAX14906_REG_WRITE(dev, MAX14906_SHT_VDD_EN_REG, data->chan_en.sht_vdd_en.reg_raw);
return 0;
}
static int gpio_max14906_init(const struct device *dev)
{
const struct max14906_config *config = dev->config;
int err = 0;
LOG_DBG(" --- GPIO MAX14906 init IN ---");
if (!spi_is_ready_dt(&config->spi)) {
LOG_ERR("SPI bus is not ready\n");
return -ENODEV;
}
/* setup READY gpio - normal low */
if (!gpio_is_ready_dt(&config->ready_gpio)) {
LOG_ERR("READY GPIO device not ready");
return -ENODEV;
}
err = gpio_pin_configure_dt(&config->ready_gpio, GPIO_INPUT);
if (err < 0) {
LOG_ERR("Failed to configure reset GPIO");
return err;
}
/* setup FAULT gpio - normal high */
if (!gpio_is_ready_dt(&config->fault_gpio)) {
LOG_ERR("FAULT GPIO device not ready");
return -ENODEV;
}
err = gpio_pin_configure_dt(&config->fault_gpio, GPIO_INPUT);
if (err < 0) {
LOG_ERR("Failed to configure DC GPIO");
return err;
}
/* setup LATCH gpio - normal high */
if (!gpio_is_ready_dt(&config->sync_gpio)) {
LOG_ERR("SYNC GPIO device not ready");
return -ENODEV;
}
err = gpio_pin_configure_dt(&config->sync_gpio, GPIO_OUTPUT_INACTIVE);
if (err < 0) {
LOG_ERR("Failed to configure busy GPIO");
return err;
}
/* setup LATCH gpio - normal high */
if (!gpio_is_ready_dt(&config->en_gpio)) {
LOG_ERR("SYNC GPIO device not ready");
return -ENODEV;
}
err = gpio_pin_configure_dt(&config->en_gpio, GPIO_OUTPUT_INACTIVE);
if (err < 0) {
LOG_ERR("Failed to configure busy GPIO");
return err;
}
gpio_pin_set_dt(&config->en_gpio, 1);
gpio_pin_set_dt(&config->sync_gpio, 1);
LOG_DBG("[GPIO] FAULT - %d\n", gpio_pin_get_dt(&config->fault_gpio));
LOG_DBG("[GPIO] READY - %d\n", gpio_pin_get_dt(&config->ready_gpio));
LOG_DBG("[GPIO] SYNC - %d\n", gpio_pin_get_dt(&config->sync_gpio));
LOG_DBG("[GPIO] EN - %d\n", gpio_pin_get_dt(&config->en_gpio));
int ret = gpio_max14906_clean_on_power(dev);
MAX14906_REG_WRITE(dev, MAX14906_SETOUT_REG, 0);
gpio_max14906_config_diag(dev);
LOG_DBG(" --- GPIO MAX14906 init OUT ---");
return ret;
}
static const struct gpio_driver_api gpio_max14906_api = {
.pin_configure = gpio_max14906_config,
.port_get_raw = gpio_max14906_port_get_raw,
.port_set_bits_raw = gpio_max14906_port_set_bits_raw,
.port_clear_bits_raw = gpio_max14906_port_clear_bits_raw,
.port_toggle_bits = gpio_max14906_port_toggle_bits,
};
#define GPIO_MAX14906_DEVICE(id) \
static const struct max14906_config max14906_##id##_cfg = { \
.spi = SPI_DT_SPEC_INST_GET(id, SPI_OP_MODE_MASTER | SPI_WORD_SET(8U), 0U), \
.ready_gpio = GPIO_DT_SPEC_INST_GET(id, drdy_gpios), \
.fault_gpio = GPIO_DT_SPEC_INST_GET(id, fault_gpios), \
.sync_gpio = GPIO_DT_SPEC_INST_GET(id, sync_gpios), \
.en_gpio = GPIO_DT_SPEC_INST_GET(id, en_gpios), \
.crc_en = DT_INST_PROP(id, crc_en), \
.config1.reg_bits.FLED_SET = DT_INST_PROP(id, fled_set), \
.config1.reg_bits.SLED_SET = DT_INST_PROP(id, sled_set), \
.config1.reg_bits.FLED_STRETCH = DT_INST_PROP(id, fled_stretch), \
.config1.reg_bits.FFILTER_EN = DT_INST_PROP(id, ffilter_en), \
.config1.reg_bits.FILTER_LONG = DT_INST_PROP(id, filter_long), \
.config1.reg_bits.FLATCH_EN = DT_INST_PROP(id, flatch_en), \
.config1.reg_bits.LED_CURR_LIM = DT_INST_PROP(id, led_cur_lim), \
.config2.reg_bits.VDD_ON_THR = DT_INST_PROP(id, vdd_on_thr), \
.config2.reg_bits.SYNCH_WD_EN = DT_INST_PROP(id, synch_wd_en), \
.config2.reg_bits.SHT_VDD_THR = DT_INST_PROP(id, sht_vdd_thr), \
.config2.reg_bits.OW_OFF_CS = DT_INST_PROP(id, ow_off_cs), \
.config2.reg_bits.WD_TO = DT_INST_PROP(id, wd_to), \
.pkt_size = (DT_INST_PROP(id, crc_en) & 0x1) ? 3 : 2, \
.spi_addr = DT_INST_PROP(id, spi_addr), \
}; \
\
static struct max14906_data max14906_##id##_data = { \
.chan_en.opn_wr_en.reg_bits = \
{ \
.OW_OFF_EN1 = DT_INST_PROP_BY_IDX(id, ow_en, 0), \
.OW_OFF_EN2 = DT_INST_PROP_BY_IDX(id, ow_en, 1), \
.OW_OFF_EN3 = DT_INST_PROP_BY_IDX(id, ow_en, 2), \
.OW_OFF_EN4 = DT_INST_PROP_BY_IDX(id, ow_en, 3), \
.GDRV_EN1 = DT_INST_PROP_BY_IDX(id, gdrv_en, 0), \
.GDRV_EN1 = DT_INST_PROP_BY_IDX(id, gdrv_en, 1), \
.GDRV_EN2 = DT_INST_PROP_BY_IDX(id, gdrv_en, 2), \
.GDRV_EN3 = DT_INST_PROP_BY_IDX(id, gdrv_en, 3), \
}, \
.chan_en.sht_vdd_en.reg_bits = \
{ \
.VDD_OV_EN1 = DT_INST_PROP_BY_IDX(id, vdd_ov_en, 0), \
.VDD_OV_EN2 = DT_INST_PROP_BY_IDX(id, vdd_ov_en, 1), \
.VDD_OV_EN3 = DT_INST_PROP_BY_IDX(id, vdd_ov_en, 2), \
.VDD_OV_EN4 = DT_INST_PROP_BY_IDX(id, vdd_ov_en, 3), \
.SH_VDD_EN1 = DT_INST_PROP_BY_IDX(id, sh_vdd_en, 0), \
.SH_VDD_EN2 = DT_INST_PROP_BY_IDX(id, sh_vdd_en, 1), \
.SH_VDD_EN3 = DT_INST_PROP_BY_IDX(id, sh_vdd_en, 2), \
.SH_VDD_EN4 = DT_INST_PROP_BY_IDX(id, sh_vdd_en, 3), \
}, \
}; \
\
DEVICE_DT_INST_DEFINE(id, &gpio_max14906_init, NULL, &max14906_##id##_data, \
&max14906_##id##_cfg, POST_KERNEL, \
CONFIG_GPIO_MAX14906_INIT_PRIORITY, &gpio_max14906_api);
DT_INST_FOREACH_STATUS_OKAY(GPIO_MAX14906_DEVICE)

View file

@ -0,0 +1,321 @@
/*
* Copyright (c) 2024 Analog Devices Inc.
* Copyright (c) 2024 Baylibre SAS
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_DRIVERS_GPIO_GPIO_MAX14906_H_
#define ZEPHYR_DRIVERS_GPIO_GPIO_MAX14906_H_
#define MAX14906_FAULT2_ENABLES 5
#define MAX14906_CHANNELS 4
#define MAX14916_CHANNELS 8
#define MAX149x6_MAX_PKT_SIZE 3
#define MAX14906_SETOUT_REG 0x0
#define MAX14906_SETLED_REG 0x1
#define MAX14906_DOILEVEL_REG 0x2
#define MAX14906_INT_REG 0x3
#define MAX14906_OVR_LD_REG 0x4
#define MAX14906_OPN_WIR_FLT_REG 0x5
#define MAX14906_SHT_VDD_FLT_REG 0x6
#define MAX14906_GLOB_ERR_REG 0x7
#define MAX14906_OPN_WR_EN_REG 0x8
#define MAX14906_SHT_VDD_EN_REG 0x9
#define MAX14906_CONFIG1_REG 0xA
#define MAX14906_CONFIG2_REG 0xB
#define MAX14906_CONFIG_DI_REG 0xC
#define MAX14906_CONFIG_DO_REG 0xD
#define MAX14906_CONFIG_CURR_LIM 0xE
#define MAX14906_CONFIG_MASK 0xF
#define MAX149x6_CHIP_ADDR_MASK GENMASK(7, 6)
#define MAX149x6_ADDR_MASK GENMASK(4, 1)
#define MAX149x6_RW_MASK BIT(0)
/* DoiLevel register */
#define MAX14906_DOI_LEVEL_MASK(x) BIT(x)
/* SetOUT register */
#define MAX14906_HIGHO_MASK(x) BIT(x)
#define MAX14906_DO_MASK(x) (GENMASK(1, 0) << (2 * (x)))
#define MAX14906_CH_DIR_MASK(x) BIT((x) + 4)
#define MAX14906_CH(x) (x)
#define MAX14906_IEC_TYPE_MASK BIT(7)
#define MAX14906_CL_MASK(x) (GENMASK(1, 0) << (2 * (x)))
/**
* @brief Hardwired device address
*/
enum max149x6_spi_addr {
MAX14906_ADDR_0, /* A0=0, A1=0 */
MAX14906_ADDR_1, /* A0=1, A1=0 */
MAX14906_ADDR_2, /* A0=0, A1=1 */
MAX14906_ADDR_3, /* A0=1, A1=1 */
};
enum max14906_iec_type {
MAX14906_TYPE_1_3,
MAX14906_TYPE_2,
};
/**
* @brief Channel configuration options.
*/
enum max14906_function {
MAX14906_OUT,
MAX14906_IN,
MAX14906_HIGH_Z
};
/**
* @brief Configuration options for the output driver (on each channel).
*/
enum max14906_do_mode {
MAX14906_HIGH_SIDE,
MAX14906_HIGH_SIDE_INRUSH,
MAX14906_PUSH_PULL_CLAMP,
MAX14906_PUSH_PULL
};
/**
* @brief Current limit options for output channels.
*/
enum max14906_cl {
MAX14906_CL_600,
MAX14906_CL_130,
MAX14906_CL_300,
MAX14906_CL_1200,
};
union max14906_doi_level {
uint8_t reg_raw;
struct {
uint8_t VDDOK_FAULT1: 1; /* BIT0 */
uint8_t VDDOK_FAULT2: 1;
uint8_t VDDOK_FAULT3: 1;
uint8_t VDDOK_FAULT4: 1;
uint8_t SAFE_DAMAGE_F1: 1;
uint8_t SAFE_DAMAGE_F2: 1;
uint8_t SAFE_DAMAGE_F3: 1;
uint8_t SAFE_DAMAGE_F4: 1; /* BIT7 */
} reg_bits;
};
union max14906_interrupt {
uint8_t reg_raw;
struct {
uint8_t OVER_LD_FAULT: 1; /* BIT0 */
uint8_t CURR_LIM: 1;
uint8_t OW_OFF_FAULT: 1;
uint8_t ABOVE_VDD_FAULT: 1;
uint8_t SHT_VDD_FAULT: 1;
uint8_t DE_MAG_FAULT: 1;
uint8_t SUPPLY_ERR: 1;
uint8_t COM_ERR: 1; /* BIT7 */
} reg_bits;
};
union max14906_ovr_ld_chf {
uint8_t reg_raw;
struct {
uint8_t OVL1: 1; /* BIT0 */
uint8_t OVL2: 1;
uint8_t OVL3: 1;
uint8_t OVL4: 1;
uint8_t CL1: 1;
uint8_t CL2: 1;
uint8_t CL3: 1;
uint8_t CL4: 1; /* BIT7 */
} reg_bits;
};
union max14906_opn_wir_chf {
uint8_t reg_raw;
struct {
uint8_t OW_OFF1: 1; /* BIT0 */
uint8_t OW_OFF2: 1;
uint8_t OW_OFF3: 1;
uint8_t OW_OFF4: 1;
uint8_t ABOVE_VDD1: 1;
uint8_t ABOVE_VDD2: 1;
uint8_t ABOVE_VDD3: 1;
uint8_t ABOVE_VDD4: 1; /* BIT7 */
} reg_bits;
};
union max14906_sht_vdd_chf {
uint8_t reg_raw;
struct {
uint8_t SHVDD1: 1; /* BIT0 */
uint8_t SHVDD2: 1;
uint8_t SHVDD3: 1;
uint8_t SHVDD4: 1;
uint8_t VDDOV1: 1;
uint8_t VDDOV2: 1;
uint8_t VDDOV3: 1;
uint8_t VDDOV4: 1; /* BIT7 */
} reg_bits;
};
union max14906_global_err {
uint8_t reg_raw;
struct {
uint8_t VINT_UV: 1; /* BIT0 */
uint8_t V5_UVLO: 1;
uint8_t VDD_LOW: 1;
uint8_t VDD_WARN: 1;
uint8_t VDD_UVLO: 1;
uint8_t THRMSHUTD: 1;
uint8_t LOSSGND: 1;
uint8_t WDOG_ERR: 1; /* BIT7 */
} reg_bits;
};
union max14906_opn_wr_en {
uint8_t reg_raw;
struct {
uint8_t OW_OFF_EN1: 1; /* BIT0 */
uint8_t OW_OFF_EN2: 1;
uint8_t OW_OFF_EN3: 1;
uint8_t OW_OFF_EN4: 1;
uint8_t GDRV_EN1: 1;
uint8_t GDRV_EN2: 1;
uint8_t GDRV_EN3: 1;
uint8_t GDRV_EN4: 1; /* BIT7 */
} reg_bits;
};
union max14906_sht_vdd_en {
uint8_t reg_raw;
struct {
uint8_t SH_VDD_EN1: 1; /* BIT0 */
uint8_t SH_VDD_EN2: 1;
uint8_t SH_VDD_EN3: 1;
uint8_t SH_VDD_EN4: 1;
uint8_t VDD_OV_EN1: 1;
uint8_t VDD_OV_EN2: 1;
uint8_t VDD_OV_EN3: 1;
uint8_t VDD_OV_EN4: 1; /* BIT7 */
} reg_bits;
};
union max14906_config_di {
uint8_t reg_raw;
struct {
uint8_t OVL_BLANK: 2; /* BIT0 */
uint8_t OVL_STRETCH_EN: 1;
uint8_t ABOVE_VDD_PROT_EN: 1;
uint8_t VDD_FAULT_SEL: 1;
uint8_t VDD_FAULT_DIS: 1;
uint8_t RESERVED: 1;
uint8_t TYP_2_DI: 1; /* BIT7 */
} reg_bits;
};
union max14906_config_do {
uint8_t reg_raw;
struct {
uint8_t DO_MODE1: 2; /* BIT0 */
uint8_t DO_MODE2: 2;
uint8_t DO_MODE3: 2;
uint8_t DO_MODE4: 2; /* BIT7 */
} reg_bits;
};
union max14906_config_curr_lim {
uint8_t reg_raw;
struct {
uint8_t CL1: 2; /* BIT0 */
uint8_t CL2: 2;
uint8_t CL3: 2;
uint8_t CL4: 2; /* BIT7 */
} reg_bits;
};
union max14906_mask {
uint8_t reg_raw;
struct {
uint8_t OVER_LD_M: 1; /* BIT0 */
uint8_t CURR_LIM_M: 1;
uint8_t OW_OFF_M: 1;
uint8_t ABOVE_VDD_M: 1;
uint8_t SHT_VDD_M: 1;
uint8_t VDD_OK_M: 1;
uint8_t SUPPLY_ERR_M: 1;
uint8_t COM_ERR_M: 1; /* BIT7 */
} reg_bits;
};
union max14906_config1 {
uint8_t reg_raw;
struct {
uint8_t FLED_SET: 1; /* BIT0 */
uint8_t SLED_SET: 1;
uint8_t FLED_STRETCH: 2;
uint8_t FFILTER_EN: 1;
uint8_t FILTER_LONG: 1;
uint8_t FLATCH_EN: 1;
uint8_t LED_CURR_LIM: 1; /* BIT7 */
} reg_bits;
};
union max14906_config2 {
uint8_t reg_raw;
struct {
uint8_t VDD_ON_THR: 1; /* BIT0 */
uint8_t SYNCH_WD_EN: 1;
uint8_t SHT_VDD_THR: 2;
uint8_t OW_OFF_CS: 2;
uint8_t WD_TO: 2; /* BIT7 */
} reg_bits;
};
/* Config1 register Enable/Disable SLED */
#define MAX149x6_SLED_MASK BIT(1)
/* Config1 register Enable/Disable FLED */
#define MAX149x6_FLED_MASK BIT(0)
#define MAX149x6_ENABLE 1
#define MAX149x6_DISABLE 0
struct max149x6_config {
struct spi_dt_spec spi;
struct gpio_dt_spec fault_gpio;
struct gpio_dt_spec ready_gpio;
struct gpio_dt_spec sync_gpio;
struct gpio_dt_spec en_gpio;
bool crc_en;
union max14906_config1 config1;
union max14906_config2 config2;
union max14906_config_curr_lim curr_lim;
union max14906_config_di config_do;
union max14906_config_do config_di;
enum max149x6_spi_addr spi_addr;
uint8_t pkt_size;
};
#define max14906_config max149x6_config
struct max14906_data {
struct gpio_driver_data common;
struct {
union max14906_doi_level doi_level;
union max14906_ovr_ld_chf ovr_ld;
union max14906_opn_wir_chf opn_wir;
union max14906_sht_vdd_chf sht_vdd;
} chan;
struct {
union max14906_opn_wr_en opn_wr_en;
union max14906_sht_vdd_en sht_vdd_en;
} chan_en;
struct {
union max14906_interrupt interrupt;
union max14906_global_err glob_err;
union max14906_mask mask;
} glob;
};
#endif

View file

@ -0,0 +1,157 @@
/*
* Copyright (c) 2024 Analog Devices Inc.
* Copyright (c) 2024 Baylibre SAS
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_DRIVERS_GPIO_GPIO_MAX149X6_H_
#define ZEPHYR_DRIVERS_GPIO_GPIO_MAX149X6_H_
#define MAX149x6_READ 0
#define MAX149x6_WRITE 1
#define MAX149X6_GET_BIT(val, i) (0x1 & ((val) >> (i)))
#define PRINT_ERR_BIT(bit1, bit2) \
if ((bit1) & (bit2)) \
LOG_ERR("[%s] %d", #bit1, bit1)
#define PRINT_ERR(bit) \
if (bit) \
LOG_ERR("[DIAG] [%s] %d\n", #bit, bit)
#define PRINT_INF(bit) LOG_INFO("[%s] %d\n", #bit, bit)
#define LOG_DIAG(...) Z_LOG(LOG_LEVEL_ERR, __VA_ARGS__)
/**
* @brief Compute the CRC5 value for an array of bytes when writing to MAX149X6
* @param data - array of data to encode
* @param encode - action to be performed - true(encode), false(decode)
* @return the resulted CRC5
*/
static uint8_t max149x6_crc(uint8_t *data, bool encode)
{
uint8_t crc5_start = 0x1f;
uint8_t crc5_poly = 0x15;
uint8_t crc5_result = crc5_start;
uint8_t extra_byte = 0x00;
uint8_t data_bit;
uint8_t result_bit;
int i;
/*
* This is a custom implementation of a CRC5 algorithm, detailed here:
* https://www.analog.com/en/app-notes/how-to-program-the-max14906-quadchannel-
* industrial-digital-output-digital-input.html
*/
for (i = (encode) ? 0 : 2; i < 8; i++) {
data_bit = (data[0] >> (7 - i)) & 0x01;
result_bit = (crc5_result & 0x10) >> 4;
if (data_bit ^ result_bit) {
crc5_result = crc5_poly ^ ((crc5_result << 1) & 0x1f);
} else {
crc5_result = (crc5_result << 1) & 0x1f;
}
}
for (i = 0; i < 8; i++) {
data_bit = (data[1] >> (7 - i)) & 0x01;
result_bit = (crc5_result & 0x10) >> 4;
if (data_bit ^ result_bit) {
crc5_result = crc5_poly ^ ((crc5_result << 1) & 0x1f);
} else {
crc5_result = (crc5_result << 1) & 0x1f;
}
}
for (i = 0; i < 3; i++) {
data_bit = (extra_byte >> (7 - i)) & 0x01;
result_bit = (crc5_result & 0x10) >> 4;
if (data_bit ^ result_bit) {
crc5_result = crc5_poly ^ ((crc5_result << 1) & 0x1f);
} else {
crc5_result = (crc5_result << 1) & 0x1f;
}
}
return crc5_result;
}
/*
* @brief Register read/write function for MAX149x6
*
* @param dev - MAX149x6 device config.
* @param addr - Register value to which data is written.
* @param val - Value which is to be written to requested register.
* @return 0 in case of success, negative error code otherwise.
*/
static int max149x6_reg_transceive(const struct device *dev, uint8_t addr, uint8_t val,
uint8_t *rx_diag_buff, uint8_t rw)
{
uint8_t crc;
int ret;
uint8_t local_rx_buff[MAX149x6_MAX_PKT_SIZE] = {0};
uint8_t local_tx_buff[MAX149x6_MAX_PKT_SIZE] = {0};
const struct max149x6_config *config = dev->config;
struct spi_buf tx_buf = {
.buf = &local_tx_buff,
.len = config->pkt_size,
};
const struct spi_buf_set tx = {.buffers = &tx_buf, .count = 1};
struct spi_buf rx_buf = {
.buf = &local_rx_buff,
.len = config->pkt_size,
};
const struct spi_buf_set rx = {.buffers = &rx_buf, .count = 1};
if (config->crc_en & 0) {
rx_buf.len++;
}
local_tx_buff[0] = FIELD_PREP(MAX149x6_ADDR_MASK, addr) |
FIELD_PREP(MAX149x6_CHIP_ADDR_MASK, config->spi_addr) |
FIELD_PREP(MAX149x6_RW_MASK, rw & 0x1);
local_tx_buff[1] = val;
/* If CRC enabled calculate it */
if (config->crc_en) {
local_tx_buff[2] = max149x6_crc(&local_tx_buff[0], true);
}
/* write cmd & read resp at once */
ret = spi_transceive_dt(&config->spi, &tx, &rx);
if (ret) {
LOG_ERR("Err spi_transcieve_dt [%d]\n", ret);
return ret;
}
/* if CRC enabled check readed */
if (config->crc_en) {
crc = max149x6_crc(&local_rx_buff[0], false);
if (crc != (local_rx_buff[2] & 0x1F)) {
LOG_ERR("READ CRC ERR (%d)-(%d)\n", crc, (local_rx_buff[2] & 0x1F));
return -EINVAL;
}
}
if (rx_diag_buff != NULL) {
rx_diag_buff[0] = local_rx_buff[0];
}
/* In case of write we are getting 2 diagnostic bytes - byte0 & byte1
* and pass them to diag buffer to be parsed in next stage
*/
if ((MAX149x6_WRITE == rw) && (rx_diag_buff != NULL)) {
rx_diag_buff[1] = local_rx_buff[1];
} else {
ret = local_rx_buff[1];
}
return ret;
}
#endif

View file

@ -360,6 +360,7 @@
&test_gpio 0 0
&test_gpio 0 0
&test_gpio 0 0
&test_gpio 0 0
&test_gpio 0 0>;
test_spi_mcp23s17: mcp23s17@0 {
@ -440,6 +441,26 @@
ngpios = <8>;
#gpio-cells = <2>;
};
test_spi_max14906: max14906@5 {
compatible = "adi,max1906-gpio";
status = "okay";
reg = <0x06>;
spi-max-frequency = <0>;
gpio-controller;
#gpio-cells = <2>;
ngpios = <4>;
crc-en;
spi-addr = <0>;
ow-en = <0 0 0 0>;
vdd-ov-en = <0 0 0 0>;
gdrv-en = <0 0 0 0>;
sh-vdd-en = <0 0 0 0>;
drdy-gpios = <&test_gpio 0 0>;
fault-gpios = <&test_gpio 0 0>;
sync-gpios = <&test_gpio 0 0>;
en-gpios = <&test_gpio 0 0>;
};
};
};
};