Skip to content

Commit

Permalink
hwmv2: soc: Port IMXRT family to HWMV2
Browse files Browse the repository at this point in the history
Port IMXRT family to HWMV2, including series:
- RT11XX
- RT10XX
- RT6XX

Not including RT5XX

Co-authored-by: Declan Snyder <[email protected]>
Co-authored-by: Daniel DeGrasse <[email protected]>
Co-authored-by: Mahesh Mahadevan <[email protected]>
Co-authored-by: David Leach <[email protected]>
Co-authored-by: Yves Vandervennet <[email protected]>
Co-authored-by: Emilio Benavente <[email protected]>

Signed-off-by: Declan Snyder <[email protected]>
  • Loading branch information
decsny committed Feb 27, 2024
1 parent aacb536 commit 8a7e638
Show file tree
Hide file tree
Showing 80 changed files with 1,325 additions and 1,508 deletions.
2 changes: 1 addition & 1 deletion Kconfig.zephyr
Original file line number Diff line number Diff line change
Expand Up @@ -643,7 +643,7 @@ config BUILD_OUTPUT_UF2_FAMILY_ID
default "0x1c5f21b0" if SOC_SERIES_ESP32
default "0x621e937a" if SOC_NRF52833_QIAA
default "0xada52840" if SOC_NRF52840_QIAA
default "0x4fb2d5bd" if SOC_SERIES_IMX_RT
default "0x4fb2d5bd" if SOC_SERIES_IMXRT10XX || SOC_SERIES_IMXRT11XX
default "0x2abc77ec" if SOC_SERIES_LPC55XXX
default "0xe48bff56" if SOC_SERIES_RP2XXX
default "0x68ed2b88" if SOC_SERIES_SAMD21
Expand Down
2 changes: 1 addition & 1 deletion arch/arm/core/cortex_m/timing.c
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
static inline uint64_t z_arm_dwt_freq_get(void)
{
#if defined(CONFIG_SOC_FAMILY_NRF) || \
defined(CONFIG_SOC_SERIES_IMX_RT6XX)
defined(CONFIG_SOC_SERIES_IMXRT6XX)
/*
* DWT frequency is taken directly from the
* System Core clock (CPU) frequency, if the
Expand Down
4 changes: 2 additions & 2 deletions drivers/can/Kconfig.mcux
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,8 @@ config CAN_MAX_FILTER
int "Maximum number of concurrent active RX filters"
default 5
range 1 15 if SOC_SERIES_KINETIS_KE1XF || SOC_SERIES_KINETIS_K6X
range 1 13 if SOC_SERIES_IMX_RT && CAN_MCUX_FLEXCAN_FD
range 1 63 if SOC_SERIES_IMX_RT
range 1 13 if (SOC_SERIES_IMXRT10XX || SOC_SERIES_IMXRT11XX) && CAN_MCUX_FLEXCAN_FD
range 1 63 if SOC_SERIES_IMXRT10XX || SOC_SERIES_IMXRT11XX
range 1 96 if SOC_SERIES_S32K3
range 1 32 if SOC_SERIES_S32K1 && !SOC_S32K142W && !SOC_S32K144W
range 1 64 if SOC_S32K142W || SOC_S32K144W
Expand Down
2 changes: 1 addition & 1 deletion drivers/clock_control/clock_control_mcux_ccm.c
Original file line number Diff line number Diff line change
Expand Up @@ -353,7 +353,7 @@ static int CCM_SET_FUNC_ATTR mcux_ccm_set_subsys_rate(const struct device *dev,
case IMX_CCM_FLEXSPI_CLK:
__fallthrough;
case IMX_CCM_FLEXSPI2_CLK:
#if defined(CONFIG_SOC_SERIES_IMX_RT10XX) && defined(CONFIG_MEMC_MCUX_FLEXSPI)
#if defined(CONFIG_SOC_SERIES_IMXRT10XX) && defined(CONFIG_MEMC_MCUX_FLEXSPI)
/* The SOC is using the FlexSPI for XIP. Therefore,
* the FlexSPI itself must be managed within the function,
* which is SOC specific.
Expand Down
2 changes: 1 addition & 1 deletion drivers/clock_control/clock_control_mcux_ccm_rev2.c
Original file line number Diff line number Diff line change
Expand Up @@ -173,7 +173,7 @@ static int CCM_SET_FUNC_ATTR mcux_ccm_set_subsys_rate(const struct device *dev,
case IMX_CCM_FLEXSPI_CLK:
__fallthrough;
case IMX_CCM_FLEXSPI2_CLK:
#if defined(CONFIG_SOC_SERIES_IMX_RT11XX) && defined(CONFIG_MEMC_MCUX_FLEXSPI)
#if defined(CONFIG_SOC_SERIES_IMXRT11XX) && defined(CONFIG_MEMC_MCUX_FLEXSPI)
/* The SOC is using the FlexSPI for XIP. Therefore,
* the FlexSPI itself must be managed within the function,
* which is SOC specific.
Expand Down
4 changes: 2 additions & 2 deletions drivers/ethernet/Kconfig.mcux
Original file line number Diff line number Diff line change
Expand Up @@ -94,8 +94,8 @@ if PTP_CLOCK_MCUX
config ETH_MCUX_PTP_CLOCK_SRC_HZ
int "Frequency of the clock source for the PTP timer"
default 50000000 if SOC_SERIES_KINETIS_K6X
default 50000000 if SOC_SERIES_IMX_RT10XX
default 24000000 if SOC_SERIES_IMX_RT11XX
default 50000000 if SOC_SERIES_IMXRT10XX
default 24000000 if SOC_SERIES_IMXRT11XX
help
Set the frequency in Hz sourced to the PTP timer.
If the value is set properly, the timer will be accurate.
Expand Down
18 changes: 9 additions & 9 deletions drivers/ethernet/eth_mcux.c
Original file line number Diff line number Diff line change
Expand Up @@ -396,7 +396,7 @@ static void eth_mcux_phy_start(struct eth_context *context)
k_work_submit(&context->phy_work);
break;
#endif
#if defined(CONFIG_SOC_SERIES_IMX_RT)
#if defined(CONFIG_SOC_SERIES_IMXRT10XX) || defined(CONFIG_SOC_SERIES_IMXRT11XX)
context->phy_state = eth_mcux_phy_state_initial;
#else
context->phy_state = eth_mcux_phy_state_reset;
Expand Down Expand Up @@ -453,7 +453,7 @@ static void eth_mcux_phy_event(struct eth_context *context)
uint32_t status;
#endif
bool link_up;
#if defined(CONFIG_SOC_SERIES_IMX_RT)
#if defined(CONFIG_SOC_SERIES_IMXRT10XX) || defined(CONFIG_SOC_SERIES_IMXRT11XX)
status_t res;
uint16_t ctrl2;
#endif
Expand All @@ -466,7 +466,7 @@ static void eth_mcux_phy_event(struct eth_context *context)
#endif
switch (context->phy_state) {
case eth_mcux_phy_state_initial:
#if defined(CONFIG_SOC_SERIES_IMX_RT)
#if defined(CONFIG_SOC_SERIES_IMXRT10XX) || defined(CONFIG_SOC_SERIES_IMXRT11XX)
ENET_DisableInterrupts(context->base, ENET_EIR_MII_MASK);
res = PHY_Read(context->phy_handle, PHY_CONTROL2_REG, &ctrl2);
ENET_EnableInterrupts(context->base, ENET_EIR_MII_MASK);
Expand All @@ -481,7 +481,7 @@ static void eth_mcux_phy_event(struct eth_context *context)
ctrl2);
}
context->phy_state = eth_mcux_phy_state_reset;
#endif /* CONFIG_SOC_SERIES_IMX_RT */
#endif
#if defined(CONFIG_ETH_MCUX_NO_PHY_SMI)
/*
* When the iface is available proceed with the eth link setup,
Expand Down Expand Up @@ -633,7 +633,7 @@ static void eth_mcux_delayed_phy_work(struct k_work *item)

static void eth_mcux_phy_setup(struct eth_context *context)
{
#if defined(CONFIG_SOC_SERIES_IMX_RT)
#if defined(CONFIG_SOC_SERIES_IMXRT10XX) || defined(CONFIG_SOC_SERIES_IMXRT11XX)
status_t res;
uint16_t oms_override;

Expand Down Expand Up @@ -1024,14 +1024,14 @@ static void eth_mcux_init(const struct device *dev)
context->phy_state = eth_mcux_phy_state_initial;
context->phy_handle->ops = &phyksz8081_ops;

#if defined(CONFIG_SOC_SERIES_IMX_RT10XX)
#if defined(CONFIG_SOC_SERIES_IMXRT10XX)
#if DT_NODE_HAS_STATUS(DT_NODELABEL(enet), okay)
sys_clock = CLOCK_GetFreq(kCLOCK_IpgClk);
#endif
#if DT_NODE_HAS_STATUS(DT_NODELABEL(enet2), okay)
sys_clock = CLOCK_GetFreq(kCLOCK_EnetPll1Clk);
#endif
#elif defined(CONFIG_SOC_SERIES_IMX_RT11XX)
#elif defined(CONFIG_SOC_SERIES_IMXRT11XX)
sys_clock = CLOCK_GetRootClockFreq(kCLOCK_Root_Bus);
#else
sys_clock = CLOCK_GetFreq(kCLOCK_CoreSysClk);
Expand Down Expand Up @@ -1391,9 +1391,9 @@ static void eth_mcux_err_isr(const struct device *dev)
}
#endif

#if defined(CONFIG_SOC_SERIES_IMX_RT10XX)
#if defined(CONFIG_SOC_SERIES_IMXRT10XX)
#define ETH_MCUX_UNIQUE_ID (OCOTP->CFG1 ^ OCOTP->CFG2)
#elif defined(CONFIG_SOC_SERIES_IMX_RT11XX)
#elif defined(CONFIG_SOC_SERIES_IMXRT11XX)
#define ETH_MCUX_UNIQUE_ID (OCOTP->FUSEN[40].FUSE)
#elif defined(CONFIG_SOC_SERIES_KINETIS_K6X)
#define ETH_MCUX_UNIQUE_ID (SIM->UIDH ^ SIM->UIDMH ^ SIM->UIDML ^ SIM->UIDL)
Expand Down
4 changes: 2 additions & 2 deletions drivers/ethernet/eth_nxp_enet.c
Original file line number Diff line number Diff line change
Expand Up @@ -772,9 +772,9 @@ static const struct ethernet_api api_funcs = {
#define FREESCALE_OUI_B1 0x04
#define FREESCALE_OUI_B2 0x9f

#if defined(CONFIG_SOC_SERIES_IMX_RT10XX)
#if defined(CONFIG_SOC_SERIES_IMXRT10XX)
#define ETH_NXP_ENET_UNIQUE_ID (OCOTP->CFG1 ^ OCOTP->CFG2)
#elif defined(CONFIG_SOC_SERIES_IMX_RT11XX)
#elif defined(CONFIG_SOC_SERIES_IMXRT11XX)
#define ETH_NXP_ENET_UNIQUE_ID (OCOTP->FUSEN[40].FUSE)
#elif defined(CONFIG_SOC_SERIES_KINETIS_K6X)
#define ETH_NXP_ENET_UNIQUE_ID (SIM->UIDH ^ SIM->UIDMH ^ SIM->UIDML ^ SIM->UIDL)
Expand Down
6 changes: 3 additions & 3 deletions drivers/gpio/gpio_mcux_igpio.c
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ static int mcux_igpio_configure(const struct device *dev,
(volatile uint32_t *)config->pin_muxes[cfg_idx].config_register;
uint32_t reg = *gpio_cfg_reg;

#ifdef CONFIG_SOC_SERIES_IMX_RT10XX
#ifdef CONFIG_SOC_SERIES_IMXRT10XX
if ((flags & GPIO_SINGLE_ENDED) != 0) {
/* Set ODE bit */
reg |= IOMUXC_SW_PAD_CTL_PAD_ODE_MASK;
Expand All @@ -92,7 +92,7 @@ static int mcux_igpio_configure(const struct device *dev,
/* Set pin to keeper */
reg &= ~IOMUXC_SW_PAD_CTL_PAD_PUE_MASK;
}
#elif defined(CONFIG_SOC_SERIES_IMX_RT11XX)
#elif defined(CONFIG_SOC_SERIES_IMXRT11XX)
if (config->pin_muxes[pin].pue_mux) {
/* PUE type register layout (GPIO_AD pins) */
if ((flags & GPIO_SINGLE_ENDED) != 0) {
Expand Down Expand Up @@ -184,7 +184,7 @@ static int mcux_igpio_configure(const struct device *dev,
/* Set pin to highz */
reg &= ~(0x1 << MCUX_IMX_BIAS_PULL_ENABLE_SHIFT);
}
#endif /* CONFIG_SOC_SERIES_IMX_RT10XX */
#endif /* CONFIG_SOC_SERIES_IMXRT10XX */

memcpy(&pin_cfg.pinmux, &config->pin_muxes[cfg_idx], sizeof(pin_cfg.pinmux));
/* cfg register will be set by pinctrl_configure_pins */
Expand Down
2 changes: 1 addition & 1 deletion drivers/hwinfo/Kconfig
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ config HWINFO_MCUX_SYSCON
config HWINFO_IMXRT
bool "NXP i.mx RT device ID"
default y
depends on SOC_SERIES_IMX_RT
depends on SOC_SERIES_IMXRT10XX || SOC_SERIES_IMXRT11XX
help
Enable NXP i.mx RT hwinfo driver.

Expand Down
2 changes: 1 addition & 1 deletion drivers/hwinfo/hwinfo_imxrt.c
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ ssize_t z_impl_hwinfo_get_device_id(uint8_t *buffer, size_t length)
{
struct imxrt_uid dev_id;

#ifdef CONFIG_SOC_SERIES_IMX_RT11XX
#ifdef CONFIG_SOC_SERIES_IMXRT11XX
dev_id.id[0] = sys_cpu_to_be32(OCOTP->FUSEN[17].FUSE);
dev_id.id[1] = sys_cpu_to_be32(OCOTP->FUSEN[16].FUSE);
#else
Expand Down
4 changes: 2 additions & 2 deletions drivers/i2s/i2s_mcux_sai.c
Original file line number Diff line number Diff line change
Expand Up @@ -1148,13 +1148,13 @@ static void audio_clock_settings(const struct device *dev)
imxrt_audio_codec_pll_init(clock_name, dev_cfg->clk_src,
dev_cfg->clk_pre_div, dev_cfg->clk_src_div);

#ifdef CONFIG_SOC_SERIES_IMX_RT11XX
#ifdef CONFIG_SOC_SERIES_IMXRT11XX
audioPllConfig.loopDivider = dev_cfg->pll_lp;
audioPllConfig.postDivider = dev_cfg->pll_pd;
audioPllConfig.numerator = dev_cfg->pll_num;
audioPllConfig.denominator = dev_cfg->pll_den;
audioPllConfig.ssEnable = false;
#elif defined CONFIG_SOC_SERIES_IMX_RT10XX
#elif defined CONFIG_SOC_SERIES_IMXRT10XX
audioPllConfig.src = dev_cfg->pll_src;
audioPllConfig.loopDivider = dev_cfg->pll_lp;
audioPllConfig.postDivider = dev_cfg->pll_pd;
Expand Down
12 changes: 6 additions & 6 deletions drivers/pinctrl/pinctrl_imx.c
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ int pinctrl_configure_pins(const pinctrl_soc_pin_t *pins, uint8_t pin_cnt,
uint32_t input_daisy = pins[i].pinmux.input_daisy;
uint32_t config_register = pins[i].pinmux.config_register;
uint32_t pin_ctrl_flags = pins[i].pin_ctrl_flags;
#if defined(CONFIG_SOC_SERIES_IMX_RT10XX) || defined(CONFIG_SOC_SERIES_IMX_RT11XX)
#if defined(CONFIG_SOC_SERIES_IMXRT10XX) || defined(CONFIG_SOC_SERIES_IMXRT11XX)
volatile uint32_t *gpr_register =
(volatile uint32_t *)((uintptr_t)pins[i].pinmux.gpr_register);
if (gpr_register) {
Expand Down Expand Up @@ -65,17 +65,17 @@ int pinctrl_configure_pins(const pinctrl_soc_pin_t *pins, uint8_t pin_cnt,

static int imx_pinctrl_init(void)
{
#ifdef CONFIG_SOC_SERIES_IMX_RT
#if defined(CONFIG_SOC_SERIES_IMXRT10XX) || defined(CONFIG_SOC_SERIES_IMXRT11XX)
CLOCK_EnableClock(kCLOCK_Iomuxc);
#ifdef CONFIG_SOC_SERIES_IMX_RT10XX
#ifdef CONFIG_SOC_SERIES_IMXRT10XX
CLOCK_EnableClock(kCLOCK_IomuxcSnvs);
CLOCK_EnableClock(kCLOCK_IomuxcGpr);
#elif defined(CONFIG_SOC_SERIES_IMX_RT11XX)
#elif defined(CONFIG_SOC_SERIES_IMXRT11XX)
CLOCK_EnableClock(kCLOCK_Iomuxc_Lpsr);
#endif /* CONFIG_SOC_SERIES_IMX_RT10XX */
#endif /* CONFIG_SOC_SERIES_IMXRT10XX */
#elif defined(CONFIG_SOC_MIMX8MQ6)
CLOCK_EnableClock(kCLOCK_Iomux);
#endif /* CONFIG_SOC_SERIES_IMX_RT */
#endif /* CONFIG_SOC_SERIES_IMXRT10XX || CONFIG_SOC_SERIES_IMXRT11XX */

return 0;
}
Expand Down
4 changes: 2 additions & 2 deletions drivers/serial/uart_mcux_flexcomm.c
Original file line number Diff line number Diff line change
Expand Up @@ -813,7 +813,7 @@ static void mcux_flexcomm_uart_dma_rx_callback(const struct device *dma_device,
data->rx_data.offset = 0;
}

#if defined(CONFIG_SOC_SERIES_IMX_RT5XX) || defined(CONFIG_SOC_SERIES_IMX_RT6XX)
#if defined(CONFIG_SOC_SERIES_IMX_RT5XX) || defined(CONFIG_SOC_SERIES_IMXRT6XX)
/*
* This functions calculates the inputmux connection value
* needed by INPUTMUX_EnableSignal to allow the UART's DMA
Expand Down Expand Up @@ -902,7 +902,7 @@ static int flexcomm_uart_async_init(const struct device *dev)
USART_EnableRxDMA(config->base, false);

/* Route DMA requests */
#if defined(CONFIG_SOC_SERIES_IMX_RT5XX) || defined(CONFIG_SOC_SERIES_IMX_RT6XX)
#if defined(CONFIG_SOC_SERIES_IMX_RT5XX) || defined(CONFIG_SOC_SERIES_IMXRT6XX)
/* RT 3 digit uses input mux to route DMA requests from
* the UART peripheral to a hardware designated DMA channel
*/
Expand Down
4 changes: 2 additions & 2 deletions drivers/usb/device/usb_dc_mcux.c
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ BUILD_ASSERT(NUM_INSTS <= 1, "Only one USB device supported");

/* Controller ID is for HAL usage */
#if defined(CONFIG_SOC_SERIES_IMX_RT5XX) || \
defined(CONFIG_SOC_SERIES_IMX_RT6XX) || \
defined(CONFIG_SOC_SERIES_IMXRT6XX) || \
defined(CONFIG_SOC_LPC55S28) || \
defined(CONFIG_SOC_LPC55S16)
#define CONTROLLER_ID kUSB_ControllerLpcIp3511Hs0
Expand All @@ -89,7 +89,7 @@ BUILD_ASSERT(NUM_INSTS <= 1, "Only one USB device supported");
#elif DT_NODE_HAS_STATUS(DT_NODELABEL(usbfs), okay)
#define CONTROLLER_ID kUSB_ControllerLpcIp3511Fs0
#endif /* LPC55s69 */
#elif defined(CONFIG_SOC_SERIES_IMX_RT)
#elif defined(CONFIG_SOC_SERIES_IMXRT11XX) || defined(CONFIG_SOC_SERIES_IMXRT10XX)
#if DT_NODE_HAS_STATUS(DT_NODELABEL(usb1), okay)
#define CONTROLLER_ID kUSB_ControllerEhci0
#elif DT_NODE_HAS_STATUS(DT_NODELABEL(usb2), okay)
Expand Down
2 changes: 1 addition & 1 deletion modules/Kconfig.mcux
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
config HAS_MCUX
bool
depends on SOC_FAMILY_KINETIS || SOC_FAMILY_IMX || SOC_FAMILY_LPC || \
SOC_FAMILY_NXP_ADSP || SOC_FAMILY_NXP_S32
SOC_FAMILY_NXP_ADSP || SOC_FAMILY_NXP_S32 || SOC_FAMILY_NXP_IMXRT

if HAS_MCUX

Expand Down
4 changes: 4 additions & 0 deletions modules/hal_nxp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,4 +15,8 @@ if(CONFIG_HAS_MCUX OR CONFIG_HAS_IMX_HAL OR CONFIG_HAS_NXP_S32_HAL)

zephyr_compile_definitions_ifdef(CONFIG_CAN_MCUX_FLEXCAN
FLEXCAN_WAIT_TIMEOUT=${CONFIG_CAN_MCUX_FLEXCAN_WAIT_TIMEOUT})

zephyr_compile_definitions_ifdef(CONFIG_ENTROPY_MCUX_CAAM CACHE_MODE_WRITE_THROUGH)

zephyr_compile_definitions_ifdef(CONFIG_USB_DEVICE_DRIVER DATA_SECTION_IS_CACHEABLE=1)
endif()
42 changes: 42 additions & 0 deletions soc/nxp/imxrt/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
# Copyright 2024 NXP
# SPDX-License-Identifier: Apache-2.0

add_subdirectory(${SOC_SERIES})

zephyr_include_directories(.)
zephyr_include_directories(${SOC_SERIES})

zephyr_linker_sources_ifdef(CONFIG_NXP_IMXRT_BOOT_HEADER
ROM_START SORT_KEY 0 boot_header.ld)

if(CONFIG_SOC_SERIES_IMXRT10XX OR CONFIG_SOC_SERIES_IMXRT11XX)
if(CONFIG_DEVICE_CONFIGURATION_DATA)
set(boot_hdr_dcd_data_section ".boot_hdr.dcd_data")
endif()
zephyr_sources(mpu_regions.c)
zephyr_linker_section_configure(
SECTION .rom_start
INPUT ".boot_hdr.conf"
OFFSET ${CONFIG_FLEXSPI_CONFIG_BLOCK_OFFSET}
KEEP
PRIO 10
)
zephyr_linker_section_configure(
SECTION .rom_start
INPUT ".boot_hdr.ivt"
".boot_hdr.data"
${boot_hdr_dcd_data_section}
OFFSET ${CONFIG_IMAGE_VECTOR_TABLE_OFFSET}
KEEP
PRIO 11
)
zephyr_compile_definitions(XIP_EXTERNAL_FLASH)
endif()

if(CONFIG_SOC_SERIES_IMXRT6XX OR CONFIG_SOC_SERIES_IMX_RT5XX)
zephyr_linker_sources_ifdef(CONFIG_USB_DEVICE_DRIVER SECTIONS usb.ld)
endif()

if(CONFIG_MEMC)
zephyr_library_include_directories(${ZEPHYR_BASE}/drivers/memc)
endif()
Loading

0 comments on commit 8a7e638

Please sign in to comment.