Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 0 additions & 16 deletions boards/arm/frdm_k22f/pinmux.c
Original file line number Diff line number Diff line change
Expand Up @@ -38,22 +38,6 @@ static int frdm_k22f_pinmux_init(const struct device *dev)
__ASSERT_NO_MSG(device_is_ready(porte));
#endif

#if DT_NODE_HAS_STATUS(DT_NODELABEL(uart0), okay) && CONFIG_SERIAL
#error "No UART0 is used"
#endif

#if DT_NODE_HAS_STATUS(DT_NODELABEL(uart1), okay) && CONFIG_SERIAL
/* UART1 RX, TX */
pinmux_pin_set(porte, 0, PORT_PCR_MUX(kPORT_MuxAlt3));
pinmux_pin_set(porte, 1, PORT_PCR_MUX(kPORT_MuxAlt3));
#endif

#if DT_NODE_HAS_STATUS(DT_NODELABEL(uart2), okay) && CONFIG_SERIAL
/* UART2 RX, TX */
pinmux_pin_set(portd, 2, PORT_PCR_MUX(kPORT_MuxAlt3));
pinmux_pin_set(portd, 3, PORT_PCR_MUX(kPORT_MuxAlt3));
#endif

#if DT_NODE_HAS_COMPAT_STATUS(DT_NODELABEL(ftm0), nxp_kinetis_ftm_pwm, okay) && CONFIG_PWM
/* Red, green, blue LEDs as PWM channels*/
pinmux_pin_set(porta, 1, PORT_PCR_MUX(kPORT_MuxAlt3));
Expand Down
20 changes: 0 additions & 20 deletions boards/arm/frdm_k64f/pinmux.c
Original file line number Diff line number Diff line change
Expand Up @@ -38,26 +38,6 @@ static int frdm_k64f_pinmux_init(const struct device *dev)
__ASSERT_NO_MSG(device_is_ready(porte));
#endif

#if DT_NODE_HAS_STATUS(DT_NODELABEL(uart0), okay) && CONFIG_SERIAL
/* UART0 RX, TX */
pinmux_pin_set(portb, 16, PORT_PCR_MUX(kPORT_MuxAlt3));
pinmux_pin_set(portb, 17, PORT_PCR_MUX(kPORT_MuxAlt3));
#endif

#if DT_NODE_HAS_STATUS(DT_NODELABEL(uart2), okay) && CONFIG_SERIAL
/* UART2 RX, TX */
pinmux_pin_set(portd, 0, PORT_PCR_MUX(kPORT_MuxAlt3));
pinmux_pin_set(portd, 1, PORT_PCR_MUX(kPORT_MuxAlt3));
pinmux_pin_set(portd, 2, PORT_PCR_MUX(kPORT_MuxAlt3));
pinmux_pin_set(portd, 3, PORT_PCR_MUX(kPORT_MuxAlt3));
#endif

#if DT_NODE_HAS_STATUS(DT_NODELABEL(uart3), okay) && CONFIG_SERIAL
/* UART3 RX, TX */
pinmux_pin_set(portc, 16, PORT_PCR_MUX(kPORT_MuxAlt3));
pinmux_pin_set(portc, 17, PORT_PCR_MUX(kPORT_MuxAlt3));
#endif

#if DT_NODE_HAS_STATUS(DT_NODELABEL(spi0), okay) && CONFIG_SPI
/* SPI0 CS0, SCK, SOUT, SIN */
pinmux_pin_set(portd, 0, PORT_PCR_MUX(kPORT_MuxAlt2));
Expand Down
6 changes: 0 additions & 6 deletions boards/arm/frdm_kl25z/pinmux.c
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,6 @@ static int frdm_kl25z_pinmux_init(const struct device *dev)
__ASSERT_NO_MSG(device_is_ready(porte));
#endif

#if DT_NODE_HAS_STATUS(DT_NODELABEL(uart0), okay) && CONFIG_SERIAL
/* UART0 RX, TX */
pinmux_pin_set(porta, 1, PORT_PCR_MUX(kPORT_MuxAlt2));
pinmux_pin_set(porta, 2, PORT_PCR_MUX(kPORT_MuxAlt2));
#endif

#if DT_NODE_HAS_STATUS(DT_NODELABEL(i2c0), okay) && CONFIG_I2C
/* I2C0 SCL, SDA */
pinmux_pin_set(porte, 24, PORT_PCR_MUX(kPORT_MuxAlt5)
Expand Down
12 changes: 0 additions & 12 deletions boards/arm/hexiwear_k64/pinmux.c
Original file line number Diff line number Diff line change
Expand Up @@ -62,18 +62,6 @@ static int hexiwear_k64_pinmux_init(const struct device *dev)
| PORT_PCR_ODE_MASK);
#endif

#if DT_NODE_HAS_STATUS(DT_NODELABEL(uart0), okay) && CONFIG_SERIAL
/* UART0 RX, TX */
pinmux_pin_set(portb, 16, PORT_PCR_MUX(kPORT_MuxAlt3));
pinmux_pin_set(portb, 17, PORT_PCR_MUX(kPORT_MuxAlt3));
#endif

#if DT_NODE_HAS_STATUS(DT_NODELABEL(uart4), okay) && CONFIG_SERIAL
/* UART4 RX, TX - BLE */
pinmux_pin_set(porte, 24, PORT_PCR_MUX(kPORT_MuxAlt3));
pinmux_pin_set(porte, 25, PORT_PCR_MUX(kPORT_MuxAlt3));
#endif

#if defined(CONFIG_MAX30101) && DT_NODE_HAS_STATUS(DT_NODELABEL(gpioa), okay)
const struct device *gpioa =
device_get_binding(DT_LABEL(DT_NODELABEL(gpioa)));
Expand Down
6 changes: 0 additions & 6 deletions boards/arm/twr_kv58f220m/pinmux.c
Original file line number Diff line number Diff line change
Expand Up @@ -46,12 +46,6 @@ static int twr_kv58f220m_pinmux_init(const struct device *dev)
| PORT_PCR_ODE_MASK);
#endif

#if DT_NODE_HAS_STATUS(DT_NODELABEL(uart0), okay) && CONFIG_SERIAL
/* UART0 RX, TX */
pinmux_pin_set(portb, 0, PORT_PCR_MUX(kPORT_MuxAlt7));
pinmux_pin_set(portb, 1, PORT_PCR_MUX(kPORT_MuxAlt7));
#endif

return 0;
}

Expand Down
6 changes: 0 additions & 6 deletions boards/arm/usb_kw24d512/pinmux.c
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,6 @@ static int usb_kw24d512_pinmux_init(const struct device *dev)
__ASSERT_NO_MSG(device_is_ready(porte));
#endif

#if DT_NODE_HAS_STATUS(DT_NODELABEL(uart0), okay) && CONFIG_SERIAL
/* UART0 RX, TX */
pinmux_pin_set(porta, 1, PORT_PCR_MUX(kPORT_MuxAlt2));
pinmux_pin_set(porta, 2, PORT_PCR_MUX(kPORT_MuxAlt2));
#endif

#if DT_NODE_HAS_STATUS(DT_NODELABEL(spi1), okay) && CONFIG_SPI
/* SPI1 CS0, SCK, SOUT, SIN */
pinmux_pin_set(portb, 10, PORT_PCR_MUX(kPORT_MuxAlt2));
Expand Down
1 change: 1 addition & 0 deletions drivers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ add_subdirectory_ifdef(CONFIG_IPM ipm)
add_subdirectory_ifdef(CONFIG_LED led)
add_subdirectory_ifdef(CONFIG_LED_STRIP led_strip)
add_subdirectory_ifdef(CONFIG_MODEM modem)
add_subdirectory_ifdef(CONFIG_PINCTRL pinctrl)
add_subdirectory_ifdef(CONFIG_PINMUX pinmux)
add_subdirectory_ifdef(CONFIG_PWM pwm)
add_subdirectory_ifdef(CONFIG_SENSOR sensor)
Expand Down
2 changes: 2 additions & 0 deletions drivers/Kconfig
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@ source "drivers/i2s/Kconfig"

source "drivers/pwm/Kconfig"

source "drivers/pinctrl/Kconfig"

source "drivers/pinmux/Kconfig"

source "drivers/adc/Kconfig"
Expand Down
2 changes: 1 addition & 1 deletion drivers/adc/adc_sam_afec.c
Original file line number Diff line number Diff line change
Expand Up @@ -356,7 +356,7 @@ static void adc_sam_isr(const struct device *dev)
.regs = (Afec *)DT_INST_REG_ADDR(n), \
.cfg_func = adc##n##_sam_cfg_func, \
.periph_id = DT_INST_PROP(n, peripheral_id), \
.afec_trg_pin = ATMEL_SAM_DT_PIN(n, 0), \
.afec_trg_pin = ATMEL_SAM_DT_INST_PIN(n, 0), \
}; \
\
static struct adc_sam_data adc##n##_sam_data = { \
Expand Down
2 changes: 1 addition & 1 deletion drivers/ethernet/eth_sam_gmac.c
Original file line number Diff line number Diff line change
Expand Up @@ -2214,7 +2214,7 @@ static void eth0_irq_config(void)
}

#ifdef CONFIG_SOC_FAMILY_SAM
static const struct soc_gpio_pin pins_eth0[] = ATMEL_SAM_DT_PINS(0);
static const struct soc_gpio_pin pins_eth0[] = ATMEL_SAM_DT_INST_PINS(0);
#endif

static const struct eth_sam_dev_cfg eth0_config = {
Expand Down
3 changes: 1 addition & 2 deletions drivers/i2c/i2c_sam4l_twim.c
Original file line number Diff line number Diff line change
Expand Up @@ -614,8 +614,7 @@ static const struct i2c_driver_api i2c_sam_twim_driver_api = {
DEVICE_DT_INST_GET(n), 0); \
} \
\
static const struct soc_gpio_pin pins_twim##n[] = \
{ATMEL_SAM_DT_PIN(n, 0), ATMEL_SAM_DT_PIN(n, 1)}; \
static const struct soc_gpio_pin pins_twim##n[] = ATMEL_SAM_DT_INST_PINS(n); \
\
static const struct i2c_sam_twim_dev_cfg i2c##n##_sam_config = {\
.regs = (Twim *)DT_INST_REG_ADDR(n), \
Expand Down
3 changes: 1 addition & 2 deletions drivers/i2c/i2c_sam_twi.c
Original file line number Diff line number Diff line change
Expand Up @@ -346,8 +346,7 @@ static const struct i2c_driver_api i2c_sam_twi_driver_api = {
DEVICE_DT_INST_GET(n), 0); \
} \
\
static const struct soc_gpio_pin pins_twi##n[] = \
{ATMEL_SAM_DT_PIN(n, 0), ATMEL_SAM_DT_PIN(n, 1)}; \
static const struct soc_gpio_pin pins_twi##n[] = ATMEL_SAM_DT_INST_PINS(n); \
\
static const struct i2c_sam_twi_dev_cfg i2c##n##_sam_config = { \
.regs = (Twi *)DT_INST_REG_ADDR(n), \
Expand Down
3 changes: 1 addition & 2 deletions drivers/i2c/i2c_sam_twihs.c
Original file line number Diff line number Diff line change
Expand Up @@ -333,8 +333,7 @@ static const struct i2c_driver_api i2c_sam_twihs_driver_api = {
DEVICE_DT_INST_GET(n), 0); \
} \
\
static const struct soc_gpio_pin pins_twihs##n[] = \
{ATMEL_SAM_DT_PIN(n, 0), ATMEL_SAM_DT_PIN(n, 1)}; \
static const struct soc_gpio_pin pins_twihs##n[] = ATMEL_SAM_DT_INST_PINS(n); \
\
static const struct i2c_sam_twihs_dev_cfg i2c##n##_sam_config = {\
.regs = (Twihs *)DT_INST_REG_ADDR(n), \
Expand Down
2 changes: 1 addition & 1 deletion drivers/i2s/i2s_sam_ssc.c
Original file line number Diff line number Diff line change
Expand Up @@ -976,7 +976,7 @@ static void i2s0_sam_irq_config(void)
DEVICE_DT_INST_GET(0), 0);
}

static const struct soc_gpio_pin i2s0_pins[] = ATMEL_SAM_DT_PINS(0);
static const struct soc_gpio_pin i2s0_pins[] = ATMEL_SAM_DT_INST_PINS(0);

static const struct i2s_sam_dev_cfg i2s0_sam_config = {
.dev_dma = DEVICE_DT_GET(DT_INST_DMAS_CTLR_BY_NAME(0, tx)),
Expand Down
6 changes: 6 additions & 0 deletions drivers/pinctrl/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# SPDX-License-Identifier: Apache-2.0

zephyr_sources_ifdef(CONFIG_USERSPACE pinctrl_handlers.c)

zephyr_sources_ifdef(CONFIG_PINCTRL_STM32 pinctrl_stm32.c)
zephyr_sources_ifdef(CONFIG_PINCTRL_SAM pinctrl_sam.c)
27 changes: 27 additions & 0 deletions drivers/pinctrl/Kconfig
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
# HW Info driver configuration options

# Copyright (c) 2021 Piotr Mienkowski
# SPDX-License-Identifier: Apache-2.0

menuconfig PINCTRL
bool "Pin Controller driver"
help
Enable pinctrl driver.

if PINCTRL

config PINCTRL_STM32
bool "STM32 pinctrl"
default y
depends on SOC_FAMILY_STM32
help
Enable STM32 pinctrl driver.

config PINCTRL_SAM
bool "Atmel SAM device ID"
default y
depends on SOC_FAMILY_SAM
help
Enable Atmel SAM pinctrl driver.

endif
16 changes: 16 additions & 0 deletions drivers/pinctrl/pinctrl_handlers.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
/*
* Copyright (c) 2021 Piotr Mienkowski
*
* SPDX-License-Identifier: Apache-2.0
*/

#include <syscall_handler.h>
#include <drivers/pinctrl.h>

int z_vrfy_pinctrl_pin_configure(const pinctrl_dt_pin_spec_t *pin_spec)
{
Z_SYSCALL_MEMORY_READ(pin_spec, sizeof(pinctrl_dt_pin_spec_t));

return z_impl_pinctrl_pin_configure((const struct pinctrl_dt_pin_spec *)pin_spec);
}
#include <syscalls/pinctrl_pin_configure_mrsh.c>
15 changes: 15 additions & 0 deletions drivers/pinctrl/pinctrl_sam.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
/*
* Copyright (c) 2021 Piotr Mienkowski
*
* SPDX-License-Identifier: Apache-2.0
*/

#include <drivers/pinctrl.h>
#include <soc.h>

int z_impl_pinctrl_pin_configure(const pinctrl_dt_pin_spec_t *pin_spec)
{
soc_gpio_configure((const struct soc_gpio_pin *)pin_spec);

return 0;
}
8 changes: 8 additions & 0 deletions drivers/pinmux/pinmux_mcux.c
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
#include <errno.h>
#include <device.h>
#include <drivers/pinmux.h>
#include <drivers/pinctrl.h>
#include <fsl_common.h>
#include <fsl_clock.h>

Expand All @@ -17,6 +18,13 @@ struct pinmux_mcux_config {
PORT_Type *base;
};

int z_impl_pinctrl_pin_configure(const pinctrl_dt_pin_spec_t *pin_spec)
{
pinmux_pin_set(pin_spec->port, pin_spec->pin, PORT_PCR_MUX(pin_spec->mux));

return 0;
}

static int pinmux_mcux_set(const struct device *dev, uint32_t pin,
uint32_t func)
{
Expand Down
2 changes: 1 addition & 1 deletion drivers/sensor/qdec_sam/qdec_sam.c
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ static const struct sensor_driver_api qdec_sam_driver_api = {
};

#define QDEC_SAM_INIT(n) \
static const struct soc_gpio_pin pins_tc##n[] = ATMEL_SAM_DT_PINS(n); \
static const struct soc_gpio_pin pins_tc##n[] = ATMEL_SAM_DT_INST_PINS(n); \
\
static const struct qdec_sam_dev_cfg qdec##n##_sam_config = { \
.regs = (Tc *)DT_INST_REG_ADDR(n), \
Expand Down
1 change: 1 addition & 0 deletions drivers/serial/Kconfig.usart_sam
Original file line number Diff line number Diff line change
Expand Up @@ -8,5 +8,6 @@ config USART_SAM
depends on SOC_FAMILY_SAM
select SERIAL_HAS_DRIVER
select SERIAL_SUPPORT_INTERRUPT
select PINCTRL
help
This option enables the USARTx driver for Atmel SAM MCUs.
10 changes: 10 additions & 0 deletions drivers/serial/uart_mcux.c
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
#include <device.h>
#include <drivers/uart.h>
#include <drivers/clock_control.h>
#include <drivers/pinctrl.h>
#include <fsl_uart.h>
#include <soc.h>

Expand All @@ -21,6 +22,8 @@ struct uart_mcux_config {
#ifdef CONFIG_UART_INTERRUPT_DRIVEN
void (*irq_config_func)(const struct device *dev);
#endif
const pinctrl_dt_pin_spec_t *pins;
size_t num_pins;
};

struct uart_mcux_data {
Expand All @@ -40,6 +43,8 @@ static int uart_mcux_configure(const struct device *dev,
uint32_t clock_freq;
status_t retval;

pinctrl_pin_list_configure(config->pins, config->num_pins);

if (clock_control_get_rate(config->clock_dev, config->clock_subsys,
&clock_freq)) {
return -EINVAL;
Expand Down Expand Up @@ -359,10 +364,15 @@ static const struct uart_driver_api uart_mcux_driver_api = {
};

#define UART_MCUX_DECLARE_CFG(n, IRQ_FUNC_INIT) \
static const pinctrl_dt_pin_spec_t uart_pins_##n[] = \
PINCTRL_DT_SPEC_GET(DT_DRV_INST(n), 0); \
\
static const struct uart_mcux_config uart_mcux_##n##_config = { \
.base = (UART_Type *)DT_INST_REG_ADDR(n), \
.clock_dev = DEVICE_DT_GET(DT_INST_CLOCKS_CTLR(n)), \
.clock_subsys = (clock_control_subsys_t)DT_INST_CLOCKS_CELL(n, name),\
.pins = uart_pins_##n, \
.num_pins = ARRAY_SIZE(uart_pins_##n), \
IRQ_FUNC_INIT \
}

Expand Down
4 changes: 2 additions & 2 deletions drivers/serial/uart_sam.c
Original file line number Diff line number Diff line change
Expand Up @@ -327,8 +327,8 @@ static const struct uart_driver_api uart_sam_driver_api = {
.regs = (Uart *)DT_INST_REG_ADDR(n), \
.periph_id = DT_INST_PROP(n, peripheral_id), \
\
.pin_rx = ATMEL_SAM_DT_PIN(n, 0), \
.pin_tx = ATMEL_SAM_DT_PIN(n, 1), \
.pin_rx = ATMEL_SAM_DT_INST_PIN(n, 0), \
.pin_tx = ATMEL_SAM_DT_INST_PIN(n, 1), \
\
IRQ_FUNC_INIT \
}
Expand Down
15 changes: 9 additions & 6 deletions drivers/serial/usart_sam.c
Original file line number Diff line number Diff line change
Expand Up @@ -20,13 +20,14 @@
#include <init.h>
#include <soc.h>
#include <drivers/uart.h>
#include <drivers/pinctrl.h>

/* Device constant configuration parameters */
struct usart_sam_dev_cfg {
Usart *regs;
uint32_t periph_id;
struct soc_gpio_pin pin_rx;
struct soc_gpio_pin pin_tx;
unsigned int num_pins;
const pinctrl_dt_pin_spec_t *pins;

#ifdef CONFIG_UART_INTERRUPT_DRIVEN
uart_irq_config_func_t irq_config_func;
Expand Down Expand Up @@ -64,8 +65,7 @@ static int usart_sam_init(const struct device *dev)
soc_pmc_peripheral_enable(cfg->periph_id);

/* Connect pins to the peripheral */
soc_gpio_configure(&cfg->pin_rx);
soc_gpio_configure(&cfg->pin_tx);
pinctrl_pin_list_configure(cfg->pins, cfg->num_pins);

/* Reset and disable USART */
usart->US_CR = US_CR_RSTRX | US_CR_RSTTX
Expand Down Expand Up @@ -324,12 +324,15 @@ static const struct uart_driver_api usart_sam_driver_api = {
};

#define USART_SAM_DECLARE_CFG(n, IRQ_FUNC_INIT) \
static const pinctrl_dt_pin_spec_t pins_usart##n[] = \
PINCTRL_DT_SPEC_GET(DT_DRV_INST(n), 0); \
\
static const struct usart_sam_dev_cfg usart##n##_sam_config = { \
.regs = (Usart *)DT_INST_REG_ADDR(n), \
.periph_id = DT_INST_PROP(n, peripheral_id), \
\
.pin_rx = ATMEL_SAM_DT_PIN(n, 0), \
.pin_tx = ATMEL_SAM_DT_PIN(n, 1), \
.pins = pins_usart##n, \
.num_pins = ARRAY_SIZE(pins_usart##n), \
\
IRQ_FUNC_INIT \
}
Expand Down
4 changes: 2 additions & 2 deletions drivers/spi/spi_sam.c
Original file line number Diff line number Diff line change
Expand Up @@ -457,8 +457,8 @@ static const struct spi_driver_api spi_sam_driver_api = {
static const struct spi_sam_config spi_sam_config_##n = { \
.regs = (Spi *)DT_INST_REG_ADDR(n), \
.periph_id = DT_INST_PROP(n, peripheral_id), \
.num_pins = ATMEL_SAM_DT_NUM_PINS(n), \
.pins = ATMEL_SAM_DT_PINS(n), \
.num_pins = ATMEL_SAM_DT_INST_NUM_PINS(n), \
.pins = ATMEL_SAM_DT_INST_PINS(n), \
}

#define SPI_SAM_DEVICE_INIT(n) \
Expand Down
Loading