drivers: pinctrl: microchip: mec: One PINCTRL driver for all MEC parts
GPIO hardware in Microchip MEC parts is the same except for the MUX field (number of alternate functions). We modify the old XEC PINCTRL driver to work on all MEC parts and also be independent of HAL and CMSIS register structures. During development we found a DT issue with DT_ENUM_IDX_OR always inserting the default value. Worked around by converting slew rate and drive strength to YAML integer type and created defines for the values in the dt-bindings header. Signed-off-by: Scott Worley <scott.worley@microchip.com>
This commit is contained in:
committed by
Henrik Brix Andersen
parent
7ed9c743c0
commit
99ce899c22
@@ -28,7 +28,6 @@ zephyr_library_sources_ifdef(CONFIG_PINCTRL_IMX_SCU pinctrl_imx_scu.c)
|
||||
zephyr_library_sources_ifdef(CONFIG_PINCTRL_INFINEON_CAT1 pinctrl_infineon.c)
|
||||
zephyr_library_sources_ifdef(CONFIG_PINCTRL_ITE_IT8XXX2 pinctrl_ite_it8xxx2.c)
|
||||
zephyr_library_sources_ifdef(CONFIG_PINCTRL_MAX32 pinctrl_max32.c)
|
||||
zephyr_library_sources_ifdef(CONFIG_PINCTRL_MCHP_MEC5 pinctrl_mchp_mec5.c)
|
||||
zephyr_library_sources_ifdef(CONFIG_PINCTRL_MCHP_PORT_G1 pinctrl_mchp_port_g1.c)
|
||||
zephyr_library_sources_ifdef(CONFIG_PINCTRL_MCHP_XEC pinctrl_mchp_xec.c)
|
||||
zephyr_library_sources_ifdef(CONFIG_PINCTRL_MCI_IO_MUX pinctrl_mci_io_mux.c)
|
||||
|
||||
@@ -62,7 +62,6 @@ source "drivers/pinctrl/Kconfig.lpc_iocon"
|
||||
source "drivers/pinctrl/Kconfig.max32"
|
||||
source "drivers/pinctrl/Kconfig.mchp"
|
||||
source "drivers/pinctrl/Kconfig.mci_io_mux"
|
||||
source "drivers/pinctrl/Kconfig.mec5"
|
||||
source "drivers/pinctrl/Kconfig.mspm0"
|
||||
source "drivers/pinctrl/Kconfig.npcx"
|
||||
source "drivers/pinctrl/Kconfig.nrf"
|
||||
|
||||
@@ -1,9 +0,0 @@
|
||||
# Copyright (c) 2024 Microchip Technology Inc.
|
||||
# SPDX-License-Identifier: Apache-2.0
|
||||
|
||||
config PINCTRL_MCHP_MEC5
|
||||
bool "Pin controller driver for MCHP MEC5 MCUs"
|
||||
default y
|
||||
depends on DT_HAS_MICROCHIP_MEC5_PINCTRL_ENABLED
|
||||
help
|
||||
Enable pin controller driver for Microchip MEC5 MCUs
|
||||
@@ -1,166 +0,0 @@
|
||||
/*
|
||||
* Copyright (c) 2016 Open-RnD Sp. z o.o.
|
||||
* Copyright (c) 2021 Linaro Limited
|
||||
* Copyright (c) 2021 Nordic Semiconductor ASA
|
||||
* Copyright (c) 2024 Microchip Technology Inc.
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
#define DT_DRV_COMPAT microchip_mec5_pinctrl
|
||||
|
||||
#include <zephyr/drivers/pinctrl.h>
|
||||
#include <zephyr/dt-bindings/pinctrl/mchp-xec-pinctrl.h>
|
||||
#include <mec_gpio_api.h>
|
||||
|
||||
static const struct mec_gpio_props cfg1[] = {
|
||||
{MEC_GPIO_OSEL_PROP_ID, MEC_GPIO_PROP_OSEL_CTRL},
|
||||
{MEC_GPIO_INPAD_DIS_PROP_ID, MEC_GPIO_PROP_INPAD_EN},
|
||||
};
|
||||
|
||||
/* DT enable booleans take precedence over disable booleans.
|
||||
* We initially clear alternate output disable allowing us to set output state
|
||||
* in the control register. Hardware sets output state bit in both control and
|
||||
* parallel output register bits. Alternate output disable only controls which
|
||||
* register bit is writable by the EC. We also clear the input pad disable
|
||||
* bit because we need the input pin state and we don't know if the requested
|
||||
* alternate function is input or bi-directional.
|
||||
* Note 1: hardware allows input and output to be simultaneously enabled.
|
||||
* Note 2: hardware interrupt detection is only on the input path.
|
||||
*/
|
||||
static int mec5_config_pin(uint32_t pinmux, uint32_t altf)
|
||||
{
|
||||
uint32_t conf = pinmux;
|
||||
uint32_t pin = 0, temp = 0;
|
||||
int ret = 0;
|
||||
size_t idx = 0;
|
||||
struct mec_gpio_props cfg2[12];
|
||||
|
||||
ret = mec_hal_gpio_pin_num(MCHP_XEC_PINMUX_PORT(pinmux), MCHP_XEC_PINMUX_PIN(pinmux), &pin);
|
||||
if (ret) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
ret = mec_hal_gpio_set_props(pin, cfg1, ARRAY_SIZE(cfg1));
|
||||
if (ret) {
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
/* slew rate */
|
||||
temp = (conf >> MCHP_XEC_SLEW_RATE_POS) & MCHP_XEC_SLEW_RATE_MSK0;
|
||||
if (temp != MCHP_XEC_SLEW_RATE_MSK0) {
|
||||
cfg2[idx].prop = MEC_GPIO_SLEW_RATE_ID;
|
||||
cfg2[idx].val = (uint8_t)MEC_GPIO_SLEW_RATE_SLOW;
|
||||
if (temp == MCHP_XEC_SLEW_RATE_FAST0) {
|
||||
cfg2[idx].val = (uint8_t)MEC_GPIO_SLEW_RATE_FAST;
|
||||
}
|
||||
idx++;
|
||||
}
|
||||
|
||||
/* drive strength */
|
||||
temp = (conf >> MCHP_XEC_DRV_STR_POS) & MCHP_XEC_DRV_STR_MSK0;
|
||||
if (temp != MCHP_XEC_DRV_STR_MSK0) {
|
||||
cfg2[idx].prop = MEC_GPIO_DRV_STR_ID;
|
||||
cfg2[idx].val = (uint8_t)(temp - 1u);
|
||||
idx++;
|
||||
}
|
||||
|
||||
/* Touch internal pull-up/pull-down? */
|
||||
cfg2[idx].prop = MEC_GPIO_PUD_PROP_ID;
|
||||
if (conf & BIT(MCHP_XEC_NO_PUD_POS)) {
|
||||
cfg2[idx++].val = MEC_GPIO_PROP_NO_PUD;
|
||||
} else if (conf & BIT(MCHP_XEC_PU_POS)) {
|
||||
cfg2[idx++].val = MEC_GPIO_PROP_PULL_UP;
|
||||
} else if (conf & BIT(MCHP_XEC_PD_POS)) {
|
||||
cfg2[idx++].val = MEC_GPIO_PROP_PULL_DN;
|
||||
}
|
||||
|
||||
/* Touch output enable. We always enable input */
|
||||
if (conf & (BIT(MCHP_XEC_OUT_DIS_POS) | BIT(MCHP_XEC_OUT_EN_POS))) {
|
||||
cfg2[idx].prop = MEC_GPIO_DIR_PROP_ID;
|
||||
cfg2[idx].val = MEC_GPIO_PROP_DIR_IN;
|
||||
if (conf & BIT(MCHP_XEC_OUT_EN_POS)) {
|
||||
cfg2[idx].val = MEC_GPIO_PROP_DIR_OUT;
|
||||
}
|
||||
idx++;
|
||||
}
|
||||
|
||||
/* Touch output state? Bit can be set even if the direction is input only */
|
||||
if (conf & (BIT(MCHP_XEC_OUT_LO_POS) | BIT(MCHP_XEC_OUT_HI_POS))) {
|
||||
cfg2[idx].prop = MEC_GPIO_CTRL_OUT_VAL_ID;
|
||||
cfg2[idx].val = 0u;
|
||||
if (conf & BIT(MCHP_XEC_OUT_HI_POS)) {
|
||||
cfg2[idx].val = 1u;
|
||||
}
|
||||
idx++;
|
||||
}
|
||||
|
||||
/* Touch output buffer type? */
|
||||
if (conf & (BIT(MCHP_XEC_PUSH_PULL_POS) | BIT(MCHP_XEC_OPEN_DRAIN_POS))) {
|
||||
cfg2[idx].prop = MEC_GPIO_OBUFT_PROP_ID;
|
||||
cfg2[idx].val = MEC_GPIO_PROP_PUSH_PULL;
|
||||
if (conf & BIT(MCHP_XEC_OPEN_DRAIN_POS)) {
|
||||
cfg2[idx].val = MEC_GPIO_PROP_OPEN_DRAIN;
|
||||
}
|
||||
idx++;
|
||||
}
|
||||
|
||||
/* Always touch power gate */
|
||||
cfg2[idx].prop = MEC_GPIO_PWRGT_PROP_ID;
|
||||
cfg2[idx].val = MEC_GPIO_PROP_PWRGT_VTR;
|
||||
if (conf & BIT(MCHP_XEC_PIN_LOW_POWER_POS)) {
|
||||
cfg2[idx].val = MEC_GPIO_PROP_PWRGT_OFF;
|
||||
}
|
||||
idx++;
|
||||
|
||||
/* Always touch MUX (alternate function) */
|
||||
cfg2[idx].prop = MEC_GPIO_MUX_PROP_ID;
|
||||
cfg2[idx].val = (uint8_t)altf;
|
||||
idx++;
|
||||
|
||||
/* Always touch invert of alternate function. Need another bit to avoid touching */
|
||||
cfg2[idx].prop = MEC_GPIO_FUNC_POL_PROP_ID;
|
||||
cfg2[idx].val = MEC_GPIO_PROP_FUNC_OUT_NON_INV;
|
||||
if (conf & BIT(MCHP_XEC_FUNC_INV_POS)) {
|
||||
cfg2[idx].val = MEC_GPIO_PROP_FUNC_OUT_INV;
|
||||
}
|
||||
idx++;
|
||||
|
||||
/* HW sets output state set in control & parallel regs */
|
||||
ret = mec_hal_gpio_set_props(pin, cfg2, idx);
|
||||
if (ret) {
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
/* make output state in control read-only in control and read-write in parallel reg */
|
||||
ret = mec_hal_gpio_set_property(pin, MEC_GPIO_OSEL_PROP_ID, MEC_GPIO_PROP_OSEL_PAROUT);
|
||||
if (ret) {
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int pinctrl_configure_pins(const pinctrl_soc_pin_t *pins, uint8_t pin_cnt, uintptr_t reg)
|
||||
{
|
||||
uint32_t pinmux, func;
|
||||
int ret;
|
||||
|
||||
ARG_UNUSED(reg);
|
||||
|
||||
for (uint8_t i = 0U; i < pin_cnt; i++) {
|
||||
pinmux = pins[i];
|
||||
|
||||
func = MCHP_XEC_PINMUX_FUNC(pinmux);
|
||||
if (func >= MCHP_AFMAX) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
ret = mec5_config_pin(pinmux, func);
|
||||
if (ret < 0) {
|
||||
return ret;
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
@@ -9,8 +9,14 @@
|
||||
|
||||
#define DT_DRV_COMPAT microchip_xec_pinctrl
|
||||
|
||||
#include <zephyr/drivers/pinctrl.h>
|
||||
#include <soc.h>
|
||||
#include <zephyr/arch/cpu.h>
|
||||
#include <zephyr/devicetree.h>
|
||||
#include <zephyr/drivers/pinctrl.h>
|
||||
#include <zephyr/dt-bindings/pinctrl/mchp-xec-pinctrl.h>
|
||||
#include <zephyr/sys/sys_io.h>
|
||||
|
||||
#define XEC_GPIO_PORT_REG_SPACE 0x80u
|
||||
|
||||
/*
|
||||
* Microchip XEC: each GPIO pin has two 32-bit control register.
|
||||
@@ -21,31 +27,31 @@
|
||||
* parent node. A zero value in the PINCTRL pinmux field means
|
||||
* do not touch.
|
||||
*/
|
||||
static void config_drive_slew(struct gpio_regs * const regs, uint32_t idx, uint32_t conf)
|
||||
static void config_drive_slew(mm_reg_t gpio_cr1_addr, const pinctrl_soc_pin_t *p)
|
||||
{
|
||||
uint32_t slew = (conf >> MCHP_XEC_SLEW_RATE_POS) & MCHP_XEC_SLEW_RATE_MSK0;
|
||||
uint32_t drvstr = (conf >> MCHP_XEC_DRV_STR_POS) & MCHP_XEC_DRV_STR_MSK0;
|
||||
mm_reg_t gpio_cr2_addr = gpio_cr1_addr + MEC_GPIO_CR2_OFS;
|
||||
uint32_t msk = 0, val = 0;
|
||||
|
||||
if (slew) {
|
||||
msk |= MCHP_GPIO_CTRL2_SLEW_MASK;
|
||||
/* slow slew value is 0 */
|
||||
if (slew == MCHP_XEC_SLEW_RATE_FAST0) {
|
||||
val |= MCHP_GPIO_CTRL2_SLEW_FAST;
|
||||
if (p->slew_rate != 0) { /* touch slew rate? */
|
||||
msk |= MEC_GPIO_CR2_SLEW_MSK;
|
||||
if (p->slew_rate > 1u) {
|
||||
val |= MEC_GPIO_CR2_SLEW_SET(MEC_GPIO_CR2_SLEW_SLOW);
|
||||
} else {
|
||||
val |= MEC_GPIO_CR2_SLEW_SET(MEC_GPIO_CR2_SLEW_FAST);
|
||||
}
|
||||
}
|
||||
|
||||
if (drvstr) {
|
||||
msk |= MCHP_GPIO_CTRL2_DRV_STR_MASK;
|
||||
/* drive strength values are 0 based */
|
||||
val |= ((drvstr - 1u) << MCHP_GPIO_CTRL2_DRV_STR_POS);
|
||||
if (p->drive_str != 0) { /* touch drive strength? */
|
||||
msk |= MEC_GPIO_CR2_DSTR_MSK;
|
||||
val |= MEC_GPIO_CR2_DSTR_SET((uint32_t)p->drive_str - 1u);
|
||||
}
|
||||
|
||||
if (!msk) {
|
||||
if (msk == 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
regs->CTRL2[idx] = (regs->CTRL2[idx] & ~msk) | (val & msk);
|
||||
val = (val & msk) | (sys_read32(gpio_cr2_addr) & ~msk);
|
||||
sys_write32(val, gpio_cr2_addr);
|
||||
}
|
||||
|
||||
/*
|
||||
@@ -56,21 +62,21 @@ static void config_drive_slew(struct gpio_regs * const regs, uint32_t idx, uint3
|
||||
* If pull up and/or down is set enable the respective pull or both for what
|
||||
* MCHP calls repeater(keeper) mode.
|
||||
*/
|
||||
static uint32_t prog_pud(uint32_t pcr1, uint32_t conf)
|
||||
static uint32_t prog_pud(uint32_t pcr1, const pinctrl_soc_pin_t *p)
|
||||
{
|
||||
if (conf & BIT(MCHP_XEC_NO_PUD_POS)) {
|
||||
pcr1 &= ~(MCHP_GPIO_CTRL_PUD_MASK);
|
||||
pcr1 |= MCHP_GPIO_CTRL_PUD_NONE;
|
||||
if (p->no_pud != 0) {
|
||||
pcr1 &= ~(MEC_GPIO_CR1_PUD_MSK);
|
||||
pcr1 |= MEC_GPIO_CR1_PUD_NONE;
|
||||
return pcr1;
|
||||
}
|
||||
|
||||
if (conf & (BIT(MCHP_XEC_PU_POS) | BIT(MCHP_XEC_PD_POS))) {
|
||||
pcr1 &= ~(MCHP_GPIO_CTRL_PUD_MASK);
|
||||
if (conf & BIT(MCHP_XEC_PU_POS)) {
|
||||
pcr1 |= MCHP_GPIO_CTRL_PUD_PU;
|
||||
if ((p->pd != 0) || (p->pu != 0)) {
|
||||
pcr1 &= ~(MEC_GPIO_CR1_PUD_MSK);
|
||||
if (p->pu != 0) {
|
||||
pcr1 |= MEC_GPIO_CR1_PUD_PU;
|
||||
}
|
||||
if (conf & BIT(MCHP_XEC_PD_POS)) {
|
||||
pcr1 |= MCHP_GPIO_CTRL_PUD_PD;
|
||||
if (p->pd != 0) {
|
||||
pcr1 |= MEC_GPIO_CR1_PUD_PD;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -88,100 +94,108 @@ static uint32_t prog_pud(uint32_t pcr1, uint32_t conf)
|
||||
* Note 1: hardware allows input and output to be simultaneously enabled.
|
||||
* Note 2: hardware interrupt detection is only on the input path.
|
||||
*/
|
||||
static int xec_config_pin(uint32_t portpin, uint32_t conf, uint32_t altf)
|
||||
static int xec_config_pin(uint32_t portpin, const pinctrl_soc_pin_t *p, uint32_t altf)
|
||||
{
|
||||
struct gpio_regs * const regs = (struct gpio_regs * const)DT_INST_REG_ADDR(0);
|
||||
mm_reg_t gpio_cr1_addr = (mm_reg_t)DT_INST_REG_ADDR(0);
|
||||
uint32_t port = MCHP_XEC_PINMUX_PORT(portpin);
|
||||
uint32_t pin = (uint32_t)MCHP_XEC_PINMUX_PIN(portpin);
|
||||
uint32_t idx = 0u, pcr1 = 0u;
|
||||
uint32_t pcr1 = 0u;
|
||||
|
||||
if (port >= NUM_MCHP_GPIO_PORTS) {
|
||||
if (port >= MEC_GPIO_MAX_PORTS) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
/* MCHP XEC family is 32 pins per port */
|
||||
idx = (port * 32U) + pin;
|
||||
/* MCHP XEC family Control 1 and 2 are 32-bit registers */
|
||||
gpio_cr1_addr += (port * XEC_GPIO_PORT_REG_SPACE) + (pin * 4u);
|
||||
|
||||
config_drive_slew(regs, idx, conf);
|
||||
config_drive_slew(gpio_cr1_addr, p);
|
||||
|
||||
/* Clear alternate output disable and input pad disable */
|
||||
regs->CTRL[idx] &= ~(BIT(MCHP_GPIO_CTRL_AOD_POS) | BIT(MCHP_GPIO_CTRL_INPAD_DIS_POS));
|
||||
pcr1 = regs->CTRL[idx]; /* current configuration including pin input state */
|
||||
pcr1 = regs->CTRL[idx]; /* read multiple times to allow propagation from pad */
|
||||
pcr1 = regs->CTRL[idx]; /* Is this necessary? */
|
||||
pcr1 = sys_read32(gpio_cr1_addr) &
|
||||
~(BIT(MEC_GPIO_CR1_OCR_POS) | BIT(MEC_GPIO_CR1_INPD_POS));
|
||||
sys_write32(pcr1, gpio_cr1_addr);
|
||||
pcr1 = sys_read32(gpio_cr1_addr);
|
||||
|
||||
pcr1 = prog_pud(pcr1, conf);
|
||||
pcr1 = prog_pud(pcr1, p);
|
||||
|
||||
/* Touch output enable. We always enable input */
|
||||
if (conf & BIT(MCHP_XEC_OUT_DIS_POS)) {
|
||||
pcr1 &= ~(MCHP_GPIO_CTRL_DIR_OUTPUT);
|
||||
if (p->out_dis != 0) {
|
||||
pcr1 &= ~(MEC_GPIO_CR1_DIR_MSK);
|
||||
pcr1 |= MEC_GPIO_CR1_DIR_SET(MEC_GPIO_CR1_DIR_IN);
|
||||
}
|
||||
if (conf & BIT(MCHP_XEC_OUT_EN_POS)) {
|
||||
pcr1 |= MCHP_GPIO_CTRL_DIR_OUTPUT;
|
||||
|
||||
if (p->out_en != 0) {
|
||||
pcr1 &= ~(MEC_GPIO_CR1_DIR_MSK);
|
||||
pcr1 |= MEC_GPIO_CR1_DIR_SET(MEC_GPIO_CR1_DIR_OUT);
|
||||
}
|
||||
|
||||
/* Touch output state? Bit can be set even if the direction is input only */
|
||||
if (conf & BIT(MCHP_XEC_OUT_LO_POS)) {
|
||||
pcr1 &= ~BIT(MCHP_GPIO_CTRL_OUTVAL_POS);
|
||||
if (p->out_lo != 0) {
|
||||
pcr1 &= ~(MEC_GPIO_CR1_ODAT_MSK);
|
||||
pcr1 |= MEC_GPIO_CR1_ODAT_SET(MEC_GPIO_CR1_ODAT_LO);
|
||||
}
|
||||
if (conf & BIT(MCHP_XEC_OUT_HI_POS)) {
|
||||
pcr1 |= BIT(MCHP_GPIO_CTRL_OUTVAL_POS);
|
||||
|
||||
if (p->out_hi != 0) {
|
||||
pcr1 &= ~(MEC_GPIO_CR1_ODAT_MSK);
|
||||
pcr1 |= MEC_GPIO_CR1_ODAT_SET(MEC_GPIO_CR1_ODAT_HI);
|
||||
}
|
||||
|
||||
/* Touch output buffer type? */
|
||||
if (conf & BIT(MCHP_XEC_PUSH_PULL_POS)) {
|
||||
pcr1 &= ~(MCHP_GPIO_CTRL_BUFT_OPENDRAIN);
|
||||
if (p->obuf_pp != 0) {
|
||||
pcr1 &= ~(MEC_GPIO_CR1_OBUF_MSK);
|
||||
pcr1 |= MEC_GPIO_CR1_OBUF_SET(MEC_GPIO_CR1_OBUF_PP);
|
||||
}
|
||||
if (conf & BIT(MCHP_XEC_OPEN_DRAIN_POS)) {
|
||||
pcr1 |= MCHP_GPIO_CTRL_BUFT_OPENDRAIN;
|
||||
|
||||
if (p->obuf_od != 0) {
|
||||
pcr1 &= ~(MEC_GPIO_CR1_OBUF_MSK);
|
||||
pcr1 |= MEC_GPIO_CR1_OBUF_SET(MEC_GPIO_CR1_OBUF_OD);
|
||||
}
|
||||
|
||||
/* Always touch power gate */
|
||||
pcr1 &= ~MCHP_GPIO_CTRL_PWRG_MASK;
|
||||
if (conf & BIT(MCHP_XEC_PIN_LOW_POWER_POS)) {
|
||||
pcr1 |= MCHP_GPIO_CTRL_PWRG_OFF;
|
||||
pcr1 &= ~(MEC_GPIO_CR1_PG_MSK);
|
||||
if (p->lp != 0) {
|
||||
pcr1 |= MEC_GPIO_CR1_PG_SET(MEC_GPIO_CR1_PG_UNPWRD);
|
||||
} else {
|
||||
pcr1 |= MCHP_GPIO_CTRL_PWRG_VTR_IO;
|
||||
pcr1 |= MEC_GPIO_CR1_PG_SET(MEC_GPIO_CR1_PG_VTR);
|
||||
}
|
||||
|
||||
/* Always touch MUX (alternate function) */
|
||||
pcr1 &= ~MCHP_GPIO_CTRL_MUX_MASK;
|
||||
pcr1 |= (uint32_t)((altf & MCHP_GPIO_CTRL_MUX_MASK0) << MCHP_GPIO_CTRL_MUX_POS);
|
||||
pcr1 &= ~(MEC_GPIO_CR1_MUX_MSK);
|
||||
pcr1 |= MEC_GPIO_CR1_MUX_SET((uint32_t)altf);
|
||||
|
||||
/* Always touch invert of alternate function. Need another bit to avoid touching */
|
||||
if (conf & BIT(MCHP_XEC_FUNC_INV_POS)) {
|
||||
pcr1 |= BIT(MCHP_GPIO_CTRL_POL_POS);
|
||||
if (p->finv != 0) {
|
||||
pcr1 |= BIT(MEC_GPIO_CR1_FPOL_POS);
|
||||
} else {
|
||||
pcr1 &= ~BIT(MCHP_GPIO_CTRL_POL_POS);
|
||||
pcr1 &= ~BIT(MEC_GPIO_CR1_FPOL_POS);
|
||||
}
|
||||
|
||||
/* output state set in control & parallel regs */
|
||||
regs->CTRL[idx] = pcr1;
|
||||
sys_write32(pcr1, gpio_cr1_addr);
|
||||
/* make output state in control read-only in control and read-write in parallel reg */
|
||||
regs->CTRL[idx] = pcr1 | BIT(MCHP_GPIO_CTRL_AOD_POS);
|
||||
sys_set_bit(gpio_cr1_addr, MEC_GPIO_CR1_OCR_POS);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int pinctrl_configure_pins(const pinctrl_soc_pin_t *pins, uint8_t pin_cnt,
|
||||
uintptr_t reg)
|
||||
int pinctrl_configure_pins(const pinctrl_soc_pin_t *pins, uint8_t pin_cnt, uintptr_t reg)
|
||||
{
|
||||
uint32_t portpin, pinmux, func;
|
||||
int ret;
|
||||
uint32_t portpin = 0, func = 0;
|
||||
int ret = 0;
|
||||
|
||||
ARG_UNUSED(reg);
|
||||
|
||||
for (uint8_t i = 0U; i < pin_cnt; i++) {
|
||||
pinmux = pins[i];
|
||||
const pinctrl_soc_pin_t *p = &pins[i];
|
||||
|
||||
func = MCHP_XEC_PINMUX_FUNC(pinmux);
|
||||
func = MCHP_XEC_PINMUX_FUNC(p->pinmux);
|
||||
if (func >= MCHP_AFMAX) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
portpin = MEC_XEC_PINMUX_PORT_PIN(pinmux);
|
||||
portpin = MEC_XEC_PINMUX_PORT_PIN(p->pinmux);
|
||||
|
||||
ret = xec_config_pin(portpin, pinmux, func);
|
||||
ret = xec_config_pin(portpin, p, func);
|
||||
if (ret < 0) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
@@ -163,7 +163,7 @@
|
||||
};
|
||||
|
||||
pinctrl: pin-controller@40081000 {
|
||||
compatible = "microchip,mec5-pinctrl";
|
||||
compatible = "microchip,xec-pinctrl";
|
||||
#address-cells = <1>;
|
||||
#size-cells = <1>;
|
||||
reg = <0x40081000 0x1000>;
|
||||
|
||||
@@ -1,125 +0,0 @@
|
||||
# Copyright (c) 2024 Microchip Technology Inc.
|
||||
# SPDX-License-Identifier: Apache-2.0
|
||||
|
||||
description: |
|
||||
Microchip XEC Pin controller
|
||||
|
||||
Based on pincfg-node.yaml binding.
|
||||
The MCHP XEC pin controller is a singleton node responsible for controlling
|
||||
pin function selection and pin properties. For example, you can use this
|
||||
node to select peripheral pin functions.
|
||||
|
||||
The node has the 'pinctrl' node label set in your SoC's devicetree,
|
||||
so you can modify it like this:
|
||||
|
||||
&pinctrl {
|
||||
/* your modifications go here */
|
||||
};
|
||||
|
||||
All device pin configurations should be placed in child nodes of the
|
||||
'pinctrl' node, as in the spi0 example shown at the end:
|
||||
|
||||
A group can also specify shared pin properties common to all the specified
|
||||
pins, such as the 'bias-pull-up' property in group 2. Here is a list of
|
||||
supported standard pin properties:
|
||||
|
||||
- bias-disable: Disable pull-up/down (default behavior, not required).
|
||||
- bias-pull-down: Enable pull-down resistor.
|
||||
- bias-pull-up: Enable pull-up resistor.
|
||||
- drive-push-pull: Output driver is push-pull (default, not required).
|
||||
- drive-open-drain: Output driver is open-drain.
|
||||
- output-high: Set output state high when pin configured.
|
||||
- output-low: Set output state low when pin configured.
|
||||
|
||||
Custom pin properties for drive strength and slew rate are available:
|
||||
- drive-strength
|
||||
- slew-rate
|
||||
|
||||
Driver strength and slew rate hardware defaults vary by SoC and pin.
|
||||
|
||||
An example for MEC174x family, include the chip level pinctrl
|
||||
DTSI file in the board level DTS:
|
||||
|
||||
#include <microchip/mec5/mec1743qlj-a0-pinctrl.dtsi>
|
||||
|
||||
We want to use the shared SPI port of the MEC172x QMSPI controller
|
||||
and want the chip select 0 to be open-drain.
|
||||
|
||||
To change a pin's pinctrl default properties add a reference to the
|
||||
pin in the board's DTS file and set the properties.
|
||||
|
||||
&spi0 {
|
||||
pinctrl-0 = < &shd_cs0_n_gpio055
|
||||
&shd_clk_gpio056
|
||||
&shd_io0_gpio223
|
||||
&shd_io1_gpio224
|
||||
&shd_io3_gpio016 >;
|
||||
pinctrl-names = "default";
|
||||
}
|
||||
|
||||
&shd_cs0_n_gpio055 {
|
||||
drive-open-drain;
|
||||
};
|
||||
|
||||
compatible: "microchip,mec5-pinctrl"
|
||||
|
||||
include: base.yaml
|
||||
|
||||
properties:
|
||||
reg:
|
||||
required: true
|
||||
|
||||
child-binding:
|
||||
description: |
|
||||
This binding gives a base representation of the Microchip XEC pins
|
||||
configuration
|
||||
|
||||
include:
|
||||
- name: pincfg-node.yaml
|
||||
property-allowlist:
|
||||
- bias-disable
|
||||
- bias-pull-down
|
||||
- bias-pull-up
|
||||
- drive-push-pull
|
||||
- drive-open-drain
|
||||
- low-power-enable
|
||||
- output-disable
|
||||
- output-enable
|
||||
- output-high
|
||||
- output-low
|
||||
|
||||
properties:
|
||||
pinmux:
|
||||
type: int
|
||||
required: true
|
||||
description: Pinmux selection
|
||||
|
||||
slew-rate:
|
||||
type: string
|
||||
enum:
|
||||
- "low-speed"
|
||||
- "high-speed"
|
||||
description: |
|
||||
Pin speed. The default value of slew-rate is the SoC power-on-reset
|
||||
value. Please refer to the data sheet as a small number of pins
|
||||
may have a different default and some pins do not implement
|
||||
slew rate adjustment.
|
||||
|
||||
drive-strength:
|
||||
type: string
|
||||
enum:
|
||||
- "1x"
|
||||
- "2x"
|
||||
- "4x"
|
||||
- "6x"
|
||||
description: |
|
||||
Pin output drive strength for PIO and PIO-24 pin types. Default
|
||||
is "1x" for most pins. PIO pins are 2, 4, 8, or 12 mA. PIO-24 pins
|
||||
are 4, 8, 16, or 24 mA. Please refer to the data sheet for each
|
||||
pin's PIO type and default drive strength.
|
||||
|
||||
microchip,output-func-invert:
|
||||
type: boolean
|
||||
description:
|
||||
Invert polarity of an output alternate function. Input functions
|
||||
are not affected.
|
||||
@@ -95,33 +95,21 @@ child-binding:
|
||||
required: true
|
||||
description: Pinmux selection
|
||||
|
||||
slew-rate:
|
||||
type: string
|
||||
default: "no-change"
|
||||
enum:
|
||||
- "no-change"
|
||||
- "low-speed"
|
||||
- "high-speed"
|
||||
description: |
|
||||
Pin speed. The default value of slew-rate is the SoC power-on-reset
|
||||
value. Please refer to the data sheet as a small number of pins
|
||||
may have a different default and some pins do not implement
|
||||
slew rate adjustment.
|
||||
|
||||
drive-strength:
|
||||
type: string
|
||||
default: "no-change"
|
||||
enum:
|
||||
- "no-change"
|
||||
- "1x"
|
||||
- "2x"
|
||||
- "4x"
|
||||
- "6x"
|
||||
type: int
|
||||
description: |
|
||||
Pin output drive strength for PIO and PIO-24 pin types. Default
|
||||
is "1x" for most pins. PIO pins are 2, 4, 8, or 12 mA. PIO-24 pins
|
||||
are 4, 8, 16, or 24 mA. Please refer to the data sheet for each
|
||||
pin's PIO type and default drive strength.
|
||||
GPIO pin output driver strength. Value range is 0 to 4.
|
||||
Refer to the part data sheet if the pin is PIO-12 or PIO-24.
|
||||
Value 0 is no change.
|
||||
PIO-12: 1(2 mA), 2(4 mA), 3(8 mA), or 4(12 mA).
|
||||
PIO-24: 1(4 mA), 2(8 mA), 3(16 mA), or 4(24 mA).
|
||||
|
||||
slew-rate:
|
||||
type: int
|
||||
description: |
|
||||
GPIO pin slew rate. Value range is 0 to 2.
|
||||
Value 0 is no change.
|
||||
1 = fast slew rate(default), 2 = slow (half-speed) slew rate.
|
||||
|
||||
microchip,output-func-invert:
|
||||
type: boolean
|
||||
|
||||
@@ -20,28 +20,15 @@
|
||||
#define MCHP_AF7 0x7
|
||||
#define MCHP_AFMAX 0x8
|
||||
|
||||
#define MCHP_XEC_NO_PUD_POS 12
|
||||
#define MCHP_XEC_PD_POS 13
|
||||
#define MCHP_XEC_PU_POS 14
|
||||
#define MCHP_XEC_PUSH_PULL_POS 15
|
||||
#define MCHP_XEC_OPEN_DRAIN_POS 16
|
||||
#define MCHP_XEC_OUT_DIS_POS 17
|
||||
#define MCHP_XEC_OUT_EN_POS 18
|
||||
#define MCHP_XEC_OUT_HI_POS 19
|
||||
#define MCHP_XEC_OUT_LO_POS 20
|
||||
/* bit[21] unused */
|
||||
#define MCHP_XEC_SLEW_RATE_POS 22
|
||||
#define MCHP_XEC_SLEW_RATE_MSK0 0x3
|
||||
#define MCHP_XEC_SLEW_RATE_SLOW0 0x1
|
||||
#define MCHP_XEC_SLEW_RATE_FAST0 0x2
|
||||
#define MCHP_XEC_DRV_STR_POS 24
|
||||
#define MCHP_XEC_DRV_STR_MSK0 0x7
|
||||
#define MCHP_XEC_DRV_STR0_1X 0x1 /* 2 or 4(PIO-24) mA */
|
||||
#define MCHP_XEC_DRV_STR0_2X 0x2 /* 4 or 8(PIO-24) mA */
|
||||
#define MCHP_XEC_DRV_STR0_4X 0x3 /* 8 or 16(PIO-24) mA */
|
||||
#define MCHP_XEC_DRV_STR0_6X 0x4 /* 12 or 24(PIO-24) mA */
|
||||
#define MCHP_XEC_PIN_LOW_POWER_POS 27
|
||||
#define MCHP_XEC_FUNC_INV_POS 29
|
||||
#define MCHP_XEC_SLEW_RATE_NO_CHANGE 0
|
||||
#define MCHP_XEC_SLEW_RATE_FAST 1
|
||||
#define MCHP_XEC_SLEW_RATE_SLOW 2
|
||||
|
||||
#define MCHP_XEC_DRV_STR_NO_CHANGE 0
|
||||
#define MCHP_XEC_DRV_STR_1X 1 /* 2 or 4(PIO-24) mA */
|
||||
#define MCHP_XEC_DRV_STR_2X 2 /* 4 or 8(PIO-24) mA */
|
||||
#define MCHP_XEC_DRV_STR_4X 3 /* 8 or 16(PIO-24) mA */
|
||||
#define MCHP_XEC_DRV_STR_6X 4 /* 12 or 24(PIO-24) mA */
|
||||
|
||||
#define MCHP_XEC_PINMUX_PORT_POS 0
|
||||
#define MCHP_XEC_PINMUX_PORT_MSK 0xf
|
||||
|
||||
@@ -26,47 +26,47 @@ extern "C" {
|
||||
/** @cond INTERNAL_HIDDEN */
|
||||
|
||||
/* Type for MCHP XEC pin. */
|
||||
typedef uint32_t pinctrl_soc_pin_t;
|
||||
struct mec_pinctrl {
|
||||
uint32_t pinmux : 12; /* b[11:0] */
|
||||
uint32_t no_pud : 1; /* b[12] */
|
||||
uint32_t pd : 1; /* b[13] */
|
||||
uint32_t pu : 1; /* b[14] */
|
||||
uint32_t obuf_pp : 1; /* b[15] */
|
||||
uint32_t obuf_od : 1; /* b[16] */
|
||||
uint32_t out_dis : 1; /* b[17] */
|
||||
uint32_t out_en : 1; /* b[18] */
|
||||
uint32_t out_hi : 1; /* b[19] */
|
||||
uint32_t out_lo : 1; /* b[20] */
|
||||
uint32_t rsvd21 : 1; /* b[21] unused */
|
||||
uint32_t slew_rate : 2; /* b[23:22] */
|
||||
uint32_t drive_str : 3; /* b[26:24] */
|
||||
uint32_t rsvd27 : 1; /* b[27] unused */
|
||||
uint32_t finv : 1; /* b[28] */
|
||||
uint32_t lp : 1; /* b[29] */
|
||||
};
|
||||
|
||||
/* initialize pinmux member fields of pinctrl_pin_t */
|
||||
#define Z_PINCTRL_MCHP_XEC_PINMUX_INIT(node_id) (uint32_t)(DT_PROP(node_id, pinmux))
|
||||
typedef struct mec_pinctrl pinctrl_soc_pin_t;
|
||||
|
||||
#ifdef CONFIG_HAS_MEC5_HAL
|
||||
#define Z_PINCTRL_STATE_PINCFG_INIT(node_id) \
|
||||
((DT_PROP(node_id, bias_disable) << MCHP_XEC_NO_PUD_POS) | \
|
||||
(DT_PROP(node_id, bias_pull_down) << MCHP_XEC_PD_POS) | \
|
||||
(DT_PROP(node_id, bias_pull_up) << MCHP_XEC_PU_POS) | \
|
||||
(DT_PROP(node_id, drive_push_pull) << MCHP_XEC_PUSH_PULL_POS) | \
|
||||
(DT_PROP(node_id, drive_open_drain) << MCHP_XEC_OPEN_DRAIN_POS) | \
|
||||
(DT_PROP(node_id, output_disable) << MCHP_XEC_OUT_DIS_POS) | \
|
||||
(DT_PROP(node_id, output_enable) << MCHP_XEC_OUT_EN_POS) | \
|
||||
(DT_PROP(node_id, output_high) << MCHP_XEC_OUT_HI_POS) | \
|
||||
(DT_PROP(node_id, output_low) << MCHP_XEC_OUT_LO_POS) | \
|
||||
(DT_PROP(node_id, low_power_enable) << MCHP_XEC_PIN_LOW_POWER_POS) | \
|
||||
(DT_PROP(node_id, microchip_output_func_invert) << MCHP_XEC_FUNC_INV_POS) | \
|
||||
(DT_ENUM_IDX_OR(node_id, slew_rate, 0x3) << MCHP_XEC_SLEW_RATE_POS) | \
|
||||
(DT_ENUM_IDX_OR(node_id, drive_strength, 0x7) << MCHP_XEC_DRV_STR_POS))
|
||||
#else
|
||||
#define Z_PINCTRL_STATE_PINCFG_INIT(node_id) \
|
||||
((DT_PROP(node_id, bias_disable) << MCHP_XEC_NO_PUD_POS) | \
|
||||
(DT_PROP(node_id, bias_pull_down) << MCHP_XEC_PD_POS) | \
|
||||
(DT_PROP(node_id, bias_pull_up) << MCHP_XEC_PU_POS) | \
|
||||
(DT_PROP(node_id, drive_push_pull) << MCHP_XEC_PUSH_PULL_POS) | \
|
||||
(DT_PROP(node_id, drive_open_drain) << MCHP_XEC_OPEN_DRAIN_POS) | \
|
||||
(DT_PROP(node_id, output_disable) << MCHP_XEC_OUT_DIS_POS) | \
|
||||
(DT_PROP(node_id, output_enable) << MCHP_XEC_OUT_EN_POS) | \
|
||||
(DT_PROP(node_id, output_high) << MCHP_XEC_OUT_HI_POS) | \
|
||||
(DT_PROP(node_id, output_low) << MCHP_XEC_OUT_LO_POS) | \
|
||||
(DT_PROP(node_id, low_power_enable) << MCHP_XEC_PIN_LOW_POWER_POS) | \
|
||||
(DT_PROP(node_id, microchip_output_func_invert) << MCHP_XEC_FUNC_INV_POS) | \
|
||||
(DT_ENUM_IDX(node_id, slew_rate) << MCHP_XEC_SLEW_RATE_POS) | \
|
||||
(DT_ENUM_IDX(node_id, drive_strength) << MCHP_XEC_DRV_STR_POS))
|
||||
#endif
|
||||
#define MCHP_XEC_PIN_INIT(node_id) \
|
||||
{ \
|
||||
.pinmux = DT_PROP(node_id, pinmux), \
|
||||
.no_pud = DT_PROP(node_id, bias_disable), \
|
||||
.pd = DT_PROP(node_id, bias_pull_down), \
|
||||
.pu = DT_PROP(node_id, bias_pull_up), \
|
||||
.obuf_pp = DT_PROP(node_id, drive_push_pull), \
|
||||
.obuf_od = DT_PROP(node_id, drive_open_drain), \
|
||||
.out_dis = DT_PROP(node_id, output_disable), \
|
||||
.out_en = DT_PROP(node_id, output_enable), \
|
||||
.out_hi = DT_PROP(node_id, output_high), \
|
||||
.out_lo = DT_PROP(node_id, output_low), \
|
||||
.slew_rate = DT_PROP_OR(node_id, slew_rate, 0), \
|
||||
.drive_str = DT_PROP_OR(node_id, drive_strength, 0), \
|
||||
.finv = DT_PROP(node_id, microchip_output_func_invert), \
|
||||
.lp = DT_PROP(node_id, low_power_enable), \
|
||||
},
|
||||
|
||||
/* initialize pin structure members */
|
||||
#define Z_PINCTRL_STATE_PIN_INIT(node_id, state_prop, idx) \
|
||||
(Z_PINCTRL_MCHP_XEC_PINMUX_INIT(DT_PROP_BY_IDX(node_id, state_prop, idx)) | \
|
||||
Z_PINCTRL_STATE_PINCFG_INIT(DT_PROP_BY_IDX(node_id, state_prop, idx))),
|
||||
#define Z_PINCTRL_STATE_PIN_INIT(node_id, prop, idx) \
|
||||
MCHP_XEC_PIN_INIT(DT_PROP_BY_IDX(node_id, prop, idx))
|
||||
|
||||
/* Use DT FOREACH macro to initialize each used pin */
|
||||
#define Z_PINCTRL_STATE_PINS_INIT(node_id, prop) \
|
||||
|
||||
@@ -122,8 +122,10 @@
|
||||
#define MEC_GPIO_CR2_DSTR_SET(ds) FIELD_PREP(MEC_GPIO_CR2_DSTR_MSK, (ds))
|
||||
#define MEC_GPIO_CR2_DSTR_GET(r) FIELD_GET(MEC_GPIO_CR2_DSTR_MSK, (r))
|
||||
|
||||
#define MEC_GPIO_CR1_OFS 0
|
||||
#define MEC_GPIO_CR2_OFS 0x500u
|
||||
#define MEC_GPIO_CR1_OFS 0
|
||||
#define MEC_GPIO_PP_IN_OFS 0x300u
|
||||
#define MEC_GPIO_PP_OUT_OFS 0x380u
|
||||
#define MEC_GPIO_CR2_OFS 0x500u
|
||||
|
||||
/* gpio_base is the base address of the GPIO peripheral block */
|
||||
#define MEC_GPIO_CR1_ADDR(gpio_base, pin) \
|
||||
@@ -134,6 +136,12 @@
|
||||
|
||||
#define MCHP_XEC_PINCTRL_REG_IDX(pin) ((pin >> 5) * 32 + (pin & 0x1f))
|
||||
|
||||
#define MEC_GPIO_PP_IN_ADDR(gpio_base, pin) \
|
||||
((uint32_t)(gpio_base) + MEC_GPIO_PP_IN_OFS + ((((uint32_t)(pin) >> 5) & 0xFU) * 4U))
|
||||
|
||||
#define MEC_GPIO_PP_OUT_ADDR(gpio_base, pin) \
|
||||
((uint32_t)(gpio_base) + MEC_GPIO_PP_OUT_OFS + ((((uint32_t)(pin) >> 5) & 0xFU) * 4U))
|
||||
|
||||
/** @brief All GPIO register as arrays of registers */
|
||||
struct gpio_regs {
|
||||
volatile uint32_t CTRL[174];
|
||||
|
||||
Reference in New Issue
Block a user