drivers: nxp: convert SIUL2 drivers to native

Convert pin control, GPIO and external interrupt controller drivers
based on SIUL2 peripheral to native drivers. This must be done in a
single commit to preserve atomicity, as these drivers depend on each
other.

Signed-off-by: Manuel Argüelles <manuel.arguelles@nxp.com>
This commit is contained in:
Manuel Argüelles 2024-07-18 17:59:49 +07:00 committed by Carles Cufí
commit 6c7d836b0c
15 changed files with 591 additions and 502 deletions

View file

@ -1,5 +1,5 @@
/*
* Copyright 2022-2023 NXP
* Copyright 2022-2024 NXP
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -9,12 +9,10 @@
#include <zephyr/kernel.h>
#include <zephyr/drivers/gpio.h>
#include <zephyr/drivers/gpio/gpio_utils.h>
#include <zephyr/drivers/pinctrl.h>
#include <zephyr/dt-bindings/gpio/nxp-s32-gpio.h>
#include <zephyr/logging/log.h>
#include <Siul2_Port_Ip.h>
#include <Siul2_Dio_Ip.h>
LOG_MODULE_REGISTER(nxp_s32_gpio, CONFIG_GPIO_LOG_LEVEL);
#ifdef CONFIG_NXP_S32_EIRQ
@ -24,6 +22,19 @@ LOG_MODULE_REGISTER(nxp_s32_gpio, CONFIG_GPIO_LOG_LEVEL);
#include <zephyr/drivers/interrupt_controller/intc_wkpu_nxp_s32.h>
#endif
/* SIUL2 Multiplexed Signal Configuration Register (offset from port base) */
#define SIUL2_MSCR(n) (0x4 * (n))
/* SIUL2 Parallel GPIO Pad Data Out (offset from gpio base) */
#define SIUL2_PGPDO 0
/* SIUL2 Parallel GPIO Pad Data In */
#define SIUL2_PGPDI 0x40
/* Handy accessors */
#define GPIO_READ(r) sys_read16(config->gpio_base + (r))
#define GPIO_WRITE(r, v) sys_write16((v), config->gpio_base + (r))
#define PORT_READ(p) sys_read32(config->port_base + SIUL2_MSCR(p))
#define PORT_WRITE(p, v) sys_write32((v), config->port_base + SIUL2_MSCR(p))
#if defined(CONFIG_NXP_S32_EIRQ) || defined(CONFIG_NXP_S32_WKPU)
#define NXP_S32_GPIO_LINE_NOT_FOUND 0xff
@ -42,10 +53,8 @@ struct gpio_nxp_s32_irq_config {
struct gpio_nxp_s32_config {
/* gpio_driver_config needs to be first */
struct gpio_driver_config common;
Siul2_Dio_Ip_GpioType *gpio_base;
Siul2_Port_Ip_PortType *port_base;
mem_addr_t gpio_base;
mem_addr_t port_base;
#ifdef CONFIG_NXP_S32_EIRQ
struct gpio_nxp_s32_irq_config *eirq_info;
#endif
@ -66,13 +75,17 @@ struct gpio_nxp_s32_data {
#endif
};
static ALWAYS_INLINE uint16_t reverse_bits_16(uint16_t value)
{
return (uint16_t)(__RBIT((uint32_t)value) >> 16);
}
static int nxp_s32_gpio_configure(const struct device *dev, gpio_pin_t pin,
gpio_flags_t flags)
{
const struct gpio_nxp_s32_config *port_config = dev->config;
Siul2_Dio_Ip_GpioType *gpio_base = port_config->gpio_base;
Siul2_Port_Ip_PortType *port_base = port_config->port_base;
Siul2_Port_Ip_PortPullConfig pull_config;
const struct gpio_nxp_s32_config *config = dev->config;
uint32_t mscr_val;
uint32_t pgpdo_val;
if ((flags & GPIO_SINGLE_ENDED) != 0) {
return -ENOTSUP;
@ -88,43 +101,31 @@ static int nxp_s32_gpio_configure(const struct device *dev, gpio_pin_t pin,
}
#endif
switch (flags & GPIO_DIR_MASK) {
case GPIO_INPUT:
Siul2_Port_Ip_SetPinDirection(port_base, pin, SIUL2_PORT_IN);
break;
case GPIO_OUTPUT:
Siul2_Port_Ip_SetPinDirection(port_base, pin, SIUL2_PORT_OUT);
break;
case GPIO_INPUT | GPIO_OUTPUT:
Siul2_Port_Ip_SetPinDirection(port_base, pin, SIUL2_PORT_IN_OUT);
break;
default:
Siul2_Port_Ip_SetPinDirection(port_base, pin, SIUL2_PORT_HI_Z);
break;
}
mscr_val = PORT_READ(pin);
mscr_val &= ~(SIUL2_MSCR_SSS_MASK | SIUL2_MSCR_OBE_MASK | SIUL2_MSCR_IBE_MASK |
SIUL2_MSCR_PUE_MASK | SIUL2_MSCR_PUS_MASK);
Siul2_Port_Ip_SetOutputBuffer(port_base, pin,
(flags & GPIO_OUTPUT), PORT_MUX_AS_GPIO);
if (flags & GPIO_OUTPUT) {
mscr_val |= SIUL2_MSCR_OBE(1U);
switch (flags & (GPIO_OUTPUT | GPIO_OUTPUT_INIT_HIGH | GPIO_OUTPUT_INIT_LOW)) {
case GPIO_OUTPUT_HIGH:
Siul2_Dio_Ip_WritePin(gpio_base, pin, 1);
break;
case GPIO_OUTPUT_LOW:
Siul2_Dio_Ip_WritePin(gpio_base, pin, 0);
break;
default:
break;
pgpdo_val = GPIO_READ(SIUL2_PGPDO);
if (flags & GPIO_OUTPUT_INIT_HIGH) {
pgpdo_val |= BIT(15 - pin);
} else if (flags & GPIO_OUTPUT_INIT_LOW) {
pgpdo_val &= ~BIT(15 - pin);
}
GPIO_WRITE(SIUL2_PGPDO, pgpdo_val);
}
if ((flags & GPIO_PULL_UP) != 0) {
pull_config = PORT_INTERNAL_PULL_UP_ENABLED;
} else if ((flags & GPIO_PULL_DOWN) != 0) {
pull_config = PORT_INTERNAL_PULL_DOWN_ENABLED;
} else {
pull_config = PORT_INTERNAL_PULL_NOT_ENABLED;
if (flags & GPIO_INPUT) {
mscr_val |= SIUL2_MSCR_IBE(1U);
}
Siul2_Port_Ip_SetPullSel(port_base, pin, pull_config);
if (flags & (GPIO_PULL_UP | GPIO_PULL_DOWN)) {
mscr_val |= SIUL2_MSCR_PUE(1U);
if (flags & GPIO_PULL_UP) {
mscr_val |= SIUL2_MSCR_PUS(1U);
}
}
PORT_WRITE(pin, mscr_val);
return 0;
}
@ -133,7 +134,7 @@ static int nxp_s32_gpio_port_get_raw(const struct device *port, uint32_t *value)
{
const struct gpio_nxp_s32_config *config = port->config;
*value = Siul2_Dio_Ip_ReadPins(config->gpio_base);
*value = reverse_bits_16(GPIO_READ(SIUL2_PGPDI));
return 0;
}
@ -143,11 +144,11 @@ static int nxp_s32_gpio_port_set_masked_raw(const struct device *port,
gpio_port_value_t value)
{
const struct gpio_nxp_s32_config *config = port->config;
Siul2_Dio_Ip_GpioType *gpio_base = config->gpio_base;
gpio_port_pins_t pins_value = Siul2_Dio_Ip_GetPinsOutput(gpio_base);
gpio_port_pins_t pins_value;
pins_value = reverse_bits_16(GPIO_READ(SIUL2_PGPDO));
pins_value = (pins_value & ~mask) | (mask & value);
Siul2_Dio_Ip_WritePins(gpio_base, pins_value);
GPIO_WRITE(SIUL2_PGPDO, reverse_bits_16(pins_value));
return 0;
}
@ -156,8 +157,11 @@ static int nxp_s32_gpio_port_set_bits_raw(const struct device *port,
gpio_port_pins_t pins)
{
const struct gpio_nxp_s32_config *config = port->config;
uint16_t reg_val;
Siul2_Dio_Ip_SetPins(config->gpio_base, pins);
reg_val = GPIO_READ(SIUL2_PGPDO);
reg_val |= reverse_bits_16(pins);
GPIO_WRITE(SIUL2_PGPDO, reg_val);
return 0;
}
@ -166,8 +170,11 @@ static int nxp_s32_gpio_port_clear_bits_raw(const struct device *port,
gpio_port_pins_t pins)
{
const struct gpio_nxp_s32_config *config = port->config;
uint16_t reg_val;
Siul2_Dio_Ip_ClearPins(config->gpio_base, pins);
reg_val = GPIO_READ(SIUL2_PGPDO);
reg_val &= ~reverse_bits_16(pins);
GPIO_WRITE(SIUL2_PGPDO, reg_val);
return 0;
}
@ -176,8 +183,11 @@ static int nxp_s32_gpio_port_toggle_bits(const struct device *port,
gpio_port_pins_t pins)
{
const struct gpio_nxp_s32_config *config = port->config;
uint16_t reg_val;
Siul2_Dio_Ip_TogglePins(config->gpio_base, pins);
reg_val = GPIO_READ(SIUL2_PGPDO);
reg_val ^= reverse_bits_16(pins);
GPIO_WRITE(SIUL2_PGPDO, reg_val);
return 0;
}
@ -207,28 +217,18 @@ static void nxp_s32_gpio_isr(uint8_t pin, void *arg)
}
#if defined(CONFIG_NXP_S32_EIRQ)
static int nxp_s32_gpio_eirq_get_trigger(Siul2_Icu_Ip_EdgeType *edge_type,
enum gpio_int_mode mode,
static int nxp_s32_gpio_eirq_get_trigger(enum eirq_nxp_s32_trigger *eirq_trigger,
enum gpio_int_trig trigger)
{
if (mode == GPIO_INT_MODE_DISABLED) {
*edge_type = SIUL2_ICU_DISABLE;
return 0;
}
if (mode == GPIO_INT_MODE_LEVEL) {
return -ENOTSUP;
}
switch (trigger) {
case GPIO_INT_TRIG_LOW:
*edge_type = SIUL2_ICU_FALLING_EDGE;
*eirq_trigger = EIRQ_NXP_S32_FALLING_EDGE;
break;
case GPIO_INT_TRIG_HIGH:
*edge_type = SIUL2_ICU_RISING_EDGE;
*eirq_trigger = EIRQ_NXP_S32_RISING_EDGE;
break;
case GPIO_INT_TRIG_BOTH:
*edge_type = SIUL2_ICU_BOTH_EDGES;
*eirq_trigger = EIRQ_NXP_S32_BOTH_EDGES;
break;
default:
return -ENOTSUP;
@ -245,37 +245,39 @@ static int nxp_s32_gpio_config_eirq(const struct device *dev,
const struct gpio_nxp_s32_config *config = dev->config;
const struct gpio_nxp_s32_irq_config *irq_cfg = config->eirq_info;
uint8_t irq_line;
Siul2_Icu_Ip_EdgeType edge_type;
enum eirq_nxp_s32_trigger eirq_trigger;
if (irq_cfg == NULL) {
LOG_ERR("external interrupt controller not available or enabled");
return -ENOTSUP;
}
if (nxp_s32_gpio_eirq_get_trigger(&edge_type, mode, trig)) {
LOG_ERR("trigger or mode not supported");
if (mode == GPIO_INT_MODE_LEVEL) {
return -ENOTSUP;
}
irq_line = nxp_s32_gpio_pin_to_line(irq_cfg, pin);
if (irq_line == NXP_S32_GPIO_LINE_NOT_FOUND) {
if (edge_type == SIUL2_ICU_DISABLE) {
if (mode == GPIO_INT_MODE_DISABLED) {
return 0;
}
LOG_ERR("pin %d cannot be used for external interrupt", pin);
return -ENOTSUP;
}
if (edge_type == SIUL2_ICU_DISABLE) {
if (mode == GPIO_INT_MODE_DISABLED) {
eirq_nxp_s32_disable_interrupt(irq_cfg->ctrl, irq_line);
eirq_nxp_s32_unset_callback(irq_cfg->ctrl, irq_line);
} else {
if (eirq_nxp_s32_set_callback(irq_cfg->ctrl, irq_line,
nxp_s32_gpio_isr, pin, (void *)dev)) {
if (nxp_s32_gpio_eirq_get_trigger(&eirq_trigger, trig)) {
return -ENOTSUP;
}
if (eirq_nxp_s32_set_callback(irq_cfg->ctrl, irq_line, pin,
nxp_s32_gpio_isr, (void *)dev)) {
LOG_ERR("pin %d is already in use", pin);
return -EBUSY;
}
eirq_nxp_s32_enable_interrupt(irq_cfg->ctrl, irq_line, edge_type);
eirq_nxp_s32_enable_interrupt(irq_cfg->ctrl, irq_line, eirq_trigger);
}
return 0;
@ -391,34 +393,34 @@ static int nxp_s32_gpio_pin_get_config(const struct device *dev,
gpio_flags_t *out_flags)
{
const struct gpio_nxp_s32_config *config = dev->config;
Siul2_Dio_Ip_GpioType *gpio_base = config->gpio_base;
Siul2_Port_Ip_PortType *port_base = config->port_base;
Siul2_Dio_Ip_PinsChannelType pins_output;
uint16_t pins_output;
uint32_t mscr_val;
gpio_flags_t flags = 0;
if ((port_base->MSCR[pin] & SIUL2_MSCR_IBE_MASK) != 0) {
mscr_val = PORT_READ(pin);
if ((mscr_val & SIUL2_MSCR_IBE_MASK) != 0) {
flags |= GPIO_INPUT;
}
if ((port_base->MSCR[pin] & SIUL2_MSCR_OBE_MASK) != 0) {
if ((mscr_val & SIUL2_MSCR_OBE_MASK) != 0) {
flags |= GPIO_OUTPUT;
pins_output = Siul2_Dio_Ip_GetPinsOutput(gpio_base);
if ((pins_output & BIT(pin)) != 0) {
pins_output = GPIO_READ(SIUL2_PGPDO);
if ((pins_output & BIT(15 - pin)) != 0) {
flags |= GPIO_OUTPUT_HIGH;
} else {
flags |= GPIO_OUTPUT_LOW;
}
#ifdef FEATURE_SIUL2_PORT_IP_HAS_OPEN_DRAIN
if ((port_base->MSCR[pin] & SIUL2_MSCR_ODE_MASK) != 0) {
#if defined(SIUL2_MSCR_ODE_MASK)
if ((mscr_val & SIUL2_MSCR_ODE_MASK) != 0) {
flags |= GPIO_OPEN_DRAIN;
}
#endif /* FEATURE_SIUL2_PORT_IP_HAS_OPEN_DRAIN */
#endif /* SIUL2_MSCR_ODE_MASK */
}
if ((port_base->MSCR[pin] & SIUL2_MSCR_PUE_MASK) != 0) {
if ((port_base->MSCR[pin] & SIUL2_MSCR_PUS_MASK) != 0) {
if ((mscr_val & SIUL2_MSCR_PUE_MASK) != 0) {
if ((mscr_val & SIUL2_MSCR_PUS_MASK) != 0) {
flags |= GPIO_PULL_UP;
} else {
flags |= GPIO_PULL_DOWN;
@ -438,7 +440,6 @@ static int nxp_s32_gpio_port_get_direction(const struct device *dev,
gpio_port_pins_t *outputs)
{
const struct gpio_nxp_s32_config *config = dev->config;
Siul2_Port_Ip_PortType *port_base = config->port_base;
gpio_port_pins_t ip = 0;
gpio_port_pins_t op = 0;
uint32_t pin;
@ -448,7 +449,7 @@ static int nxp_s32_gpio_port_get_direction(const struct device *dev,
if (inputs != NULL) {
while (map) {
pin = find_lsb_set(map) - 1;
ip |= (!!(port_base->MSCR[pin] & SIUL2_MSCR_IBE_MASK)) * BIT(pin);
ip |= (!!(PORT_READ(pin) & SIUL2_MSCR_IBE_MASK)) * BIT(pin);
map &= ~BIT(pin);
}
@ -458,7 +459,7 @@ static int nxp_s32_gpio_port_get_direction(const struct device *dev,
if (outputs != NULL) {
while (map) {
pin = find_lsb_set(map) - 1;
op |= (!!(port_base->MSCR[pin] & SIUL2_MSCR_OBE_MASK)) * BIT(pin);
op |= (!!(PORT_READ(pin) & SIUL2_MSCR_OBE_MASK)) * BIT(pin);
map &= ~BIT(pin);
}
@ -513,12 +514,6 @@ static const struct gpio_driver_api gpio_nxp_s32_driver_api = {
& ~(GPIO_NXP_S32_RESERVED_PIN_MASK(n))), \
(GPIO_PORT_PIN_MASK_FROM_DT_INST(n)))
#define GPIO_NXP_S32_REG_ADDR(n) \
((Siul2_Dio_Ip_GpioType *)DT_INST_REG_ADDR_BY_NAME(n, pgpdo))
#define GPIO_NXP_S32_PORT_REG_ADDR(n) \
((Siul2_Port_Ip_PortType *)DT_INST_REG_ADDR_BY_NAME(n, mscr))
#ifdef CONFIG_NXP_S32_EIRQ
#define GPIO_NXP_S32_EIRQ_NODE(n) \
DT_INST_PHANDLE(n, interrupt_parent)
@ -587,8 +582,8 @@ static const struct gpio_driver_api gpio_nxp_s32_driver_api = {
.common = { \
.port_pin_mask = GPIO_NXP_S32_PORT_PIN_MASK(n), \
}, \
.gpio_base = GPIO_NXP_S32_REG_ADDR(n), \
.port_base = GPIO_NXP_S32_PORT_REG_ADDR(n), \
.gpio_base = DT_INST_REG_ADDR_BY_NAME(n, pgpdo), \
.port_base = DT_INST_REG_ADDR_BY_NAME(n, mscr), \
GPIO_NXP_S32_GET_EIRQ_INFO(n) \
GPIO_NXP_S32_GET_WKPU_INFO(n) \
}; \

View file

@ -11,6 +11,25 @@ config NXP_S32_EIRQ
help
External interrupt controller driver for NXP S32 MCUs
if NXP_S32_EIRQ
config NXP_S32_EIRQ_EXT_INTERRUPTS_MAX
int
default 8 if SOC_SERIES_S32ZE
default 32 if SOC_SERIES_S32K3
help
Number of SIUL2 external interrupts per controller. This is a SoC
integration option.
config NXP_S32_EIRQ_EXT_INTERRUPTS_GROUP
int
default 8
help
Number of SIUL2 external interrupts grouped into a single core
interrupt line. This is a SoC integration option.
endif # NXP_S32_EIRQ
config NXP_S32_WKPU
bool "Wake-up Unit interrupt controller driver for NXP S32 MCUs"
default y

View file

@ -9,29 +9,45 @@
#include <soc.h>
#include <zephyr/irq.h>
#include <zephyr/sys/sys_io.h>
#include <zephyr/sys/math_extras.h>
#include <zephyr/drivers/pinctrl.h>
#include <zephyr/drivers/interrupt_controller/intc_eirq_nxp_s32.h>
#include <Siul2_Icu_Ip_Irq.h>
/* SIUL2 External Interrupt Controller registers (offsets from DISR0) */
/* SIUL2 DMA/Interrupt Status Flag */
#define SIUL2_DISR0 0x0
/* SIUL2 DMA/Interrupt Request Enable */
#define SIUL2_DIRER0 0x8
/* SIUL2 DMA/Interrupt Request Select */
#define SIUL2_DIRSR0 0x10
/* SIUL2 Interrupt Rising-Edge Event Enable */
#define SIUL2_IREER0 0x18
/* SIUL2 Interrupt Falling-Edge Event Enable */
#define SIUL2_IFEER0 0x20
/* SIUL2 Interrupt Filter Enable */
#define SIUL2_IFER0 0x28
/* SIUL2 Interrupt Filter Maximum Counter Register */
#define SIUL2_IFMCR(n) (0x30 + 0x4 * (n))
#define SIUL2_IFMCR_MAXCNT_MASK GENMASK(3, 0)
#define SIUL2_IFMCR_MAXCNT(v) FIELD_PREP(SIUL2_IFMCR_MAXCNT_MASK, (v))
/* SIUL2 Interrupt Filter Clock Prescaler Register */
#define SIUL2_IFCPR 0xb0
#define SIUL2_IFCPR_IFCP_MASK GENMASK(3, 0)
#define SIUL2_IFCPR_IFCP(v) FIELD_PREP(SIUL2_IFCPR_IFCP_MASK, (v))
#define NXP_S32_NUM_CHANNELS SIUL2_ICU_IP_NUM_OF_CHANNELS
/*
* The macros from low level driver contains a bracket so
* it cannot be used for some Zephyr macros (e.g LISTIFY).
* This just does remove the bracket to be used for such macro.
*/
#define NXP_S32_NUM_CHANNELS_DEBRACKET __DEBRACKET SIUL2_ICU_IP_NUM_OF_CHANNELS
/* Handy accessors */
#define REG_READ(r) sys_read32(config->base + (r))
#define REG_WRITE(r, v) sys_write32((v), config->base + (r))
#define GLITCH_FILTER_DISABLED (SIUL2_IFMCR_MAXCNT_MASK + 1)
struct eirq_nxp_s32_config {
uint8_t instance;
mem_addr_t disr0;
mem_addr_t direr0;
const Siul2_Icu_Ip_ConfigType *icu_cfg;
mem_addr_t base;
const struct pinctrl_dev_config *pincfg;
uint8_t filter_clock_prescaler;
uint8_t max_filter_counter[CONFIG_NXP_S32_EIRQ_EXT_INTERRUPTS_MAX];
};
/* Wrapper callback for each EIRQ line, from low level driver callback to GPIO callback */
struct eirq_nxp_s32_cb {
eirq_nxp_s32_callback_t cb;
uint8_t pin;
@ -42,81 +58,121 @@ struct eirq_nxp_s32_data {
struct eirq_nxp_s32_cb *cb;
};
int eirq_nxp_s32_set_callback(const struct device *dev, uint8_t line,
eirq_nxp_s32_callback_t cb, uint8_t pin, void *arg)
static inline void eirq_nxp_s32_interrupt_handler(const struct device *dev, uint32_t irq_idx)
{
const struct eirq_nxp_s32_config *config = dev->config;
struct eirq_nxp_s32_data *data = dev->data;
uint32_t mask = GENMASK(CONFIG_NXP_S32_EIRQ_EXT_INTERRUPTS_GROUP - 1, 0);
uint32_t pending;
uint8_t irq;
pending = eirq_nxp_s32_get_pending(dev);
pending &= mask << (irq_idx * CONFIG_NXP_S32_EIRQ_EXT_INTERRUPTS_GROUP);
while (pending) {
mask = LSB_GET(pending);
irq = u64_count_trailing_zeros(mask);
/* Clear status flag */
REG_WRITE(SIUL2_DISR0, REG_READ(SIUL2_DISR0) | mask);
if (data->cb[irq].cb != NULL) {
data->cb[irq].cb(data->cb[irq].pin, data->cb[irq].data);
}
pending ^= mask;
}
}
int eirq_nxp_s32_set_callback(const struct device *dev, uint8_t irq, uint8_t pin,
eirq_nxp_s32_callback_t cb, void *arg)
{
struct eirq_nxp_s32_data *data = dev->data;
__ASSERT(line < NXP_S32_NUM_CHANNELS, "Interrupt line is out of range");
__ASSERT_NO_MSG(irq < CONFIG_NXP_S32_EIRQ_EXT_INTERRUPTS_MAX);
if ((data->cb[line].cb == cb) && (data->cb[line].data == arg)) {
if ((data->cb[irq].cb == cb) && (data->cb[irq].data == arg)) {
return 0;
}
if (data->cb[line].cb) {
if (data->cb[irq].cb) {
return -EBUSY;
}
data->cb[line].cb = cb;
data->cb[line].pin = pin;
data->cb[line].data = arg;
data->cb[irq].cb = cb;
data->cb[irq].pin = pin;
data->cb[irq].data = arg;
return 0;
}
void eirq_nxp_s32_unset_callback(const struct device *dev, uint8_t line)
void eirq_nxp_s32_unset_callback(const struct device *dev, uint8_t irq)
{
struct eirq_nxp_s32_data *data = dev->data;
__ASSERT(line < NXP_S32_NUM_CHANNELS, "Interrupt line is out of range");
__ASSERT_NO_MSG(irq < CONFIG_NXP_S32_EIRQ_EXT_INTERRUPTS_MAX);
data->cb[line].cb = NULL;
data->cb[line].pin = 0;
data->cb[line].data = NULL;
data->cb[irq].cb = NULL;
data->cb[irq].pin = 0;
data->cb[irq].data = NULL;
}
void eirq_nxp_s32_enable_interrupt(const struct device *dev, uint8_t line,
Siul2_Icu_Ip_EdgeType edge_type)
void eirq_nxp_s32_enable_interrupt(const struct device *dev, uint8_t irq,
enum eirq_nxp_s32_trigger trigger)
{
const struct eirq_nxp_s32_config *config = dev->config;
uint32_t reg_val;
__ASSERT_NO_MSG(irq < CONFIG_NXP_S32_EIRQ_EXT_INTERRUPTS_MAX);
/* Configure trigger */
reg_val = REG_READ(SIUL2_IREER0);
if ((trigger == EIRQ_NXP_S32_RISING_EDGE) || (trigger == EIRQ_NXP_S32_BOTH_EDGES)) {
reg_val |= BIT(irq);
} else {
reg_val &= ~BIT(irq);
}
REG_WRITE(SIUL2_IREER0, reg_val);
reg_val = REG_READ(SIUL2_IFEER0);
if ((trigger == EIRQ_NXP_S32_FALLING_EDGE) || (trigger == EIRQ_NXP_S32_BOTH_EDGES)) {
reg_val |= BIT(irq);
} else {
reg_val &= ~BIT(irq);
}
REG_WRITE(SIUL2_IFEER0, reg_val);
/* Clear status flag and unmask interrupt */
REG_WRITE(SIUL2_DISR0, REG_READ(SIUL2_DISR0) | BIT(irq));
REG_WRITE(SIUL2_DIRER0, REG_READ(SIUL2_DIRER0) | BIT(irq));
}
void eirq_nxp_s32_disable_interrupt(const struct device *dev, uint8_t irq)
{
const struct eirq_nxp_s32_config *config = dev->config;
__ASSERT(line < NXP_S32_NUM_CHANNELS, "Interrupt line is out of range");
__ASSERT_NO_MSG(irq < CONFIG_NXP_S32_EIRQ_EXT_INTERRUPTS_MAX);
Siul2_Icu_Ip_SetActivationCondition(config->instance, line, edge_type);
Siul2_Icu_Ip_EnableNotification(config->instance, line);
Siul2_Icu_Ip_EnableInterrupt(config->instance, line);
}
/* Disable triggers */
REG_WRITE(SIUL2_IREER0, REG_READ(SIUL2_IREER0) & ~BIT(irq));
REG_WRITE(SIUL2_IFEER0, REG_READ(SIUL2_IFEER0) & ~BIT(irq));
void eirq_nxp_s32_disable_interrupt(const struct device *dev, uint8_t line)
{
const struct eirq_nxp_s32_config *config = dev->config;
__ASSERT(line < NXP_S32_NUM_CHANNELS, "Interrupt line is out of range");
Siul2_Icu_Ip_DisableInterrupt(config->instance, line);
Siul2_Icu_Ip_DisableNotification(config->instance, line);
Siul2_Icu_Ip_SetActivationCondition(config->instance, line, SIUL2_ICU_DISABLE);
/* Clear status flag and mask interrupt */
REG_WRITE(SIUL2_DISR0, REG_READ(SIUL2_DISR0) | BIT(irq));
REG_WRITE(SIUL2_DIRER0, REG_READ(SIUL2_DIRER0) & ~BIT(irq));
}
uint32_t eirq_nxp_s32_get_pending(const struct device *dev)
{
const struct eirq_nxp_s32_config *config = dev->config;
return sys_read32(config->disr0) & sys_read32(config->direr0);
}
static void eirq_nxp_s32_callback(const struct device *dev, uint8 line)
{
const struct eirq_nxp_s32_data *data = dev->data;
if (data->cb[line].cb != NULL) {
data->cb[line].cb(data->cb[line].pin, data->cb[line].data);
}
return REG_READ(SIUL2_DISR0) & REG_READ(SIUL2_DIRER0);
}
static int eirq_nxp_s32_init(const struct device *dev)
{
const struct eirq_nxp_s32_config *config = dev->config;
uint8_t irq;
int err;
err = pinctrl_apply_state(config->pincfg, PINCTRL_STATE_DEFAULT);
@ -124,116 +180,83 @@ static int eirq_nxp_s32_init(const struct device *dev)
return err;
}
if (Siul2_Icu_Ip_Init(config->instance, config->icu_cfg)) {
return -EINVAL;
/* Disable triggers, clear status flags and mask all interrupts */
REG_WRITE(SIUL2_IREER0, 0U);
REG_WRITE(SIUL2_IFEER0, 0U);
REG_WRITE(SIUL2_DISR0, 0xffffffff);
REG_WRITE(SIUL2_DIRER0, 0U);
/* Select the request type as interrupt */
REG_WRITE(SIUL2_DIRSR0, 0U);
/* Configure glitch filters */
REG_WRITE(SIUL2_IFCPR, SIUL2_IFCPR_IFCP(config->filter_clock_prescaler));
for (irq = 0; irq < CONFIG_NXP_S32_EIRQ_EXT_INTERRUPTS_MAX; irq++) {
if (config->max_filter_counter[irq] < GLITCH_FILTER_DISABLED) {
REG_WRITE(SIUL2_IFMCR(irq),
SIUL2_IFMCR_MAXCNT(config->max_filter_counter[irq]));
REG_WRITE(SIUL2_IFER0, REG_READ(SIUL2_IFER0) | BIT(irq));
} else {
REG_WRITE(SIUL2_IFER0, REG_READ(SIUL2_IFER0) & ~BIT(irq));
}
}
return 0;
}
#define EIRQ_NXP_S32_CALLBACK(line, n) \
void nxp_s32_icu_##n##_eirq_line_##line##_callback(void) \
{ \
eirq_nxp_s32_callback(DEVICE_DT_INST_GET(n), line); \
#define EIRQ_NXP_S32_ISR_DEFINE(idx, n) \
static void eirq_nxp_s32_isr##idx##_##n(const struct device *dev) \
{ \
eirq_nxp_s32_interrupt_handler(dev, idx); \
}
#define EIRQ_NXP_S32_CHANNEL_CONFIG(idx, n) \
{ \
.hwChannel = idx, \
.digFilterEn = DT_INST_PROP_OR(DT_CHILD(n, line_##idx), filter_enable, 0), \
.maxFilterCnt = DT_INST_PROP_OR(DT_CHILD(n, line_##idx), filter_counter, 0), \
.intSel = SIUL2_ICU_IRQ, \
.intEdgeSel = SIUL2_ICU_DISABLE, \
.callback = NULL, \
.Siul2ChannelNotification = nxp_s32_icu_##n##_eirq_line_##idx##_callback, \
.callbackParam = 0U \
}
#define EIRQ_NXP_S32_CHANNELS_CONFIG(n) \
static const Siul2_Icu_Ip_ChannelConfigType eirq_##n##_channel_nxp_s32_cfg[] = { \
LISTIFY(NXP_S32_NUM_CHANNELS_DEBRACKET, EIRQ_NXP_S32_CHANNEL_CONFIG, (,), n) \
}
#define EIRQ_NXP_S32_INSTANCE_CONFIG(n) \
static const Siul2_Icu_Ip_InstanceConfigType eirq_##n##_instance_nxp_s32_cfg = { \
.intFilterClk = DT_INST_PROP_OR(n, filter_prescaler, 0), \
.altIntFilterClk = 0U, \
}
#define EIRQ_NXP_S32_COMBINE_CONFIG(n) \
static const Siul2_Icu_Ip_ConfigType eirq_##n##_nxp_s32_cfg = { \
.numChannels = NXP_S32_NUM_CHANNELS, \
.pInstanceConfig = &eirq_##n##_instance_nxp_s32_cfg, \
.pChannelsConfig = &eirq_##n##_channel_nxp_s32_cfg, \
}
#define EIRQ_NXP_S32_CONFIG(n) \
LISTIFY(NXP_S32_NUM_CHANNELS_DEBRACKET, EIRQ_NXP_S32_CALLBACK, (), n) \
EIRQ_NXP_S32_CHANNELS_CONFIG(n); \
EIRQ_NXP_S32_INSTANCE_CONFIG(n); \
EIRQ_NXP_S32_COMBINE_CONFIG(n);
#define _EIRQ_NXP_S32_IRQ_NAME(name) DT_CAT3(SIUL2_EXT_IRQ_, name, _ISR)
#define EIRQ_NXP_S32_IRQ_NAME(idx, n) \
COND_CODE_1(DT_INST_NODE_HAS_PROP(n, interrupt_names), \
(_EIRQ_NXP_S32_IRQ_NAME(DT_INST_STRING_TOKEN_BY_IDX(n, interrupt_names, idx))), \
(DT_CAT3(SIUL2_, n, _ICU_EIRQ_SINGLE_INT_HANDLER)))
#define _EIRQ_NXP_S32_IRQ_CONFIG(idx, n) \
do { \
IRQ_CONNECT(DT_INST_IRQ_BY_IDX(n, idx, irq), \
DT_INST_IRQ_BY_IDX(n, idx, priority), \
EIRQ_NXP_S32_IRQ_NAME(idx, n), \
DEVICE_DT_INST_GET(n), \
COND_CODE_1(CONFIG_GIC, (DT_INST_IRQ_BY_IDX(n, idx, flags)), (0))); \
irq_enable(DT_INST_IRQ_BY_IDX(n, idx, irq)); \
#define _EIRQ_NXP_S32_IRQ_CONFIG(idx, n) \
do { \
IRQ_CONNECT(DT_INST_IRQ_BY_IDX(n, idx, irq), DT_INST_IRQ_BY_IDX(n, idx, priority), \
eirq_nxp_s32_isr##idx##_##n, DEVICE_DT_INST_GET(n), \
COND_CODE_1(CONFIG_GIC, (DT_INST_IRQ_BY_IDX(n, idx, flags)), (0))); \
irq_enable(DT_INST_IRQ_BY_IDX(n, idx, irq)); \
} while (false);
#define EIRQ_NXP_S32_IRQ_CONFIG(n) \
#define EIRQ_NXP_S32_IRQ_CONFIG(n) \
LISTIFY(DT_NUM_IRQS(DT_DRV_INST(n)), _EIRQ_NXP_S32_IRQ_CONFIG, (), n)
#define EIRQ_NXP_S32_HW_INSTANCE_CHECK(i, n) \
(((DT_REG_ADDR(DT_INST_PARENT(n))) == IP_SIUL2_##i##_BASE) ? i : 0)
#define EIRQ_NXP_S32_FILTER_CONFIG(idx, n) \
COND_CODE_1(DT_NODE_EXISTS(DT_INST_CHILD(n, irq_##idx)), \
(DT_PROP_OR(DT_INST_CHILD(n, irq_##idx), max_filter_counter, \
GLITCH_FILTER_DISABLED)), \
(GLITCH_FILTER_DISABLED))
#define EIRQ_NXP_S32_HW_INSTANCE(n) \
LISTIFY(__DEBRACKET SIUL2_INSTANCE_COUNT, EIRQ_NXP_S32_HW_INSTANCE_CHECK, (|), n)
#define EIRQ_NXP_S32_INIT_DEVICE(n) \
EIRQ_NXP_S32_CONFIG(n) \
PINCTRL_DT_INST_DEFINE(n); \
static const struct eirq_nxp_s32_config eirq_nxp_s32_conf_##n = { \
.instance = EIRQ_NXP_S32_HW_INSTANCE(n), \
.disr0 = (mem_addr_t)DT_INST_REG_ADDR_BY_NAME(n, disr0), \
.direr0 = (mem_addr_t)DT_INST_REG_ADDR_BY_NAME(n, direr0), \
.icu_cfg = (Siul2_Icu_Ip_ConfigType *)&eirq_##n##_nxp_s32_cfg, \
.pincfg = PINCTRL_DT_INST_DEV_CONFIG_GET(n) \
}; \
static struct eirq_nxp_s32_cb eirq_nxp_s32_cb_##n[NXP_S32_NUM_CHANNELS]; \
static struct eirq_nxp_s32_data eirq_nxp_s32_data_##n = { \
.cb = eirq_nxp_s32_cb_##n, \
}; \
static int eirq_nxp_s32_init##n(const struct device *dev); \
DEVICE_DT_INST_DEFINE(n, \
eirq_nxp_s32_init##n, \
NULL, \
&eirq_nxp_s32_data_##n, \
&eirq_nxp_s32_conf_##n, \
PRE_KERNEL_2, \
CONFIG_INTC_INIT_PRIORITY, \
NULL); \
static int eirq_nxp_s32_init##n(const struct device *dev) \
{ \
int err; \
\
err = eirq_nxp_s32_init(dev); \
if (err) { \
return err; \
} \
\
EIRQ_NXP_S32_IRQ_CONFIG(n); \
\
return 0; \
}
#define EIRQ_NXP_S32_INIT_DEVICE(n) \
LISTIFY(DT_NUM_IRQS(DT_DRV_INST(n)), EIRQ_NXP_S32_ISR_DEFINE, (), n) \
PINCTRL_DT_INST_DEFINE(n); \
static const struct eirq_nxp_s32_config eirq_nxp_s32_conf_##n = { \
.base = DT_INST_REG_ADDR(n), \
.pincfg = PINCTRL_DT_INST_DEV_CONFIG_GET(n), \
.filter_clock_prescaler = DT_INST_PROP_OR(n, filter_prescaler, 0), \
.max_filter_counter = {LISTIFY(CONFIG_NXP_S32_EIRQ_EXT_INTERRUPTS_MAX, \
EIRQ_NXP_S32_FILTER_CONFIG, (,), n)}, \
}; \
static struct eirq_nxp_s32_cb eirq_nxp_s32_cb_##n[CONFIG_NXP_S32_EIRQ_EXT_INTERRUPTS_MAX]; \
static struct eirq_nxp_s32_data eirq_nxp_s32_data_##n = { \
.cb = eirq_nxp_s32_cb_##n, \
}; \
static int eirq_nxp_s32_init_##n(const struct device *dev) \
{ \
int err; \
\
err = eirq_nxp_s32_init(dev); \
if (err) { \
return err; \
} \
\
EIRQ_NXP_S32_IRQ_CONFIG(n); \
\
return 0; \
} \
DEVICE_DT_INST_DEFINE(n, eirq_nxp_s32_init_##n, NULL, &eirq_nxp_s32_data_##n, \
&eirq_nxp_s32_conf_##n, PRE_KERNEL_2, CONFIG_INTC_INIT_PRIORITY, \
NULL);
DT_INST_FOREACH_STATUS_OKAY(EIRQ_NXP_S32_INIT_DEVICE)

View file

@ -1,24 +1,63 @@
/*
* Copyright 2022 NXP
* Copyright 2022, 2024 NXP
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <zephyr/kernel.h>
#include <zephyr/drivers/pinctrl.h>
#include <Siul2_Port_Ip.h>
/* SIUL2 Multiplexed Signal Configuration Register */
#define SIUL2_MSCR(n) (0x240 + 0x4 * (n))
/* SIUL2 Input Multiplexed Signal Configuration Register */
#define SIUL2_IMCR(n) (0xa40 + 0x4 * (n))
#define SIUL2_MSCR_MAX_IDX 512U
#define SIUL2_IMCR_MAX_IDX 512U
/*
* Utility macro that expands to the SIUL2 base address if it exists or zero.
* Note that some devices may have instance gaps, hence the need to keep them in the array.
*/
#define SIUL2_BASE_OR_ZERO(nodelabel) \
COND_CODE_1(DT_NODE_EXISTS(DT_NODELABEL(nodelabel)), \
(DT_REG_ADDR(DT_NODELABEL(nodelabel))), (0U))
static mem_addr_t siul2_bases[] = {
SIUL2_BASE_OR_ZERO(siul2_0), SIUL2_BASE_OR_ZERO(siul2_1), SIUL2_BASE_OR_ZERO(siul2_2),
SIUL2_BASE_OR_ZERO(siul2_3), SIUL2_BASE_OR_ZERO(siul2_4), SIUL2_BASE_OR_ZERO(siul2_5),
};
static void pinctrl_configure_pin(const pinctrl_soc_pin_t *pin)
{
mem_addr_t base;
/* Multiplexed Signal Configuration */
__ASSERT_NO_MSG(pin->mscr.inst < ARRAY_SIZE(siul2_bases));
base = siul2_bases[pin->mscr.inst];
__ASSERT_NO_MSG(base != 0);
__ASSERT_NO_MSG(pin->mscr.idx < SIUL2_MSCR_MAX_IDX);
sys_write32(pin->mscr.val, (base + SIUL2_MSCR(pin->mscr.idx)));
/* Input Multiplexed Signal Configuration */
if (pin->mscr.val & SIUL2_MSCR_IBE_MASK) {
__ASSERT_NO_MSG(pin->imcr.inst < ARRAY_SIZE(siul2_bases));
base = siul2_bases[pin->imcr.inst];
__ASSERT_NO_MSG(base != 0);
__ASSERT_NO_MSG(pin->imcr.idx < SIUL2_IMCR_MAX_IDX);
sys_write32(pin->imcr.val, (base + SIUL2_IMCR(pin->imcr.idx)));
}
}
int pinctrl_configure_pins(const pinctrl_soc_pin_t *pins, uint8_t pin_cnt, uintptr_t reg)
{
/*
* By invoking Siul2_Port_Ip_Init multiple times on each group of pins,
* some functions like Siul2_Port_Ip_GetPinConfiguration and
* Siul2_Port_Ip_RevertPinConfiguration cannot be used since the internal
* state is not preserved between calls. Nevertheless, those functions
* are not needed to implement Pinctrl driver, so it's safe to use it
* until a public API exists to init each pin individually.
*/
Siul2_Port_Ip_Init(pin_cnt, pins);
ARG_UNUSED(reg);
for (uint8_t i = 0; i < pin_cnt; i++) {
pinctrl_configure_pin(pins++);
}
return 0;
}

View file

@ -82,17 +82,15 @@
status = "okay";
};
siul2: siul2@40290000 {
siul2_0: siul2@40290000 {
reg = <0x40290000 0x10000>;
#address-cells = <1>;
#size-cells = <1>;
eirq0: eirq@40290010 {
compatible = "nxp,s32-siul2-eirq";
reg = <0x40290010 0x04>, <0x40290018 0x04>;
reg-names = "disr0", "direr0";
reg = <0x40290010 0xb4>;
interrupts = <53 0>, <54 0>, <55 0>, <56 0>;
interrupt-names = "0_7", "8_15", "16_23", "24_31";
interrupt-controller;
#interrupt-cells = <2>;
status = "disabled";

View file

@ -217,8 +217,7 @@
eirq0: eirq0@40520010 {
compatible = "nxp,s32-siul2-eirq";
reg = <0x40520010 0x04>, <0x40520018 0x04>;
reg-names = "disr0", "direr0";
reg = <0x40520010 0xb4>;
interrupts = <GIC_SPI 514 IRQ_TYPE_LEVEL IRQ_DEFAULT_PRIORITY>;
interrupt-controller;
#interrupt-cells = <2>;
@ -269,8 +268,7 @@
eirq1: eirq1@40d20010 {
compatible = "nxp,s32-siul2-eirq";
reg = <0x40d20010 0x04>, <0x40d20018 0x04>;
reg-names = "disr0", "direr0";
reg = <0x40d20010 0xb4>;
interrupts = <GIC_SPI 515 IRQ_TYPE_LEVEL IRQ_DEFAULT_PRIORITY>;
interrupt-controller;
#interrupt-cells = <2>;
@ -345,8 +343,7 @@
eirq4: eirq4@42520010 {
compatible = "nxp,s32-siul2-eirq";
reg = <0x42520010 0x04>, <0x42520018 0x04>;
reg-names = "disr0", "direr0";
reg = <0x42520010 0xb4>;
interrupts = <GIC_SPI 516 IRQ_TYPE_LEVEL IRQ_DEFAULT_PRIORITY>;
interrupt-controller;
#interrupt-cells = <2>;
@ -404,7 +401,6 @@
gpiol: gpio@42521710 {
compatible = "nxp,s32-gpio";
reg = <0x42521710 0x02>, <0x42520480 0x40>;
reg-names = "disr0", "direr0";
reg-names = "pgpdo", "mscr";
gpio-controller;
#gpio-cells = <2>;
@ -420,8 +416,7 @@
eirq5: eirq5@42d20010 {
compatible = "nxp,s32-siul2-eirq";
reg = <0x42d20010 0x04>, <0x42d20018 0x04>;
reg-names = "disr0", "direr0";
reg = <0x42d20010 0xb4>;
interrupts = <GIC_SPI 517 IRQ_TYPE_LEVEL IRQ_DEFAULT_PRIORITY>;
interrupt-controller;
#interrupt-cells = <2>;

View file

@ -1,4 +1,4 @@
# Copyright 2022-2023 NXP
# Copyright 2022-2024 NXP
#
# SPDX-License-Identifier: Apache-2.0
@ -12,9 +12,6 @@ properties:
reg:
required: true
reg-names:
required: true
pinctrl-0:
required: true
@ -23,48 +20,44 @@ properties:
filter-prescaler:
type: int
enum: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15]
description: |
Setting the prescaler which selects the clock for all digital filters.
Valid range: 0 - 15.
interrupt-names:
description: |
For platforms that external interrupt lines belong to different interrupt
IDs (i.e. there is no single interrupt handler for all the lines), this
property is used by the shim driver to determine the ISR name as defined
by the HAL.
The naming must follow: <from-line-number>_<to-line-number>, for example:
interrupt-names = "0_7", "8_15", "16_23", "24_31";
Interrupt filter clock prescaler. The prescaler is applied to the input
clock to SIUL2, which is the peripheral clock counter in the SIUL2.
The prescaled filter clock period is:
TIRC * (IFCP + 1)
where:
* TIRC is the internal oscillator period.
* IFCP is 0 to 15.
child-binding:
description: |
NXP S32 SIUL2 External Interrupt line configuration. For each
interrupt line that has specific requirements about digital
glitch filter, a node using this binding must be added, the
name must be "line_<line_number>". For example:
NXP S32 SIUL2 External Interrupt configuration. Specific filter requirements
for each interrupt can be specified by adding a child node to the interrupt
controller, labeled `irq_<interrupt-number>`. For example:
line_0: line_0 {
filter-enable;
filter-counter = <5>;
irq_0: irq_0 {
max-filter-counter = <5>;
};
If the controller has no child node, the digital filter will be
disabled for all external interrupt lines.
This will enable a digital filter counter on the corresponding interrupt
pads to filter out glitches on the inputs. The digital filter will be
disabled for interrupt lines without specified configuration node.
properties:
filter-enable:
type: boolean
required: true
description: |
Enable digital glitch filter to filter out glitches on the input pad.
filter-counter:
max-filter-counter:
type: int
required: true
enum: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15]
description: |
Configuring the filter counter associated with digital glitch filter.
Valid range: 0 - 15.
Maximum Interrupt Filter Counter setting. This value configures the
filter counter associated with the digital glitch filter.
A value of 0 to 2, sets the filter as an all pass filter.
A value of 3 to 15, sets the filter period to (TCK * MAXCNT + n * TCK),
where:
* n can be in the range 0 to 4, and accounts for the uncertainty
factor in filter period calculation.
* TCK is the prescaled filter clock period.
interrupt-cells:
- gpio-pin

View file

@ -1,5 +1,5 @@
/*
* Copyright 2022 NXP
* Copyright 2022, 2024 NXP
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -12,57 +12,67 @@
#ifndef ZEPHYR_DRIVERS_INTERRUPT_CONTROLLER_INTC_EIRQ_NXP_S32_H_
#define ZEPHYR_DRIVERS_INTERRUPT_CONTROLLER_INTC_EIRQ_NXP_S32_H_
#include <Siul2_Icu_Ip.h>
/* Wrapper callback for EIRQ line */
/** NXP SIUL2 EIRQ callback */
typedef void (*eirq_nxp_s32_callback_t)(uint8_t pin, void *arg);
/**
* @brief Unset EIRQ callback for line
*
* @param dev EIRQ device
* @param line EIRQ line
* @brief NXP SIUL2 EIRQ pin activation type
*/
void eirq_nxp_s32_unset_callback(const struct device *dev, uint8_t line);
enum eirq_nxp_s32_trigger {
/** Interrupt triggered on rising edge */
EIRQ_NXP_S32_RISING_EDGE,
/** Interrupt triggered on falling edge */
EIRQ_NXP_S32_FALLING_EDGE,
/** Interrupt triggered on either edge */
EIRQ_NXP_S32_BOTH_EDGES,
};
/**
* @brief Set EIRQ callback for line
* @brief Unset interrupt callback
*
* @param dev EIRQ device
* @param line EIRQ line
* @param cb Callback
* @param pin GPIO pin
* @param arg Callback data
*
* @retval 0 on SUCCESS
* @retval -EBUSY if callback for the line is already set
* @param dev SIUL2 EIRQ device
* @param irq interrupt number
*/
int eirq_nxp_s32_set_callback(const struct device *dev, uint8_t line,
eirq_nxp_s32_callback_t cb, uint8_t pin, void *arg);
void eirq_nxp_s32_unset_callback(const struct device *dev, uint8_t irq);
/**
* @brief Set edge event and enable interrupt for EIRQ line
* @brief Set callback for an interrupt associated with a given pin
*
* @param dev EIRQ device
* @param line EIRQ line
* @param edge_type Type of edge event
* @param dev SIUL2 EIRQ device
* @param irq interrupt number
* @param pin GPIO pin associated with the interrupt
* @param cb callback to install
* @param arg user data to include in callback
*
* @retval 0 on success
* @retval -EBUSY if callback for the interrupt is already set
*/
void eirq_nxp_s32_enable_interrupt(const struct device *dev, uint8_t line,
Siul2_Icu_Ip_EdgeType edge_type);
int eirq_nxp_s32_set_callback(const struct device *dev, uint8_t irq, uint8_t pin,
eirq_nxp_s32_callback_t cb, void *arg);
/**
* @brief Disable interrupt for EIRQ line
* @brief Enable interrupt on a given trigger event
*
* @param dev EIRQ device
* @param line EIRQ line
* @param dev SIUL2 EIRQ device
* @param irq interrupt number
* @param trigger trigger event
*/
void eirq_nxp_s32_disable_interrupt(const struct device *dev, uint8_t line);
void eirq_nxp_s32_enable_interrupt(const struct device *dev, uint8_t irq,
enum eirq_nxp_s32_trigger trigger);
/**
* @brief Get pending interrupt for EIRQ device
* @brief Disable interrupt
*
* @param dev EIRQ device
* @return A mask contains pending flags
* @param dev SIUL2 EIRQ device
* @param irq interrupt number
*/
void eirq_nxp_s32_disable_interrupt(const struct device *dev, uint8_t irq);
/**
* @brief Get pending interrupts
*
* @param dev SIUL2 EIRQ device
* @return A bitmask containing pending pending interrupts
*/
uint32_t eirq_nxp_s32_get_pending(const struct device *dev);

View file

@ -1,153 +0,0 @@
/*
* Copyright 2022-2023 NXP
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_SOC_ARM_NXP_S32_COMMON_PINCTRL_SOC_H_
#define ZEPHYR_SOC_ARM_NXP_S32_COMMON_PINCTRL_SOC_H_
#include <zephyr/devicetree.h>
#include <zephyr/dt-bindings/pinctrl/nxp-s32-pinctrl.h>
#include <zephyr/sys/util_macro.h>
#include <zephyr/types.h>
#include <Siul2_Port_Ip.h>
/** @cond INTERNAL_HIDDEN */
/** @brief Type for NXP S32 pin configuration. */
typedef Siul2_Port_Ip_PinSettingsConfig pinctrl_soc_pin_t;
/* Alias for compatibility with previous RTD versions */
#if !defined(FEATURE_SIUL2_MAX_NUMBER_OF_INPUT) && defined(FEATURE_SIUL2_MAX_NUMBER_OF_INPUT_U8)
#define FEATURE_SIUL2_MAX_NUMBER_OF_INPUT FEATURE_SIUL2_MAX_NUMBER_OF_INPUT_U8
#endif
#if defined(SIUL2_PORT_IP_MULTIPLE_SIUL2_INSTANCES)
#define NXP_S32_SIUL2_IDX(n) \
n == 0 ? IP_SIUL2_0 : (n == 1 ? IP_SIUL2_1 : ( \
n == 3 ? IP_SIUL2_3 : (n == 4 ? IP_SIUL2_4 : ( \
n == 5 ? IP_SIUL2_5 : (NULL)))))
#else
#define NXP_S32_SIUL2_IDX(n) (n == 0 ? IP_SIUL2 : NULL)
#endif
#define NXP_S32_INPUT_BUFFER(group) \
COND_CODE_1(DT_PROP(group, input_enable), (PORT_INPUT_BUFFER_ENABLED), \
(PORT_INPUT_BUFFER_DISABLED))
#define NXP_S32_OUTPUT_BUFFER(group) \
COND_CODE_1(DT_PROP(group, output_enable), (PORT_OUTPUT_BUFFER_ENABLED), \
(PORT_OUTPUT_BUFFER_DISABLED))
#define NXP_S32_INPUT_MUX_REG(group, val) \
COND_CODE_1(DT_PROP(group, input_enable), (NXP_S32_PINMUX_GET_IMCR_IDX(val)), \
(0U))
#define NXP_S32_INPUT_MUX(group, val) \
COND_CODE_1(DT_PROP(group, input_enable), \
((Siul2_Port_Ip_PortInputMux)NXP_S32_PINMUX_GET_IMCR_SSS(val)), \
(PORT_INPUT_MUX_NO_INIT))
#define NXP_S32_PULL_SEL(group) \
COND_CODE_1(DT_PROP(group, bias_pull_up), (PORT_INTERNAL_PULL_UP_ENABLED), \
(COND_CODE_1(DT_PROP(group, bias_pull_down), \
(PORT_INTERNAL_PULL_DOWN_ENABLED), (PORT_INTERNAL_PULL_NOT_ENABLED))))
#if defined(SIUL2_PORT_IP_HAS_ONEBIT_SLEWRATE)
#define NXP_S32_SLEW_RATE(group) \
COND_CODE_1(DT_NODE_HAS_PROP(group, slew_rate), \
(UTIL_CAT(PORT_SLEW_RATE_, DT_STRING_UPPER_TOKEN(group, slew_rate))), \
(PORT_SLEW_RATE_FASTEST))
#else
#define NXP_S32_SLEW_RATE(group) \
COND_CODE_1(DT_NODE_HAS_PROP(group, slew_rate), \
(UTIL_CAT(PORT_SLEW_RATE_CONTROL, DT_PROP(group, slew_rate))), \
(PORT_SLEW_RATE_CONTROL0))
#endif
#define NXP_S32_DRIVE_STRENGTH(group) \
COND_CODE_1(DT_PROP(group, nxp_drive_strength), \
(PORT_DRIVE_STRENTGTH_ENABLED), (PORT_DRIVE_STRENTGTH_DISABLED))
#define NXP_S32_INVERT(group) \
COND_CODE_1(DT_PROP(group, nxp_invert), \
(PORT_INVERT_ENABLED), (PORT_INVERT_DISABLED))
/* To enable open drain both OBE and ODE bits need to be set */
#define NXP_S32_OPEN_DRAIN(group) \
(DT_PROP(group, drive_open_drain) && DT_PROP(group, output_enable) ? \
(PORT_OPEN_DRAIN_ENABLED) : (PORT_OPEN_DRAIN_DISABLED))
/* Only a single input mux is configured, the rest is not used */
#define NXP_S32_INPUT_MUX_NO_INIT \
[1 ... (FEATURE_SIUL2_MAX_NUMBER_OF_INPUT-1)] = PORT_INPUT_MUX_NO_INIT
#define NXP_S32_PINMUX_INIT(group, val) \
.base = NXP_S32_SIUL2_IDX(NXP_S32_PINMUX_GET_SIUL2_IDX(val)), \
.pinPortIdx = NXP_S32_PINMUX_GET_MSCR_IDX(val), \
.mux = (Siul2_Port_Ip_PortMux)NXP_S32_PINMUX_GET_MSCR_SSS(val), \
.inputMux = { \
NXP_S32_INPUT_MUX(group, val), \
NXP_S32_INPUT_MUX_NO_INIT \
}, \
.inputMuxReg = { \
NXP_S32_INPUT_MUX_REG(group, val) \
}, \
.inputBuffer = NXP_S32_INPUT_BUFFER(group), \
.outputBuffer = NXP_S32_OUTPUT_BUFFER(group), \
.pullConfig = NXP_S32_PULL_SEL(group), \
.safeMode = PORT_SAFE_MODE_DISABLED, \
.slewRateCtrlSel = NXP_S32_SLEW_RATE(group), \
.initValue = PORT_PIN_LEVEL_NOTCHANGED_U8, \
IF_ENABLED(__DEBRACKET FEATURE_SIUL2_PORT_IP_HAS_DRIVE_STRENGTH, \
(.driveStrength = NXP_S32_DRIVE_STRENGTH(group),)) \
IF_ENABLED(__DEBRACKET FEATURE_SIUL2_PORT_IP_HAS_INVERT_DATA, \
(.invert = NXP_S32_INVERT(group),)) \
IF_ENABLED(__DEBRACKET FEATURE_SIUL2_PORT_IP_HAS_OPEN_DRAIN, \
(.openDrain = NXP_S32_OPEN_DRAIN(group),)) \
IF_ENABLED(__DEBRACKET FEATURE_SIUL2_PORT_IP_HAS_INPUT_FILTER, \
(.inputFilter = PORT_INPUT_FILTER_DISABLED,)) \
IF_ENABLED(__DEBRACKET FEATURE_SIUL2_PORT_IP_HAS_RECEIVER_SELECT, \
(.receiverSel = PORT_RECEIVER_ENABLE_SINGLE_ENDED,)) \
IF_ENABLED(__DEBRACKET FEATURE_SIUL2_PORT_IP_HAS_HYSTERESIS, \
(.hysteresis = PORT_HYSTERESIS_DISABLED,)) \
IF_ENABLED(__DEBRACKET FEATURE_SIUL2_PORT_IP_HAS_ANALOG_PAD_CONTROL, \
(.analogPadControl = PORT_ANALOG_PAD_CONTROL_DISABLED,)) \
IF_ENABLED(__DEBRACKET FEATURE_SIUL2_PORT_IP_HAS_TERMINATION_RESISTOR, \
(.terminationResistor = PORT_TERMINATION_RESISTOR_DISABLED,)) \
IF_ENABLED(__DEBRACKET FEATURE_SIUL2_PORT_IP_HAS_CURRENT_REFERENCE_CONTROL, \
(.currentReferenceControl = PORT_CURRENT_REFERENCE_CONTROL_DISABLED,)) \
IF_ENABLED(__DEBRACKET FEATURE_SIUL2_PORT_IP_HAS_RX_CURRENT_BOOST, \
(.rxCurrentBoost = PORT_RX_CURRENT_BOOST_DISABLED,)) \
IF_ENABLED(__DEBRACKET FEATURE_SIUL2_PORT_IP_HAS_PULL_KEEPER, \
(.pullKeep = PORT_PULL_KEEP_DISABLED,))
/**
* @brief Utility macro to initialize each pin.
*
*
* @param group Group node identifier.
* @param prop Property name.
* @param idx Property entry index.
*/
#define Z_PINCTRL_STATE_PIN_INIT(group, prop, idx) \
{ \
NXP_S32_PINMUX_INIT(group, DT_PROP_BY_IDX(group, prop, idx)) \
},
/**
* @brief Utility macro to initialize state pins contained in a given property.
*
* @param node_id Node identifier.
* @param prop Property name describing state pins.
*/
#define Z_PINCTRL_STATE_PINS_INIT(node_id, prop) \
{DT_FOREACH_CHILD_VARGS(DT_PHANDLE(node_id, prop), \
DT_FOREACH_PROP_ELEM, pinmux, \
Z_PINCTRL_STATE_PIN_INIT)}
/** @endcond */
#endif /* ZEPHYR_SOC_ARM_NXP_S32_COMMON_PINCTRL_SOC_H_ */

View file

@ -0,0 +1,52 @@
/*
* Copyright 2022-2024 NXP
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_SOC_NXP_S32_COMMON_SIUL2_PINCTRL_H_
#define ZEPHYR_SOC_NXP_S32_COMMON_SIUL2_PINCTRL_H_
#include <zephyr/devicetree.h>
#include <zephyr/types.h>
/** @cond INTERNAL_HIDDEN */
struct pinctrl_soc_reg {
uint8_t inst;
uint16_t idx;
uint32_t val;
};
/** @brief Type for NXP SIUL2 pin configuration. */
typedef struct {
struct pinctrl_soc_reg mscr;
struct pinctrl_soc_reg imcr;
} pinctrl_soc_pin_t;
/**
* @brief Utility macro to initialize each pin.
*
*
* @param group Group node identifier.
* @param prop Property name.
* @param idx Property entry index.
*/
#define Z_PINCTRL_STATE_PIN_INIT(group, prop, idx) \
{NXP_S32_PINMUX_INIT(group, DT_PROP_BY_IDX(group, prop, idx))},
/**
* @brief Utility macro to initialize state pins contained in a given property.
*
* @param node_id Node identifier.
* @param prop Property name describing state pins.
*/
#define Z_PINCTRL_STATE_PINS_INIT(node_id, prop) \
{ \
DT_FOREACH_CHILD_VARGS(DT_PHANDLE(node_id, prop), DT_FOREACH_PROP_ELEM, pinmux, \
Z_PINCTRL_STATE_PIN_INIT) \
}
/** @endcond */
#endif /* ZEPHYR_SOC_NXP_S32_COMMON_SIUL2_PINCTRL_H_ */

View file

@ -0,0 +1,62 @@
/*
* Copyright 2022-2024 NXP
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_SOC_NXP_S32_S32K3_PINCTRL_SOC_H_
#define ZEPHYR_SOC_NXP_S32_S32K3_PINCTRL_SOC_H_
#include <zephyr/dt-bindings/pinctrl/nxp-s32-pinctrl.h>
#include <zephyr/sys/util.h>
#include "../common/siul2_pinctrl.h"
/* SIUL2 Multiplexed Signal Configuration */
#define SIUL2_MSCR_SSS_MASK GENMASK(3, 0)
#define SIUL2_MSCR_SSS(v) FIELD_PREP(SIUL2_MSCR_SSS_MASK, (v))
#define SIUL2_MSCR_SMC_MASK BIT(5)
#define SIUL2_MSCR_SMC(v) FIELD_PREP(SIUL2_MSCR_SMC_MASK, (v))
#define SIUL2_MSCR_IFE_MASK BIT(6)
#define SIUL2_MSCR_IFE(v) FIELD_PREP(SIUL2_MSCR_IFE_MASK, (v))
#define SIUL2_MSCR_DSE_MASK BIT(8)
#define SIUL2_MSCR_DSE(v) FIELD_PREP(SIUL2_MSCR_DSE_MASK, (v))
#define SIUL2_MSCR_PUS_MASK BIT(11)
#define SIUL2_MSCR_PUS(v) FIELD_PREP(SIUL2_MSCR_PUS_MASK, (v))
#define SIUL2_MSCR_PUE_MASK BIT(13)
#define SIUL2_MSCR_PUE(v) FIELD_PREP(SIUL2_MSCR_PUE_MASK, (v))
#define SIUL2_MSCR_SRC_MASK BIT(14)
#define SIUL2_MSCR_SRC(v) FIELD_PREP(SIUL2_MSCR_SRC_MASK, (v))
#define SIUL2_MSCR_PKE_MASK BIT(16)
#define SIUL2_MSCR_PKE(v) FIELD_PREP(SIUL2_MSCR_PKE_MASK, (v))
#define SIUL2_MSCR_INV_MASK BIT(17)
#define SIUL2_MSCR_INV(v) FIELD_PREP(SIUL2_MSCR_INV_MASK, (v))
#define SIUL2_MSCR_IBE_MASK BIT(19)
#define SIUL2_MSCR_IBE(v) FIELD_PREP(SIUL2_MSCR_IBE_MASK, (v))
#define SIUL2_MSCR_OBE_MASK BIT(21)
#define SIUL2_MSCR_OBE(v) FIELD_PREP(SIUL2_MSCR_OBE_MASK, (v))
/* SIUL2 Input Multiplexed Signal Configuration */
#define SIUL2_IMCR_SSS_MASK GENMASK(3, 0)
#define SIUL2_IMCR_SSS(v) FIELD_PREP(SIUL2_IMCR_SSS_MASK, (v))
#define NXP_S32_PINMUX_INIT(group, value) \
.mscr = { \
.inst = NXP_S32_PINMUX_GET_SIUL2_IDX(value), \
.idx = NXP_S32_PINMUX_GET_MSCR_IDX(value), \
.val = SIUL2_MSCR_SSS(NXP_S32_PINMUX_GET_MSCR_SSS(value)) | \
SIUL2_MSCR_OBE(DT_PROP(group, output_enable)) | \
SIUL2_MSCR_IBE(DT_PROP(group, input_enable)) | \
SIUL2_MSCR_PUE(DT_PROP(group, bias_pull_up) || \
DT_PROP(group, bias_pull_down)) | \
SIUL2_MSCR_PUS(DT_PROP(group, bias_pull_up)) | \
SIUL2_MSCR_SRC(DT_ENUM_IDX(group, slew_rate)) | \
SIUL2_MSCR_DSE(DT_PROP(group, nxp_drive_strength)) | \
SIUL2_MSCR_INV(DT_PROP(group, nxp_invert)) \
}, \
.imcr = { \
.inst = NXP_S32_PINMUX_GET_SIUL2_IDX(value), \
.idx = NXP_S32_PINMUX_GET_IMCR_IDX(value), \
.val = SIUL2_IMCR_SSS(NXP_S32_PINMUX_GET_IMCR_SSS(value)), \
}
#endif /* ZEPHYR_SOC_NXP_S32_S32K3_PINCTRL_SOC_H_ */

View file

@ -14,9 +14,4 @@
#include <cmsis_rtos_v2_adapt.h>
#endif
/* Aliases for peripheral base addresses */
/* SIUL2 */
#define IP_SIUL2_0_BASE IP_SIUL2_BASE
#endif /* _NXP_S32_S32K_SOC_H_ */

View file

@ -0,0 +1,64 @@
/*
* Copyright 2022-2024 NXP
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_SOC_NXP_S32_S32ZE_PINCTRL_SOC_H_
#define ZEPHYR_SOC_NXP_S32_S32ZE_PINCTRL_SOC_H_
#include <zephyr/dt-bindings/pinctrl/nxp-s32-pinctrl.h>
#include <zephyr/sys/util.h>
#include "../common/siul2_pinctrl.h"
/* SIUL2 Multiplexed Signal Configuration */
#define SIUL2_MSCR_SSS_MASK GENMASK(2, 0)
#define SIUL2_MSCR_SSS(v) FIELD_PREP(SIUL2_MSCR_SSS_MASK, (v))
#define SIUL2_MSCR_SMC_MASK GENMASK(7, 4)
#define SIUL2_MSCR_SMC(v) FIELD_PREP(SIUL2_MSCR_SMC_MASK, (v))
#define SIUL2_MSCR_TRC_MASK BIT(8)
#define SIUL2_MSCR_TRC(v) FIELD_PREP(SIUL2_MSCR_TRC_MASK, (v))
#define SIUL2_MSCR_RCVR_MASK BIT(10)
#define SIUL2_MSCR_RCVR(v) FIELD_PREP(SIUL2_MSCR_RCVR_MASK, (v))
#define SIUL2_MSCR_CREF_MASK BIT(11)
#define SIUL2_MSCR_CREF(v) FIELD_PREP(SIUL2_MSCR_CREF_MASK, (v))
#define SIUL2_MSCR_PUS_MASK BIT(12)
#define SIUL2_MSCR_PUS(v) FIELD_PREP(SIUL2_MSCR_PUS_MASK, (v))
#define SIUL2_MSCR_PUE_MASK BIT(13)
#define SIUL2_MSCR_PUE(v) FIELD_PREP(SIUL2_MSCR_PUE_MASK, (v))
#define SIUL2_MSCR_SRE_MASK GENMASK(16, 14)
#define SIUL2_MSCR_SRE(v) FIELD_PREP(SIUL2_MSCR_SRE_MASK, (v))
#define SIUL2_MSCR_RXCB_MASK BIT(17)
#define SIUL2_MSCR_RXCB(v) FIELD_PREP(SIUL2_MSCR_RXCB_MASK, (v))
#define SIUL2_MSCR_IBE_MASK BIT(19)
#define SIUL2_MSCR_IBE(v) FIELD_PREP(SIUL2_MSCR_IBE_MASK, (v))
#define SIUL2_MSCR_ODE_MASK BIT(20)
#define SIUL2_MSCR_ODE(v) FIELD_PREP(SIUL2_MSCR_ODE_MASK, (v))
#define SIUL2_MSCR_OBE_MASK BIT(21)
#define SIUL2_MSCR_OBE(v) FIELD_PREP(SIUL2_MSCR_OBE_MASK, (v))
/* SIUL2 Input Multiplexed Signal Configuration */
#define SIUL2_IMCR_SSS_MASK GENMASK(2, 0)
#define SIUL2_IMCR_SSS(v) FIELD_PREP(SIUL2_IMCR_SSS_MASK, (v))
#define NXP_S32_PINMUX_INIT(group, value) \
.mscr = { \
.inst = NXP_S32_PINMUX_GET_SIUL2_IDX(value), \
.idx = NXP_S32_PINMUX_GET_MSCR_IDX(value), \
.val = SIUL2_MSCR_SSS(NXP_S32_PINMUX_GET_MSCR_SSS(value)) | \
SIUL2_MSCR_OBE(DT_PROP(group, output_enable)) | \
SIUL2_MSCR_IBE(DT_PROP(group, input_enable)) | \
SIUL2_MSCR_PUE(DT_PROP(group, bias_pull_up) || \
DT_PROP(group, bias_pull_down)) | \
SIUL2_MSCR_PUS(DT_PROP(group, bias_pull_up)) | \
SIUL2_MSCR_SRE(DT_PROP(group, slew_rate)) | \
SIUL2_MSCR_ODE(DT_PROP(group, drive_open_drain) && \
DT_PROP(group, output_enable)) \
}, \
.imcr = { \
.inst = NXP_S32_PINMUX_GET_SIUL2_IDX(value), \
.idx = NXP_S32_PINMUX_GET_IMCR_IDX(value), \
.val = SIUL2_IMCR_SSS(NXP_S32_PINMUX_GET_IMCR_SSS(value)), \
}
#endif /* ZEPHYR_SOC_NXP_S32_S32ZE_PINCTRL_SOC_H_ */

View file

@ -22,9 +22,6 @@
/* Aliases for peripheral base addresses */
/* SIUL2 */
#define IP_SIUL2_2_BASE 0U /* instance does not exist on this SoC */
/* LINFlexD*/
#define IP_LINFLEX_12_BASE IP_MSC_0_LIN_BASE

View file

@ -198,7 +198,7 @@ manifest:
groups:
- hal
- name: hal_nxp
revision: 862e001504bd6e0a4feade6a718e9f973116849c
revision: 272f84ca60afc759d81ed94100e78b37a859d3ff
path: modules/hal/nxp
groups:
- hal