aboutsummaryrefslogtreecommitdiff
path: root/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template
diff options
context:
space:
mode:
Diffstat (limited to 'lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template')
-rw-r--r--lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/board.c107
-rw-r--r--lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/board.h182
-rw-r--r--lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/clock_config.c210
-rw-r--r--lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/clock_config.h110
-rw-r--r--lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/peripherals.c61
-rw-r--r--lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/peripherals.h34
-rw-r--r--lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/pin_mux.c792
-rw-r--r--lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/pin_mux.h271
8 files changed, 1767 insertions, 0 deletions
diff --git a/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/board.c b/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/board.c
new file mode 100644
index 000000000..470e16ee3
--- /dev/null
+++ b/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/board.c
@@ -0,0 +1,107 @@
1/*
2 * Copyright 2019 NXP
3 * All rights reserved.
4 *
5 * SPDX-License-Identifier: BSD-3-Clause
6 */
7
8#include <stdint.h>
9#include "board.h"
10#include "fsl_debug_console.h"
11#include "fsl_common.h"
12#if defined(SDK_I2C_BASED_COMPONENT_USED) && SDK_I2C_BASED_COMPONENT_USED
13#include "fsl_i2c.h"
14#endif /* SDK_I2C_BASED_COMPONENT_USED */
15
16/*******************************************************************************
17 * Variables
18 ******************************************************************************/
19
20/*******************************************************************************
21 * Code
22 ******************************************************************************/
23/* Initialize debug console. */
24void BOARD_InitDebugConsole(void)
25{
26 uint32_t uartClkSrcFreq;
27 /* SIM_SOPT2[27:26]:
28 * 00: Clock Disabled
29 * 01: IRC48M
30 * 10: OSCERCLK
31 * 11: MCGIRCCLK
32 */
33 CLOCK_SetLpuart0Clock(1);
34
35 uartClkSrcFreq = BOARD_DEBUG_UART_CLK_FREQ;
36
37 DbgConsole_Init(BOARD_DEBUG_UART_INSTANCE, BOARD_DEBUG_UART_BAUDRATE, BOARD_DEBUG_UART_TYPE, uartClkSrcFreq);
38}
39#if defined(SDK_I2C_BASED_COMPONENT_USED) && SDK_I2C_BASED_COMPONENT_USED
40void BOARD_I2C_Init(I2C_Type *base, uint32_t clkSrc_Hz)
41{
42 i2c_master_config_t i2cConfig = {0};
43
44 I2C_MasterGetDefaultConfig(&i2cConfig);
45 I2C_MasterInit(base, &i2cConfig, clkSrc_Hz);
46}
47
48status_t BOARD_I2C_Send(I2C_Type *base,
49 uint8_t deviceAddress,
50 uint32_t subAddress,
51 uint8_t subaddressSize,
52 uint8_t *txBuff,
53 uint8_t txBuffSize)
54{
55 i2c_master_transfer_t masterXfer;
56
57 /* Prepare transfer structure. */
58 masterXfer.slaveAddress = deviceAddress;
59 masterXfer.direction = kI2C_Write;
60 masterXfer.subaddress = subAddress;
61 masterXfer.subaddressSize = subaddressSize;
62 masterXfer.data = txBuff;
63 masterXfer.dataSize = txBuffSize;
64 masterXfer.flags = kI2C_TransferDefaultFlag;
65
66 return I2C_MasterTransferBlocking(base, &masterXfer);
67}
68
69status_t BOARD_I2C_Receive(I2C_Type *base,
70 uint8_t deviceAddress,
71 uint32_t subAddress,
72 uint8_t subaddressSize,
73 uint8_t *rxBuff,
74 uint8_t rxBuffSize)
75{
76 i2c_master_transfer_t masterXfer;
77
78 /* Prepare transfer structure. */
79 masterXfer.slaveAddress = deviceAddress;
80 masterXfer.subaddress = subAddress;
81 masterXfer.subaddressSize = subaddressSize;
82 masterXfer.data = rxBuff;
83 masterXfer.dataSize = rxBuffSize;
84 masterXfer.direction = kI2C_Read;
85 masterXfer.flags = kI2C_TransferDefaultFlag;
86
87 return I2C_MasterTransferBlocking(base, &masterXfer);
88}
89
90void BOARD_Accel_I2C_Init(void)
91{
92 BOARD_I2C_Init(BOARD_ACCEL_I2C_BASEADDR, BOARD_ACCEL_I2C_CLOCK_FREQ);
93}
94
95status_t BOARD_Accel_I2C_Send(uint8_t deviceAddress, uint32_t subAddress, uint8_t subaddressSize, uint32_t txBuff)
96{
97 uint8_t data = (uint8_t)txBuff;
98
99 return BOARD_I2C_Send(BOARD_ACCEL_I2C_BASEADDR, deviceAddress, subAddress, subaddressSize, &data, 1);
100}
101
102status_t BOARD_Accel_I2C_Receive(
103 uint8_t deviceAddress, uint32_t subAddress, uint8_t subaddressSize, uint8_t *rxBuff, uint8_t rxBuffSize)
104{
105 return BOARD_I2C_Receive(BOARD_ACCEL_I2C_BASEADDR, deviceAddress, subAddress, subaddressSize, rxBuff, rxBuffSize);
106}
107#endif /* SDK_I2C_BASED_COMPONENT_USED */
diff --git a/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/board.h b/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/board.h
new file mode 100644
index 000000000..2711f7141
--- /dev/null
+++ b/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/board.h
@@ -0,0 +1,182 @@
1/*
2 * Copyright 2019 NXP
3 * All rights reserved.
4 *
5 * SPDX-License-Identifier: BSD-3-Clause
6 */
7
8#ifndef _BOARD_H_
9#define _BOARD_H_
10
11#include "clock_config.h"
12#include "fsl_gpio.h"
13
14/*******************************************************************************
15 * Definitions
16 ******************************************************************************/
17
18/* The board name */
19#define BOARD_NAME "FRDM-K32L2B"
20
21/* The LPUART to use for debug messages. */
22#define BOARD_DEBUG_UART_TYPE kSerialPort_Uart
23#define BOARD_DEBUG_UART_BASEADDR (uint32_t) LPUART0
24#define BOARD_DEBUG_UART_INSTANCE 0U
25#define BOARD_DEBUG_UART_CLKSRC kCLOCK_McgIrc48MClk
26#define BOARD_DEBUG_UART_CLK_FREQ CLOCK_GetFreq(kCLOCK_McgIrc48MClk)
27#define BOARD_UART_IRQ LPUART0_IRQn
28#define BOARD_UART_IRQ_HANDLER LPUART0_IRQHandler
29
30#ifndef BOARD_DEBUG_UART_BAUDRATE
31#define BOARD_DEBUG_UART_BAUDRATE 115200
32#endif /* BOARD_DEBUG_UART_BAUDRATE */
33
34#define BOARD_ADC_USE_ALT_VREF 1U
35
36#define BOARD_TPM_BASEADDR TPM0
37#define BOARD_TPM_CHANNEL 5U
38
39/*! @brief The bubble level demo information */
40#define BOARD_BUBBLE_TPM_BASEADDR TPM0
41#define BOARD_TPM_X_CHANNEL 4U
42#define BOARD_TPM_Y_CHANNEL 5U
43#define BOARD_MMA8451_ADDR 0x1D
44#define BOARD_ACCEL_ADDR BOARD_MMA8451_ADDR
45#define BOARD_ACCEL_BAUDRATE 100
46#define BOARD_ACCEL_I2C_BASEADDR I2C0
47#define BOARD_ACCEL_I2C_CLOCK_FREQ CLOCK_GetFreq(I2C0_CLK_SRC)
48
49/*! @brief The rtc instance used for board. */
50#define BOARD_RTC_FUNC_BASEADDR RTC
51
52/*! @brief The Compare instance/channel used for board */
53#define BOARD_CMP_BASEADDR CMP0
54#define BOARD_CMP_CHANNEL 0U
55
56/*! @brief The i2c instance used for i2c connection by default */
57#define BOARD_I2C_BASEADDR I2C1
58
59/*! @brief The spi instance used for board. */
60#define BOARD_SPI_BASEADDR SPI1
61
62/*! @brief Define the port interrupt number for the board switches */
63#ifndef BOARD_SW1_GPIO
64#define BOARD_SW1_GPIO GPIOA
65#endif
66#ifndef BOARD_SW1_PORT
67#define BOARD_SW1_PORT PORTA
68#endif
69#ifndef BOARD_SW1_GPIO_PIN
70#define BOARD_SW1_GPIO_PIN 4U
71#endif
72#define BOARD_SW1_IRQ PORTA_IRQn
73#define BOARD_SW1_IRQ_HANDLER PORTA_IRQHandler
74#define BOARD_SW1_NAME "SW1"
75
76#ifndef BOARD_SW3_GPIO
77#define BOARD_SW3_GPIO GPIOC
78#endif
79#ifndef BOARD_SW3_PORT
80#define BOARD_SW3_PORT PORTC
81#endif
82#ifndef BOARD_SW3_GPIO_PIN
83#define BOARD_SW3_GPIO_PIN 3U
84#endif
85#define BOARD_SW3_IRQ PORTC_PORTD_IRQn
86#define BOARD_SW3_IRQ_HANDLER PORTC_PORTD_IRQHandler
87#define BOARD_SW3_NAME "SW3"
88
89#define LLWU_SW_GPIO BOARD_SW3_GPIO
90#define LLWU_SW_PORT BOARD_SW3_PORT
91#define LLWU_SW_GPIO_PIN BOARD_SW3_GPIO_PIN
92#define LLWU_SW_IRQ BOARD_SW3_IRQ
93#define LLWU_SW_IRQ_HANDLER BOARD_SW3_IRQ_HANDLER
94#define LLWU_SW_NAME BOARD_SW3_NAME
95
96/* Board led color mapping */
97#define LOGIC_LED_ON 0U
98#define LOGIC_LED_OFF 1U
99#ifndef BOARD_LED_RED_GPIO
100#define BOARD_LED_RED_GPIO GPIOE
101#endif
102#define BOARD_LED_RED_GPIO_PORT PORTE
103#ifndef BOARD_LED_RED_GPIO_PIN
104#define BOARD_LED_RED_GPIO_PIN 31U
105#endif
106#ifndef BOARD_LED_GREEN_GPIO
107#define BOARD_LED_GREEN_GPIO GPIOD
108#endif
109#define BOARD_LED_GREEN_GPIO_PORT PORTD
110#ifndef BOARD_LED_GREEN_GPIO_PIN
111#define BOARD_LED_GREEN_GPIO_PIN 5U
112#endif
113
114#define LED_RED_INIT(output) \
115 GPIO_PinWrite(BOARD_LED_RED_GPIO, BOARD_LED_RED_GPIO_PIN, output); \
116 BOARD_LED_RED_GPIO->PDDR |= (1U << BOARD_LED_RED_GPIO_PIN) /*!< Enable target LED_RED */
117#define LED_RED_ON() GPIO_PortClear(BOARD_LED_RED_GPIO, 1U << BOARD_LED_RED_GPIO_PIN) /*!< Turn on target LED_RED */
118#define LED_RED_OFF() GPIO_PortSet(BOARD_LED_RED_GPIO, 1U << BOARD_LED_RED_GPIO_PIN) /*!< Turn off target LED_RED */
119#define LED_RED_TOGGLE() \
120 GPIO_PortToggle(BOARD_LED_RED_GPIO, 1U << BOARD_LED_RED_GPIO_PIN) /*!< Toggle on target LED_RED */
121
122#define LED_GREEN_INIT(output) \
123 GPIO_PinWrite(BOARD_LED_GREEN_GPIO, BOARD_LED_GREEN_GPIO_PIN, output); \
124 BOARD_LED_GREEN_GPIO->PDDR |= (1U << BOARD_LED_GREEN_GPIO_PIN) /*!< Enable target LED_GREEN */
125#define LED_GREEN_ON() \
126 GPIO_PortClear(BOARD_LED_GREEN_GPIO, 1U << BOARD_LED_GREEN_GPIO_PIN) /*!< Turn on target LED_GREEN */
127#define LED_GREEN_OFF() \
128 GPIO_PortSet(BOARD_LED_GREEN_GPIO, 1U << BOARD_LED_GREEN_GPIO_PIN) /*!< Turn off target LED_GREEN */
129#define LED_GREEN_TOGGLE() \
130 GPIO_PortToggle(BOARD_LED_GREEN_GPIO, 1U << BOARD_LED_GREEN_GPIO_PIN) /*!< Toggle on target LED_GREEN */
131
132/* ERPC SPI configuration */
133#define ERPC_BOARD_SPI_BASEADDR SPI1
134#define ERPC_BOARD_SPI_BAUDRATE 500000U
135#define ERPC_BOARD_SPI_CLKSRC SPI1_CLK_SRC
136#define ERPC_BOARD_SPI_CLK_FREQ CLOCK_GetFreq(SPI1_CLK_SRC)
137#define ERPC_BOARD_SPI_INT_GPIO GPIOC
138#define ERPC_BOARD_SPI_INT_PORT PORTC
139#define ERPC_BOARD_SPI_INT_PIN 1U
140#define ERPC_BOARD_SPI_INT_PIN_IRQ PORTC_PORTD_IRQn
141#define ERPC_BOARD_SPI_INT_PIN_IRQ_HANDLER PORTC_PORTD_IRQHandler
142
143/* DAC base address */
144#define BOARD_DAC_BASEADDR DAC0
145
146/* Board accelerometer driver */
147#define BOARD_ACCEL_MMA
148
149#if defined(__cplusplus)
150extern "C" {
151#endif /* __cplusplus */
152
153/*******************************************************************************
154 * API
155 ******************************************************************************/
156
157void BOARD_InitDebugConsole(void);
158#if defined(SDK_I2C_BASED_COMPONENT_USED) && SDK_I2C_BASED_COMPONENT_USED
159void BOARD_I2C_Init(I2C_Type *base, uint32_t clkSrc_Hz);
160status_t BOARD_I2C_Send(I2C_Type *base,
161 uint8_t deviceAddress,
162 uint32_t subAddress,
163 uint8_t subaddressSize,
164 uint8_t *txBuff,
165 uint8_t txBuffSize);
166status_t BOARD_I2C_Receive(I2C_Type *base,
167 uint8_t deviceAddress,
168 uint32_t subAddress,
169 uint8_t subaddressSize,
170 uint8_t *rxBuff,
171 uint8_t rxBuffSize);
172void BOARD_Accel_I2C_Init(void);
173status_t BOARD_Accel_I2C_Send(uint8_t deviceAddress, uint32_t subAddress, uint8_t subaddressSize, uint32_t txBuff);
174status_t BOARD_Accel_I2C_Receive(
175 uint8_t deviceAddress, uint32_t subAddress, uint8_t subaddressSize, uint8_t *rxBuff, uint8_t rxBuffSize);
176#endif /* SDK_I2C_BASED_COMPONENT_USED */
177
178#if defined(__cplusplus)
179}
180#endif /* __cplusplus */
181
182#endif /* _BOARD_H_ */
diff --git a/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/clock_config.c b/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/clock_config.c
new file mode 100644
index 000000000..844a3534c
--- /dev/null
+++ b/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/clock_config.c
@@ -0,0 +1,210 @@
1/*
2 * Copyright 2019 NXP
3 * All rights reserved.
4 *
5 * SPDX-License-Identifier: BSD-3-Clause
6 */
7
8/***********************************************************************************************************************
9 * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file
10 * will be overwritten if the respective MCUXpresso Config Tools is used to update this file.
11 **********************************************************************************************************************/
12/*
13 * How to setup clock using clock driver functions:
14 *
15 * 1. CLOCK_SetSimSafeDivs, to make sure core clock, bus clock, flexbus clock
16 * and flash clock are in allowed range during clock mode switch.
17 *
18 * 2. Call CLOCK_Osc0Init to setup OSC clock, if it is used in target mode.
19 *
20 * 3. Call CLOCK_SetMcgliteConfig to set MCG_Lite configuration.
21 *
22 * 4. Call CLOCK_SetSimConfig to set the clock configuration in SIM.
23 */
24
25/* clang-format off */
26/* TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
27!!GlobalInfo
28product: Clocks v6.0
29processor: K32L2B11xxxxA
30package_id: K32L2B11VLH0A
31mcu_data: ksdk2_0
32processor_version: 0.0.0
33 * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/
34/* clang-format on */
35
36#include "fsl_smc.h"
37#include "clock_config.h"
38
39/*******************************************************************************
40 * Definitions
41 ******************************************************************************/
42#define OSC_CAP0P 0U /*!< Oscillator 0pF capacitor load */
43#define OSC_ER_CLK_DISABLE 0U /*!< Disable external reference clock */
44#define SIM_OSC32KSEL_OSC32KCLK_CLK 0U /*!< OSC32KSEL select: OSC32KCLK clock */
45
46/*******************************************************************************
47 * Variables
48 ******************************************************************************/
49/* System clock frequency. */
50extern uint32_t SystemCoreClock;
51
52/*******************************************************************************
53 ************************ BOARD_InitBootClocks function ************************
54 ******************************************************************************/
55void BOARD_InitBootClocks(void)
56{
57 BOARD_BootClockRUN();
58}
59
60/*******************************************************************************
61 ********************** Configuration BOARD_BootClockRUN ***********************
62 ******************************************************************************/
63/* clang-format off */
64/* TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
65!!Configuration
66name: BOARD_BootClockRUN
67called_from_default_init: true
68outputs:
69- {id: Bus_clock.outFreq, value: 24 MHz}
70- {id: Core_clock.outFreq, value: 48 MHz}
71- {id: Flash_clock.outFreq, value: 24 MHz}
72- {id: LPO_clock.outFreq, value: 1 kHz}
73- {id: MCGIRCLK.outFreq, value: 8 MHz}
74- {id: MCGPCLK.outFreq, value: 48 MHz}
75- {id: System_clock.outFreq, value: 48 MHz}
76settings:
77- {id: MCGMode, value: HIRC}
78- {id: MCG.CLKS.sel, value: MCG.HIRC}
79- {id: MCG_C2_OSC_MODE_CFG, value: ModeOscLowPower}
80- {id: MCG_C2_RANGE0_CFG, value: Very_high}
81- {id: MCG_MC_HIRCEN_CFG, value: Enabled}
82- {id: OSC0_CR_ERCLKEN_CFG, value: Enabled}
83- {id: OSC_CR_ERCLKEN_CFG, value: Enabled}
84- {id: SIM.CLKOUTSEL.sel, value: MCG.MCGPCLK}
85- {id: SIM.COPCLKSEL.sel, value: OSC.OSCERCLK}
86- {id: SIM.FLEXIOSRCSEL.sel, value: MCG.MCGPCLK}
87- {id: SIM.LPUART0SRCSEL.sel, value: MCG.MCGPCLK}
88- {id: SIM.LPUART1SRCSEL.sel, value: MCG.MCGPCLK}
89- {id: SIM.RTCCLKOUTSEL.sel, value: OSC.OSCERCLK}
90- {id: SIM.TPMSRCSEL.sel, value: MCG.MCGPCLK}
91- {id: SIM.USBSRCSEL.sel, value: MCG.MCGPCLK}
92sources:
93- {id: MCG.HIRC.outFreq, value: 48 MHz}
94- {id: OSC.OSC.outFreq, value: 32 MHz}
95 * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/
96/* clang-format on */
97
98/*******************************************************************************
99 * Variables for BOARD_BootClockRUN configuration
100 ******************************************************************************/
101const mcglite_config_t mcgliteConfig_BOARD_BootClockRUN = {
102 .outSrc = kMCGLITE_ClkSrcHirc, /* MCGOUTCLK source is HIRC */
103 .irclkEnableMode = kMCGLITE_IrclkEnable, /* MCGIRCLK enabled, MCGIRCLK disabled in STOP mode */
104 .ircs = kMCGLITE_Lirc8M, /* Slow internal reference (LIRC) 8 MHz clock selected */
105 .fcrdiv = kMCGLITE_LircDivBy1, /* Low-frequency Internal Reference Clock Divider: divided by 1 */
106 .lircDiv2 = kMCGLITE_LircDivBy1, /* Second Low-frequency Internal Reference Clock Divider: divided by 1 */
107 .hircEnableInNotHircMode = true, /* HIRC source is enabled */
108};
109const sim_clock_config_t simConfig_BOARD_BootClockRUN = {
110 .er32kSrc = SIM_OSC32KSEL_OSC32KCLK_CLK, /* OSC32KSEL select: OSC32KCLK clock */
111 .clkdiv1 = 0x10000U, /* SIM_CLKDIV1 - OUTDIV1: /1, OUTDIV4: /2 */
112};
113const osc_config_t oscConfig_BOARD_BootClockRUN = {
114 .freq = 0U, /* Oscillator frequency: 0Hz */
115 .capLoad = (OSC_CAP0P), /* Oscillator capacity load: 0pF */
116 .workMode = kOSC_ModeOscLowPower, /* Oscillator low power */
117 .oscerConfig = {
118 .enableMode =
119 kOSC_ErClkEnable, /* Enable external reference clock, disable external reference clock in STOP mode */
120 }};
121
122/*******************************************************************************
123 * Code for BOARD_BootClockRUN configuration
124 ******************************************************************************/
125void BOARD_BootClockRUN(void)
126{
127 /* Set the system clock dividers in SIM to safe value. */
128 CLOCK_SetSimSafeDivs();
129 /* Set MCG to HIRC mode. */
130 CLOCK_SetMcgliteConfig(&mcgliteConfig_BOARD_BootClockRUN);
131 /* Set the clock configuration in SIM module. */
132 CLOCK_SetSimConfig(&simConfig_BOARD_BootClockRUN);
133 /* Set SystemCoreClock variable. */
134 SystemCoreClock = BOARD_BOOTCLOCKRUN_CORE_CLOCK;
135}
136
137/*******************************************************************************
138 ********************* Configuration BOARD_BootClockVLPR ***********************
139 ******************************************************************************/
140/* clang-format off */
141/* TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
142!!Configuration
143name: BOARD_BootClockVLPR
144outputs:
145- {id: Bus_clock.outFreq, value: 1 MHz}
146- {id: Core_clock.outFreq, value: 2 MHz}
147- {id: Flash_clock.outFreq, value: 1 MHz}
148- {id: LPO_clock.outFreq, value: 1 kHz}
149- {id: MCGIRCLK.outFreq, value: 2 MHz}
150- {id: System_clock.outFreq, value: 2 MHz}
151settings:
152- {id: MCGMode, value: LIRC2M}
153- {id: powerMode, value: VLPR}
154- {id: MCG_C2_OSC_MODE_CFG, value: ModeOscLowPower}
155- {id: RTCCLKOUTConfig, value: 'yes'}
156- {id: SIM.OUTDIV4.scale, value: '2', locked: true}
157- {id: SIM.RTCCLKOUTSEL.sel, value: OSC.OSCERCLK}
158sources:
159- {id: MCG.LIRC.outFreq, value: 2 MHz}
160- {id: OSC.OSC.outFreq, value: 32.768 kHz}
161 * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/
162/* clang-format on */
163
164/*******************************************************************************
165 * Variables for BOARD_BootClockVLPR configuration
166 ******************************************************************************/
167const mcglite_config_t mcgliteConfig_BOARD_BootClockVLPR = {
168 .outSrc = kMCGLITE_ClkSrcLirc, /* MCGOUTCLK source is LIRC */
169 .irclkEnableMode = kMCGLITE_IrclkEnable, /* MCGIRCLK enabled, MCGIRCLK disabled in STOP mode */
170 .ircs = kMCGLITE_Lirc2M, /* Slow internal reference (LIRC) 2 MHz clock selected */
171 .fcrdiv = kMCGLITE_LircDivBy1, /* Low-frequency Internal Reference Clock Divider: divided by 1 */
172 .lircDiv2 = kMCGLITE_LircDivBy1, /* Second Low-frequency Internal Reference Clock Divider: divided by 1 */
173 .hircEnableInNotHircMode = false, /* HIRC source is not enabled */
174};
175const sim_clock_config_t simConfig_BOARD_BootClockVLPR = {
176 .er32kSrc = SIM_OSC32KSEL_OSC32KCLK_CLK, /* OSC32KSEL select: OSC32KCLK clock */
177 .clkdiv1 = 0x10000U, /* SIM_CLKDIV1 - OUTDIV1: /1, OUTDIV4: /2 */
178};
179const osc_config_t oscConfig_BOARD_BootClockVLPR = {
180 .freq = 0U, /* Oscillator frequency: 0Hz */
181 .capLoad = (OSC_CAP0P), /* Oscillator capacity load: 0pF */
182 .workMode = kOSC_ModeOscLowPower, /* Oscillator low power */
183 .oscerConfig = {
184 .enableMode = OSC_ER_CLK_DISABLE, /* Disable external reference clock */
185 }};
186
187/*******************************************************************************
188 * Code for BOARD_BootClockVLPR configuration
189 ******************************************************************************/
190void BOARD_BootClockVLPR(void)
191{
192 /* Set the system clock dividers in SIM to safe value. */
193 CLOCK_SetSimSafeDivs();
194 /* Set MCG to LIRC2M mode. */
195 CLOCK_SetMcgliteConfig(&mcgliteConfig_BOARD_BootClockVLPR);
196 /* Set the clock configuration in SIM module. */
197 CLOCK_SetSimConfig(&simConfig_BOARD_BootClockVLPR);
198 /* Set VLPR power mode. */
199 SMC_SetPowerModeProtection(SMC, kSMC_AllowPowerModeAll);
200#if (defined(FSL_FEATURE_SMC_HAS_LPWUI) && FSL_FEATURE_SMC_HAS_LPWUI)
201 SMC_SetPowerModeVlpr(SMC, false);
202#else
203 SMC_SetPowerModeVlpr(SMC);
204#endif
205 while (SMC_GetPowerModeState(SMC) != kSMC_PowerStateVlpr)
206 {
207 }
208 /* Set SystemCoreClock variable. */
209 SystemCoreClock = BOARD_BOOTCLOCKVLPR_CORE_CLOCK;
210}
diff --git a/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/clock_config.h b/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/clock_config.h
new file mode 100644
index 000000000..32e3f10b3
--- /dev/null
+++ b/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/clock_config.h
@@ -0,0 +1,110 @@
1/*
2 * Copyright 2019 NXP
3 * All rights reserved.
4 *
5 * SPDX-License-Identifier: BSD-3-Clause
6 */
7
8/***********************************************************************************************************************
9 * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file
10 * will be overwritten if the respective MCUXpresso Config Tools is used to update this file.
11 **********************************************************************************************************************/
12
13#ifndef _CLOCK_CONFIG_H_
14#define _CLOCK_CONFIG_H_
15
16#include "fsl_common.h"
17
18/*******************************************************************************
19 * Definitions
20 ******************************************************************************/
21
22/*******************************************************************************
23 ************************ BOARD_InitBootClocks function ************************
24 ******************************************************************************/
25
26#if defined(__cplusplus)
27extern "C" {
28#endif /* __cplusplus*/
29
30/*!
31 * @brief This function executes default configuration of clocks.
32 *
33 */
34void BOARD_InitBootClocks(void);
35
36#if defined(__cplusplus)
37}
38#endif /* __cplusplus*/
39
40/*******************************************************************************
41 ********************** Configuration BOARD_BootClockRUN ***********************
42 ******************************************************************************/
43/*******************************************************************************
44 * Definitions for BOARD_BootClockRUN configuration
45 ******************************************************************************/
46#define BOARD_BOOTCLOCKRUN_CORE_CLOCK 48000000U /*!< Core clock frequency: 48000000Hz */
47
48/*! @brief MCG lite set for BOARD_BootClockRUN configuration.
49 */
50extern const mcglite_config_t mcgliteConfig_BOARD_BootClockRUN;
51/*! @brief SIM module set for BOARD_BootClockRUN configuration.
52 */
53extern const sim_clock_config_t simConfig_BOARD_BootClockRUN;
54/*! @brief OSC set for BOARD_BootClockRUN configuration.
55 */
56extern const osc_config_t oscConfig_BOARD_BootClockRUN;
57
58/*******************************************************************************
59 * API for BOARD_BootClockRUN configuration
60 ******************************************************************************/
61#if defined(__cplusplus)
62extern "C" {
63#endif /* __cplusplus*/
64
65/*!
66 * @brief This function executes configuration of clocks.
67 *
68 */
69void BOARD_BootClockRUN(void);
70
71#if defined(__cplusplus)
72}
73#endif /* __cplusplus*/
74
75/*******************************************************************************
76 ********************* Configuration BOARD_BootClockVLPR ***********************
77 ******************************************************************************/
78/*******************************************************************************
79 * Definitions for BOARD_BootClockVLPR configuration
80 ******************************************************************************/
81#define BOARD_BOOTCLOCKVLPR_CORE_CLOCK 2000000U /*!< Core clock frequency: 2000000Hz */
82
83/*! @brief MCG lite set for BOARD_BootClockVLPR configuration.
84 */
85extern const mcglite_config_t mcgliteConfig_BOARD_BootClockVLPR;
86/*! @brief SIM module set for BOARD_BootClockVLPR configuration.
87 */
88extern const sim_clock_config_t simConfig_BOARD_BootClockVLPR;
89/*! @brief OSC set for BOARD_BootClockVLPR configuration.
90 */
91extern const osc_config_t oscConfig_BOARD_BootClockVLPR;
92
93/*******************************************************************************
94 * API for BOARD_BootClockVLPR configuration
95 ******************************************************************************/
96#if defined(__cplusplus)
97extern "C" {
98#endif /* __cplusplus*/
99
100/*!
101 * @brief This function executes configuration of clocks.
102 *
103 */
104void BOARD_BootClockVLPR(void);
105
106#if defined(__cplusplus)
107}
108#endif /* __cplusplus*/
109
110#endif /* _CLOCK_CONFIG_H_ */
diff --git a/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/peripherals.c b/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/peripherals.c
new file mode 100644
index 000000000..d6417f7ed
--- /dev/null
+++ b/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/peripherals.c
@@ -0,0 +1,61 @@
1/*
2 * Copyright 2019 NXP
3 * All rights reserved.
4 *
5 * SPDX-License-Identifier: BSD-3-Clause
6 */
7
8/***********************************************************************************************************************
9 * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file
10 * will be overwritten if the respective MCUXpresso Config Tools is used to update this file.
11 **********************************************************************************************************************/
12
13/* clang-format off */
14/* TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
15!!GlobalInfo
16product: Peripherals v6.0
17processor: K32L2B11xxxxA
18>>>>>>> release/2.6.0_k32l2b_rfp_devices
19package_id: K32L2B11VLH0A
20mcu_data: ksdk2_0
21processor_version: 0.0.0
22functionalGroups:
23- name: BOARD_InitPeripherals
24 called_from_default_init: true
25 selectedCore: core0
26 * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/
27
28/* TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
29component:
30- type: 'system'
31- type_id: 'system_54b53072540eeeb8f8e9343e71f28176'
32- global_system_definitions: []
33 * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/
34
35/* TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
36component:
37- type: 'msg'
38- type_id: 'msg_6e2baaf3b97dbeef01c0043275f9a0e7'
39- global_messages: []
40 * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/
41/* clang-format on */
42
43/***********************************************************************************************************************
44 * Included files
45 **********************************************************************************************************************/
46#include "peripherals.h"
47
48/***********************************************************************************************************************
49 * Initialization functions
50 **********************************************************************************************************************/
51void BOARD_InitPeripherals(void)
52{
53}
54
55/***********************************************************************************************************************
56 * BOARD_InitBootPeripherals function
57 **********************************************************************************************************************/
58void BOARD_InitBootPeripherals(void)
59{
60 BOARD_InitPeripherals();
61}
diff --git a/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/peripherals.h b/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/peripherals.h
new file mode 100644
index 000000000..96cfdfdd2
--- /dev/null
+++ b/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/peripherals.h
@@ -0,0 +1,34 @@
1/*
2 * Copyright 2019 NXP
3 * All rights reserved.
4 *
5 * SPDX-License-Identifier: BSD-3-Clause
6 */
7
8/***********************************************************************************************************************
9 * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file
10 * will be overwritten if the respective MCUXpresso Config Tools is used to update this file.
11 **********************************************************************************************************************/
12
13#ifndef _PERIPHERALS_H_
14#define _PERIPHERALS_H_
15
16#if defined(__cplusplus)
17extern "C" {
18#endif /* __cplusplus */
19
20/***********************************************************************************************************************
21 * Initialization functions
22 **********************************************************************************************************************/
23void BOARD_InitPeripherals(void);
24
25/***********************************************************************************************************************
26 * BOARD_InitBootPeripherals function
27 **********************************************************************************************************************/
28void BOARD_InitBootPeripherals(void);
29
30#if defined(__cplusplus)
31}
32#endif
33
34#endif /* _PERIPHERALS_H_ */
diff --git a/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/pin_mux.c b/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/pin_mux.c
new file mode 100644
index 000000000..ba444fb0a
--- /dev/null
+++ b/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/pin_mux.c
@@ -0,0 +1,792 @@
1/*
2 * Copyright 2019 NXP
3 * All rights reserved.
4 *
5 * SPDX-License-Identifier: BSD-3-Clause
6 */
7
8/***********************************************************************************************************************
9 * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file
10 * will be overwritten if the respective MCUXpresso Config Tools is used to update this file.
11 **********************************************************************************************************************/
12
13/* clang-format off */
14/*
15 * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
16!!GlobalInfo
17product: Pins v6.0
18processor: K32L2B11xxxxA
19package_id: K32L2B11VLH0A
20mcu_data: ksdk2_0
21processor_version: 0.0.0
22board: FRDM-K32L2B
23pin_labels:
24- {pin_num: '23', pin_signal: PTA1/LPUART0_RX/TPM2_CH0, label: 'J1[2]/D0/UART0_RX', identifier: DEBUG_UART0_RX}
25- {pin_num: '24', pin_signal: PTA2/LPUART0_TX/TPM2_CH1, label: 'J1[4]/D1/UART0_TX', identifier: DEBUG_UART0_TX}
26- {pin_num: '60', pin_signal: LCD_P43/PTD3/SPI0_MISO/UART2_TX/TPM0_CH3/SPI0_MOSI/FXIO0_D3, label: 'J1[6]/D2/LCD_P43', identifier: LCD_P43}
27- {pin_num: '28', pin_signal: PTA12/TPM1_CH0, label: 'J1[8]/D3'}
28- {pin_num: '26', pin_signal: PTA4/I2C1_SDA/TPM0_CH1/NMI_b, label: 'J1[10]/D4/SW1', identifier: SW1}
29- {pin_num: '27', pin_signal: PTA5/USB_CLKIN/TPM0_CH2, label: 'J1[12]/D5/USB_CLKIN', identifier: USB0_CLKIN}
30- {pin_num: '17', pin_signal: CMP0_IN5/ADC0_SE4b/PTE29/TPM0_CH2/TPM_CLKIN0, label: 'J1[14]/D6/CMP0_IN5'}
31- {pin_num: '18', pin_signal: DAC0_OUT/ADC0_SE23/CMP0_IN4/PTE30/TPM0_CH3/TPM_CLKIN1/LPUART1_TX/LPTMR0_ALT1, label: 'J1[16]/J4[11]/D7/CMP0_IN4/DAC_OUT'}
32- {pin_num: '29', pin_signal: PTA13/TPM1_CH1, label: 'J2[2]/D8'}
33- {pin_num: '59', pin_signal: LCD_P42/PTD2/SPI0_MOSI/UART2_RX/TPM0_CH2/SPI0_MISO/FXIO0_D2, label: 'J2[4]/D9/LCD_P42', identifier: LCD_P42}
34- {pin_num: '61', pin_signal: LCD_P44/PTD4/LLWU_P14/SPI1_SS/UART2_RX/TPM0_CH4/FXIO0_D4, label: 'J2[6]/D10/SPI1_PCS0/LCD_P44', identifier: LCD_P44}
35- {pin_num: '63', pin_signal: LCD_P46/ADC0_SE7b/PTD6/LLWU_P15/SPI1_MOSI/LPUART0_RX/SPI1_MISO/FXIO0_D6, label: 'J2[8]/D11/SPI1_MOSI/LCD_P46'}
36- {pin_num: '64', pin_signal: LCD_P47/PTD7/SPI1_MISO/LPUART0_TX/SPI1_MOSI/FXIO0_D7, label: 'J2[10]/D12/SPI1_MISO/LCD_P47'}
37- {pin_num: '62', pin_signal: LCD_P45/ADC0_SE6b/PTD5/SPI1_SCK/UART2_TX/TPM0_CH5/FXIO0_D5, label: 'J2[12]/D13/SPI1_SCK/LED1/LCD_P45', identifier: LED1}
38- {pin_num: '1', pin_signal: LCD_P48/PTE0/CLKOUT32K/SPI1_MISO/LPUART1_TX/RTC_CLKOUT/CMP0_OUT/I2C1_SDA, label: 'J2[18]/J4[9]/D14/I2C1_SDA/CMP0_OUT/LCD_P48', identifier: I2C1_SDA}
39- {pin_num: '2', pin_signal: LCD_P49/PTE1/SPI1_MOSI/LPUART1_RX/SPI1_MISO/I2C1_SCL, label: 'J2[20]/D15/I2C1_SCL/LCD_P49', identifier: I2C1_SCL}
40- {pin_num: '39', pin_signal: LCD_P12/PTB16/SPI1_MOSI/LPUART0_RX/TPM_CLKIN0/SPI1_MISO, label: 'J2[19]/LCD_P12'}
41- {pin_num: '40', pin_signal: LCD_P13/PTB17/SPI1_MISO/LPUART0_TX/TPM_CLKIN1/SPI1_MOSI, label: 'J2[17]/LCD_P13'}
42- {pin_num: '54', pin_signal: LCD_P25/PTC5/LLWU_P9/SPI0_SCK/LPTMR0_ALT2/CMP0_OUT, label: 'J1[15]/INT1_ACCEL/LCD_P25', identifier: INT1_ACCEL}
43- {pin_num: '56', pin_signal: LCD_P27/CMP0_IN1/PTC7/SPI0_MISO/USB_SOF_OUT/SPI0_MOSI, label: 'J1[11]/USB_SOF_OUT/LCD_P27', identifier: LCD_P27}
44- {pin_num: '55', pin_signal: LCD_P26/CMP0_IN0/PTC6/LLWU_P10/SPI0_MOSI/EXTRG_IN/SPI0_MISO, label: 'J1[9]/LCD_P26', identifier: LCD_P26}
45- {pin_num: '53', pin_signal: LCD_P24/PTC4/LLWU_P8/SPI0_SS/LPUART1_TX/TPM0_CH3, label: 'J1[7]/LCD_P24', identifier: LCD_P24}
46- {pin_num: '43', pin_signal: LCD_P20/ADC0_SE14/PTC0/EXTRG_IN/USB_SOF_OUT/CMP0_OUT, label: 'J1[5]/LCD_P20/USB_SOF_OUT', identifier: LCD_P20;USB_SOF_OUT}
47- {pin_num: '42', pin_signal: LCD_P15/PTB19/TPM2_CH1, label: 'J1[3]/LCD_P15', identifier: LCD_P15}
48- {pin_num: '41', pin_signal: LCD_P14/PTB18/TPM2_CH0, label: 'J1[1]/LCD_P14', identifier: LCD_P14}
49- {pin_num: '12', pin_signal: ADC0_DM3/ADC0_SE7a/PTE23/TPM2_CH1/UART2_RX/FXIO0_D7, label: 'J4[7]/DIFF_ADC1_DM'}
50- {pin_num: '11', pin_signal: ADC0_DP3/ADC0_SE3/PTE22/TPM2_CH0/UART2_TX/FXIO0_D6, label: 'J4[5]/DIFF_ADC1_DP'}
51- {pin_num: '10', pin_signal: LCD_P60/ADC0_DM0/ADC0_SE4a/PTE21/TPM1_CH1/LPUART0_RX/FXIO0_D5, label: 'J4[3]/DIFF_ADC0_DM/LCD_P60', identifier: LCD_P60}
52- {pin_num: '9', pin_signal: LCD_P59/ADC0_DP0/ADC0_SE0/PTE20/TPM1_CH0/LPUART0_TX/FXIO0_D4, label: 'J4[1]/DIFF_ADC0_DP/LCD_P59', identifier: LCD_P59}
53- {pin_num: '35', pin_signal: LCD_P0/ADC0_SE8/PTB0/LLWU_P5/I2C0_SCL/TPM1_CH0, label: 'J4[2]/A0/LCD_P0'}
54- {pin_num: '36', pin_signal: LCD_P1/ADC0_SE9/PTB1/I2C0_SDA/TPM1_CH1, label: 'J4[4]/A1/LCD_P1'}
55- {pin_num: '37', pin_signal: LCD_P2/ADC0_SE12/PTB2/I2C0_SCL/TPM2_CH0, label: 'J4[6]/A2/LCD_P2'}
56- {pin_num: '38', pin_signal: LCD_P3/ADC0_SE13/PTB3/I2C0_SDA/TPM2_CH1, label: 'J4[8]/A3/LCD_P3'}
57- {pin_num: '45', pin_signal: LCD_P22/ADC0_SE11/PTC2/I2C1_SDA/TPM0_CH1, label: 'J4[10]/A4/LCD_P22'}
58- {pin_num: '44', pin_signal: LCD_P21/ADC0_SE15/PTC1/LLWU_P6/RTC_CLKIN/I2C1_SCL/TPM0_CH0, label: 'J4[12]/A5/LCD_P21'}
59- {pin_num: '5', pin_signal: USB0_DP, label: 'J10[3]/USB_DP', identifier: USB0_DP}
60- {pin_num: '6', pin_signal: USB0_DM, label: 'J10[2]/USB_DM', identifier: USB0_DM}
61- {pin_num: '22', pin_signal: PTA0/TPM0_CH5/SWD_CLK, label: 'J11[4]/K32L2_SWD_CLK'}
62- {pin_num: '25', pin_signal: PTA3/I2C1_SCL/TPM0_CH0/SWD_DIO, label: 'J11[2]/SWD_DIO_TGTMCU'}
63- {pin_num: '32', pin_signal: EXTAL0/PTA18/LPUART1_RX/TPM_CLKIN0, label: EXTAL_32KHZ, identifier: EXTAL_32KHZ}
64- {pin_num: '33', pin_signal: XTAL0/PTA19/LPUART1_TX/TPM_CLKIN1/LPTMR0_ALT1, label: XTAL_32KHZ, identifier: XTAL_32KHZ}
65- {pin_num: '34', pin_signal: PTA20/RESET_b, label: 'J11[10]/J3[6]/RESET/SW2'}
66- {pin_num: '46', pin_signal: LCD_P23/PTC3/LLWU_P7/SPI1_SCK/LPUART1_RX/TPM0_CH2/CLKOUT, label: SW3/LLWU_P7/LCD_P23, identifier: SW3}
67- {pin_num: '58', pin_signal: LCD_P41/ADC0_SE5b/PTD1/SPI0_SCK/TPM0_CH1/FXIO0_D1, label: 'U2[9]/U10[9]/INT2_ACCEL/INT1_MAG/LCD_P41', identifier: INT2_ACCEL;INT1_MAG}
68- {pin_num: '21', pin_signal: PTE25/TPM0_CH1/I2C0_SDA, label: 'U2[6]/U10[6]/I2C0_SDA', identifier: I2C0_SDA}
69- {pin_num: '20', pin_signal: PTE24/TPM0_CH0/I2C0_SCL, label: 'U2[7]/U10[4]/I2C0_SCL', identifier: I2C0_SCL}
70- {pin_num: '3', pin_signal: VDD17, label: P3V3_K32L2B}
71- {pin_num: '13', pin_signal: VDDA, label: P3V3_K32L2B}
72- {pin_num: '30', pin_signal: VDD94, label: P3V3_K32L2B}
73- {pin_num: '4', pin_signal: VSS18, label: GND}
74- {pin_num: '16', pin_signal: VSSA, label: GND}
75- {pin_num: '31', pin_signal: VSS95, label: GND}
76- {pin_num: '47', pin_signal: VSS136, label: GND}
77- {pin_num: '7', pin_signal: VOUT33, label: VOUT33}
78- {pin_num: '8', pin_signal: VREGIN, label: USB_REGIN, identifier: USB0_VREGIN}
79- {pin_num: '15', pin_signal: VREFL, label: GND}
80- {pin_num: '14', pin_signal: VREFH, label: 'J19[2]/P3V3_K32L2B'}
81- {pin_num: '19', pin_signal: PTE31/TPM0_CH4, label: LED2, identifier: LED2}
82- {pin_num: '48', pin_signal: VLL3, label: 'J12[1]/P3V3_K32L2B'}
83- {pin_num: '49', pin_signal: VLL2/LCD_P4/PTC20, label: TP12/LCD_P4}
84- {pin_num: '50', pin_signal: VLL1/LCD_P5/PTC21, label: TP10/LCD_P5}
85- {pin_num: '51', pin_signal: VCAP2/LCD_P6/PTC22, label: LCD_P6}
86- {pin_num: '52', pin_signal: VCAP1/LCD_P39/PTC23, label: LCD_P39}
87- {pin_num: '57', pin_signal: LCD_P40/PTD0/SPI0_SS/TPM0_CH0/FXIO0_D0, label: LCD-09_P40, identifier: LCD_P40}
88 * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
89 */
90/* clang-format on */
91
92#include "fsl_common.h"
93#include "fsl_port.h"
94#include "fsl_gpio.h"
95#include "pin_mux.h"
96
97/* FUNCTION ************************************************************************************************************
98 *
99 * Function Name : BOARD_InitBootPins
100 * Description : Calls initialization functions.
101 *
102 * END ****************************************************************************************************************/
103void BOARD_InitBootPins(void)
104{
105 BOARD_InitPins();
106 BOARD_InitDEBUG_UARTPins();
107}
108
109/* clang-format off */
110/*
111 * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
112BOARD_InitPins:
113- options: {callFromInitBoot: 'true', prefix: BOARD_, coreID: core0, enableClock: 'true'}
114- pin_list: []
115 * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
116 */
117/* clang-format on */
118
119/* FUNCTION ************************************************************************************************************
120 *
121 * Function Name : BOARD_InitPins
122 * Description : Configures pin routing and optionally pin electrical features.
123 *
124 * END ****************************************************************************************************************/
125void BOARD_InitPins(void)
126{
127}
128
129/* clang-format off */
130/*
131 * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
132BOARD_InitLCDPins:
133- options: {prefix: BOARD_, coreID: core0, enableClock: 'true'}
134- pin_list:
135 - {pin_num: '41', peripheral: LCD, signal: 'P, 14', pin_signal: LCD_P14/PTB18/TPM2_CH0, slew_rate: slow, pull_select: up, pull_enable: disable}
136 - {pin_num: '42', peripheral: LCD, signal: 'P, 15', pin_signal: LCD_P15/PTB19/TPM2_CH1, slew_rate: slow, pull_select: up, pull_enable: disable}
137 - {pin_num: '43', peripheral: LCD, signal: 'P, 20', pin_signal: LCD_P20/ADC0_SE14/PTC0/EXTRG_IN/USB_SOF_OUT/CMP0_OUT, identifier: LCD_P20, slew_rate: slow, pull_select: up,
138 pull_enable: disable}
139 - {pin_num: '53', peripheral: LCD, signal: 'P, 24', pin_signal: LCD_P24/PTC4/LLWU_P8/SPI0_SS/LPUART1_TX/TPM0_CH3, slew_rate: slow, pull_select: up, pull_enable: disable}
140 - {pin_num: '55', peripheral: LCD, signal: 'P, 26', pin_signal: LCD_P26/CMP0_IN0/PTC6/LLWU_P10/SPI0_MOSI/EXTRG_IN/SPI0_MISO, slew_rate: slow, pull_select: up, pull_enable: disable}
141 - {pin_num: '56', peripheral: LCD, signal: 'P, 27', pin_signal: LCD_P27/CMP0_IN1/PTC7/SPI0_MISO/USB_SOF_OUT/SPI0_MOSI, slew_rate: slow, pull_select: up, pull_enable: disable}
142 - {pin_num: '57', peripheral: LCD, signal: 'P, 40', pin_signal: LCD_P40/PTD0/SPI0_SS/TPM0_CH0/FXIO0_D0, slew_rate: slow, pull_select: up, pull_enable: disable}
143 - {pin_num: '59', peripheral: LCD, signal: 'P, 42', pin_signal: LCD_P42/PTD2/SPI0_MOSI/UART2_RX/TPM0_CH2/SPI0_MISO/FXIO0_D2, slew_rate: slow, pull_select: up, pull_enable: disable}
144 - {pin_num: '60', peripheral: LCD, signal: 'P, 43', pin_signal: LCD_P43/PTD3/SPI0_MISO/UART2_TX/TPM0_CH3/SPI0_MOSI/FXIO0_D3, slew_rate: slow, pull_select: up, pull_enable: disable}
145 - {pin_num: '61', peripheral: LCD, signal: 'P, 44', pin_signal: LCD_P44/PTD4/LLWU_P14/SPI1_SS/UART2_RX/TPM0_CH4/FXIO0_D4, slew_rate: slow, pull_select: up, pull_enable: disable}
146 - {pin_num: '9', peripheral: LCD, signal: 'P, 59', pin_signal: LCD_P59/ADC0_DP0/ADC0_SE0/PTE20/TPM1_CH0/LPUART0_TX/FXIO0_D4, slew_rate: slow, pull_select: up, pull_enable: disable}
147 - {pin_num: '10', peripheral: LCD, signal: 'P, 60', pin_signal: LCD_P60/ADC0_DM0/ADC0_SE4a/PTE21/TPM1_CH1/LPUART0_RX/FXIO0_D5, slew_rate: slow, pull_select: up,
148 pull_enable: disable}
149 * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
150 */
151/* clang-format on */
152
153/* FUNCTION ************************************************************************************************************
154 *
155 * Function Name : BOARD_InitLCDPins
156 * Description : Configures pin routing and optionally pin electrical features.
157 *
158 * END ****************************************************************************************************************/
159void BOARD_InitLCDPins(void)
160{
161 /* Port B Clock Gate Control: Clock enabled */
162 CLOCK_EnableClock(kCLOCK_PortB);
163 /* Port C Clock Gate Control: Clock enabled */
164 CLOCK_EnableClock(kCLOCK_PortC);
165 /* Port D Clock Gate Control: Clock enabled */
166 CLOCK_EnableClock(kCLOCK_PortD);
167 /* Port E Clock Gate Control: Clock enabled */
168 CLOCK_EnableClock(kCLOCK_PortE);
169
170 /* PORTB18 (pin 41) is configured as LCD_P14 */
171 PORT_SetPinMux(BOARD_LCD_P14_PORT, BOARD_LCD_P14_PIN, kPORT_PinDisabledOrAnalog);
172
173 PORTB->PCR[18] = ((PORTB->PCR[18] &
174 /* Mask bits to zero which are setting */
175 (~(PORT_PCR_PS_MASK | PORT_PCR_PE_MASK | PORT_PCR_SRE_MASK | PORT_PCR_ISF_MASK)))
176
177 /* Pull Select: Internal pullup resistor is enabled on the corresponding pin, if the
178 * corresponding PE field is set. */
179 | PORT_PCR_PS(kPORT_PullUp)
180
181 /* Pull Enable: Internal pullup or pulldown resistor is not enabled on the corresponding
182 * pin. */
183 | PORT_PCR_PE(kPORT_PullDisable)
184
185 /* Slew Rate Enable: Slow slew rate is configured on the corresponding pin, if the pin is
186 * configured as a digital output. */
187 | PORT_PCR_SRE(kPORT_SlowSlewRate));
188
189 /* PORTB19 (pin 42) is configured as LCD_P15 */
190 PORT_SetPinMux(BOARD_LCD_P15_PORT, BOARD_LCD_P15_PIN, kPORT_PinDisabledOrAnalog);
191
192 PORTB->PCR[19] = ((PORTB->PCR[19] &
193 /* Mask bits to zero which are setting */
194 (~(PORT_PCR_PS_MASK | PORT_PCR_PE_MASK | PORT_PCR_SRE_MASK | PORT_PCR_ISF_MASK)))
195
196 /* Pull Select: Internal pullup resistor is enabled on the corresponding pin, if the
197 * corresponding PE field is set. */
198 | PORT_PCR_PS(kPORT_PullUp)
199
200 /* Pull Enable: Internal pullup or pulldown resistor is not enabled on the corresponding
201 * pin. */
202 | PORT_PCR_PE(kPORT_PullDisable)
203
204 /* Slew Rate Enable: Slow slew rate is configured on the corresponding pin, if the pin is
205 * configured as a digital output. */
206 | PORT_PCR_SRE(kPORT_SlowSlewRate));
207
208 /* PORTC0 (pin 43) is configured as LCD_P20 */
209 PORT_SetPinMux(BOARD_LCD_P20_PORT, BOARD_LCD_P20_PIN, kPORT_PinDisabledOrAnalog);
210
211 PORTC->PCR[0] = ((PORTC->PCR[0] &
212 /* Mask bits to zero which are setting */
213 (~(PORT_PCR_PS_MASK | PORT_PCR_PE_MASK | PORT_PCR_SRE_MASK | PORT_PCR_ISF_MASK)))
214
215 /* Pull Select: Internal pullup resistor is enabled on the corresponding pin, if the
216 * corresponding PE field is set. */
217 | PORT_PCR_PS(kPORT_PullUp)
218
219 /* Pull Enable: Internal pullup or pulldown resistor is not enabled on the corresponding pin. */
220 | PORT_PCR_PE(kPORT_PullDisable)
221
222 /* Slew Rate Enable: Slow slew rate is configured on the corresponding pin, if the pin is
223 * configured as a digital output. */
224 | PORT_PCR_SRE(kPORT_SlowSlewRate));
225
226 /* PORTC4 (pin 53) is configured as LCD_P24 */
227 PORT_SetPinMux(BOARD_LCD_P24_PORT, BOARD_LCD_P24_PIN, kPORT_PinDisabledOrAnalog);
228
229 PORTC->PCR[4] = ((PORTC->PCR[4] &
230 /* Mask bits to zero which are setting */
231 (~(PORT_PCR_PS_MASK | PORT_PCR_PE_MASK | PORT_PCR_SRE_MASK | PORT_PCR_ISF_MASK)))
232
233 /* Pull Select: Internal pullup resistor is enabled on the corresponding pin, if the
234 * corresponding PE field is set. */
235 | PORT_PCR_PS(kPORT_PullUp)
236
237 /* Pull Enable: Internal pullup or pulldown resistor is not enabled on the corresponding pin. */
238 | PORT_PCR_PE(kPORT_PullDisable)
239
240 /* Slew Rate Enable: Slow slew rate is configured on the corresponding pin, if the pin is
241 * configured as a digital output. */
242 | PORT_PCR_SRE(kPORT_SlowSlewRate));
243
244 /* PORTC6 (pin 55) is configured as LCD_P26 */
245 PORT_SetPinMux(BOARD_LCD_P26_PORT, BOARD_LCD_P26_PIN, kPORT_PinDisabledOrAnalog);
246
247 PORTC->PCR[6] = ((PORTC->PCR[6] &
248 /* Mask bits to zero which are setting */
249 (~(PORT_PCR_PS_MASK | PORT_PCR_PE_MASK | PORT_PCR_SRE_MASK | PORT_PCR_ISF_MASK)))
250
251 /* Pull Select: Internal pullup resistor is enabled on the corresponding pin, if the
252 * corresponding PE field is set. */
253 | PORT_PCR_PS(kPORT_PullUp)
254
255 /* Pull Enable: Internal pullup or pulldown resistor is not enabled on the corresponding pin. */
256 | PORT_PCR_PE(kPORT_PullDisable)
257
258 /* Slew Rate Enable: Slow slew rate is configured on the corresponding pin, if the pin is
259 * configured as a digital output. */
260 | PORT_PCR_SRE(kPORT_SlowSlewRate));
261
262 /* PORTC7 (pin 56) is configured as LCD_P27 */
263 PORT_SetPinMux(BOARD_LCD_P27_PORT, BOARD_LCD_P27_PIN, kPORT_PinDisabledOrAnalog);
264
265 PORTC->PCR[7] = ((PORTC->PCR[7] &
266 /* Mask bits to zero which are setting */
267 (~(PORT_PCR_PS_MASK | PORT_PCR_PE_MASK | PORT_PCR_SRE_MASK | PORT_PCR_ISF_MASK)))
268
269 /* Pull Select: Internal pullup resistor is enabled on the corresponding pin, if the
270 * corresponding PE field is set. */
271 | PORT_PCR_PS(kPORT_PullUp)
272
273 /* Pull Enable: Internal pullup or pulldown resistor is not enabled on the corresponding pin. */
274 | PORT_PCR_PE(kPORT_PullDisable)
275
276 /* Slew Rate Enable: Slow slew rate is configured on the corresponding pin, if the pin is
277 * configured as a digital output. */
278 | PORT_PCR_SRE(kPORT_SlowSlewRate));
279
280 /* PORTD0 (pin 57) is configured as LCD_P40 */
281 PORT_SetPinMux(BOARD_LCD_P40_PORT, BOARD_LCD_P40_PIN, kPORT_PinDisabledOrAnalog);
282
283 PORTD->PCR[0] = ((PORTD->PCR[0] &
284 /* Mask bits to zero which are setting */
285 (~(PORT_PCR_PS_MASK | PORT_PCR_PE_MASK | PORT_PCR_SRE_MASK | PORT_PCR_ISF_MASK)))
286
287 /* Pull Select: Internal pullup resistor is enabled on the corresponding pin, if the
288 * corresponding PE field is set. */
289 | PORT_PCR_PS(kPORT_PullUp)
290
291 /* Pull Enable: Internal pullup or pulldown resistor is not enabled on the corresponding pin. */
292 | PORT_PCR_PE(kPORT_PullDisable)
293
294 /* Slew Rate Enable: Slow slew rate is configured on the corresponding pin, if the pin is
295 * configured as a digital output. */
296 | PORT_PCR_SRE(kPORT_SlowSlewRate));
297
298 /* PORTD2 (pin 59) is configured as LCD_P42 */
299 PORT_SetPinMux(BOARD_LCD_P42_PORT, BOARD_LCD_P42_PIN, kPORT_PinDisabledOrAnalog);
300
301 PORTD->PCR[2] = ((PORTD->PCR[2] &
302 /* Mask bits to zero which are setting */
303 (~(PORT_PCR_PS_MASK | PORT_PCR_PE_MASK | PORT_PCR_SRE_MASK | PORT_PCR_ISF_MASK)))
304
305 /* Pull Select: Internal pullup resistor is enabled on the corresponding pin, if the
306 * corresponding PE field is set. */
307 | PORT_PCR_PS(kPORT_PullUp)
308
309 /* Pull Enable: Internal pullup or pulldown resistor is not enabled on the corresponding pin. */
310 | PORT_PCR_PE(kPORT_PullDisable)
311
312 /* Slew Rate Enable: Slow slew rate is configured on the corresponding pin, if the pin is
313 * configured as a digital output. */
314 | PORT_PCR_SRE(kPORT_SlowSlewRate));
315
316 /* PORTD3 (pin 60) is configured as LCD_P43 */
317 PORT_SetPinMux(BOARD_LCD_P43_PORT, BOARD_LCD_P43_PIN, kPORT_PinDisabledOrAnalog);
318
319 PORTD->PCR[3] = ((PORTD->PCR[3] &
320 /* Mask bits to zero which are setting */
321 (~(PORT_PCR_PS_MASK | PORT_PCR_PE_MASK | PORT_PCR_SRE_MASK | PORT_PCR_ISF_MASK)))
322
323 /* Pull Select: Internal pullup resistor is enabled on the corresponding pin, if the
324 * corresponding PE field is set. */
325 | PORT_PCR_PS(kPORT_PullUp)
326
327 /* Pull Enable: Internal pullup or pulldown resistor is not enabled on the corresponding pin. */
328 | PORT_PCR_PE(kPORT_PullDisable)
329
330 /* Slew Rate Enable: Slow slew rate is configured on the corresponding pin, if the pin is
331 * configured as a digital output. */
332 | PORT_PCR_SRE(kPORT_SlowSlewRate));
333
334 /* PORTD4 (pin 61) is configured as LCD_P44 */
335 PORT_SetPinMux(BOARD_LCD_P44_PORT, BOARD_LCD_P44_PIN, kPORT_PinDisabledOrAnalog);
336
337 PORTD->PCR[4] = ((PORTD->PCR[4] &
338 /* Mask bits to zero which are setting */
339 (~(PORT_PCR_PS_MASK | PORT_PCR_PE_MASK | PORT_PCR_SRE_MASK | PORT_PCR_ISF_MASK)))
340
341 /* Pull Select: Internal pullup resistor is enabled on the corresponding pin, if the
342 * corresponding PE field is set. */
343 | PORT_PCR_PS(kPORT_PullUp)
344
345 /* Pull Enable: Internal pullup or pulldown resistor is not enabled on the corresponding pin. */
346 | PORT_PCR_PE(kPORT_PullDisable)
347
348 /* Slew Rate Enable: Slow slew rate is configured on the corresponding pin, if the pin is
349 * configured as a digital output. */
350 | PORT_PCR_SRE(kPORT_SlowSlewRate));
351
352 /* PORTE20 (pin 9) is configured as LCD_P59 */
353 PORT_SetPinMux(BOARD_LCD_P59_PORT, BOARD_LCD_P59_PIN, kPORT_PinDisabledOrAnalog);
354
355 PORTE->PCR[20] = ((PORTE->PCR[20] &
356 /* Mask bits to zero which are setting */
357 (~(PORT_PCR_PS_MASK | PORT_PCR_PE_MASK | PORT_PCR_SRE_MASK | PORT_PCR_ISF_MASK)))
358
359 /* Pull Select: Internal pullup resistor is enabled on the corresponding pin, if the
360 * corresponding PE field is set. */
361 | PORT_PCR_PS(kPORT_PullUp)
362
363 /* Pull Enable: Internal pullup or pulldown resistor is not enabled on the corresponding
364 * pin. */
365 | PORT_PCR_PE(kPORT_PullDisable)
366
367 /* Slew Rate Enable: Slow slew rate is configured on the corresponding pin, if the pin is
368 * configured as a digital output. */
369 | PORT_PCR_SRE(kPORT_SlowSlewRate));
370
371 /* PORTE21 (pin 10) is configured as LCD_P60 */
372 PORT_SetPinMux(BOARD_LCD_P60_PORT, BOARD_LCD_P60_PIN, kPORT_PinDisabledOrAnalog);
373
374 PORTE->PCR[21] = ((PORTE->PCR[21] &
375 /* Mask bits to zero which are setting */
376 (~(PORT_PCR_PS_MASK | PORT_PCR_PE_MASK | PORT_PCR_SRE_MASK | PORT_PCR_ISF_MASK)))
377
378 /* Pull Select: Internal pullup resistor is enabled on the corresponding pin, if the
379 * corresponding PE field is set. */
380 | PORT_PCR_PS(kPORT_PullUp)
381
382 /* Pull Enable: Internal pullup or pulldown resistor is not enabled on the corresponding
383 * pin. */
384 | PORT_PCR_PE(kPORT_PullDisable)
385
386 /* Slew Rate Enable: Slow slew rate is configured on the corresponding pin, if the pin is
387 * configured as a digital output. */
388 | PORT_PCR_SRE(kPORT_SlowSlewRate));
389}
390
391/* clang-format off */
392/*
393 * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
394BOARD_InitBUTTONSPins:
395- options: {prefix: BOARD_, coreID: core0, enableClock: 'true'}
396- pin_list:
397 - {pin_num: '26', peripheral: GPIOA, signal: 'GPIO, 4', pin_signal: PTA4/I2C1_SDA/TPM0_CH1/NMI_b, direction: INPUT, slew_rate: fast, pull_select: up, pull_enable: enable,
398 passive_filter: disable}
399 - {pin_num: '46', peripheral: GPIOC, signal: 'GPIO, 3', pin_signal: LCD_P23/PTC3/LLWU_P7/SPI1_SCK/LPUART1_RX/TPM0_CH2/CLKOUT, direction: INPUT, slew_rate: fast,
400 pull_select: up, pull_enable: enable}
401 * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
402 */
403/* clang-format on */
404
405/* FUNCTION ************************************************************************************************************
406 *
407 * Function Name : BOARD_InitBUTTONSPins
408 * Description : Configures pin routing and optionally pin electrical features.
409 *
410 * END ****************************************************************************************************************/
411void BOARD_InitBUTTONSPins(void)
412{
413 /* Port A Clock Gate Control: Clock enabled */
414 CLOCK_EnableClock(kCLOCK_PortA);
415 /* Port C Clock Gate Control: Clock enabled */
416 CLOCK_EnableClock(kCLOCK_PortC);
417
418 gpio_pin_config_t SW1_config = {
419 .pinDirection = kGPIO_DigitalInput,
420 .outputLogic = 0U
421 };
422 /* Initialize GPIO functionality on pin PTA4 (pin 26) */
423 GPIO_PinInit(BOARD_SW1_GPIO, BOARD_SW1_PIN, &SW1_config);
424
425 gpio_pin_config_t SW3_config = {
426 .pinDirection = kGPIO_DigitalInput,
427 .outputLogic = 0U
428 };
429 /* Initialize GPIO functionality on pin PTC3 (pin 46) */
430 GPIO_PinInit(BOARD_SW3_GPIO, BOARD_SW3_PIN, &SW3_config);
431
432 const port_pin_config_t SW1 = {/* Internal pull-up resistor is enabled */
433 kPORT_PullUp,
434 /* Fast slew rate is configured */
435 kPORT_FastSlewRate,
436 /* Passive filter is disabled */
437 kPORT_PassiveFilterDisable,
438 /* Low drive strength is configured */
439 kPORT_LowDriveStrength,
440 /* Pin is configured as PTA4 */
441 kPORT_MuxAsGpio};
442 /* PORTA4 (pin 26) is configured as PTA4 */
443 PORT_SetPinConfig(BOARD_SW1_PORT, BOARD_SW1_PIN, &SW1);
444
445 const port_pin_config_t SW3 = {/* Internal pull-up resistor is enabled */
446 kPORT_PullUp,
447 /* Fast slew rate is configured */
448 kPORT_FastSlewRate,
449 /* Passive filter is disabled */
450 kPORT_PassiveFilterDisable,
451 /* Low drive strength is configured */
452 kPORT_LowDriveStrength,
453 /* Pin is configured as PTC3 */
454 kPORT_MuxAsGpio};
455 /* PORTC3 (pin 46) is configured as PTC3 */
456 PORT_SetPinConfig(BOARD_SW3_PORT, BOARD_SW3_PIN, &SW3);
457}
458
459/* clang-format off */
460/*
461 * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
462BOARD_InitLEDsPins:
463- options: {prefix: BOARD_, coreID: core0, enableClock: 'true'}
464- pin_list:
465 - {pin_num: '19', peripheral: GPIOE, signal: 'GPIO, 31', pin_signal: PTE31/TPM0_CH4, direction: OUTPUT, gpio_init_state: 'true', slew_rate: slow, pull_select: down,
466 pull_enable: disable}
467 - {pin_num: '62', peripheral: GPIOD, signal: 'GPIO, 5', pin_signal: LCD_P45/ADC0_SE6b/PTD5/SPI1_SCK/UART2_TX/TPM0_CH5/FXIO0_D5, direction: OUTPUT, gpio_init_state: 'true',
468 slew_rate: slow, pull_select: down, pull_enable: disable}
469 * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
470 */
471/* clang-format on */
472
473/* FUNCTION ************************************************************************************************************
474 *
475 * Function Name : BOARD_InitLEDsPins
476 * Description : Configures pin routing and optionally pin electrical features.
477 *
478 * END ****************************************************************************************************************/
479void BOARD_InitLEDsPins(void)
480{
481 /* Port D Clock Gate Control: Clock enabled */
482 CLOCK_EnableClock(kCLOCK_PortD);
483 /* Port E Clock Gate Control: Clock enabled */
484 CLOCK_EnableClock(kCLOCK_PortE);
485
486 gpio_pin_config_t LED1_config = {
487 .pinDirection = kGPIO_DigitalOutput,
488 .outputLogic = 1U
489 };
490 /* Initialize GPIO functionality on pin PTD5 (pin 62) */
491 GPIO_PinInit(BOARD_LED1_GPIO, BOARD_LED1_PIN, &LED1_config);
492
493 gpio_pin_config_t LED2_config = {
494 .pinDirection = kGPIO_DigitalOutput,
495 .outputLogic = 1U
496 };
497 /* Initialize GPIO functionality on pin PTE31 (pin 19) */
498 GPIO_PinInit(BOARD_LED2_GPIO, BOARD_LED2_PIN, &LED2_config);
499
500 const port_pin_config_t LED1 = {/* Internal pull-up/down resistor is disabled */
501 kPORT_PullDisable,
502 /* Slow slew rate is configured */
503 kPORT_SlowSlewRate,
504 /* Passive filter is disabled */
505 kPORT_PassiveFilterDisable,
506 /* Low drive strength is configured */
507 kPORT_LowDriveStrength,
508 /* Pin is configured as PTD5 */
509 kPORT_MuxAsGpio};
510 /* PORTD5 (pin 62) is configured as PTD5 */
511 PORT_SetPinConfig(BOARD_LED1_PORT, BOARD_LED1_PIN, &LED1);
512
513 const port_pin_config_t LED2 = {/* Internal pull-up/down resistor is disabled */
514 kPORT_PullDisable,
515 /* Slow slew rate is configured */
516 kPORT_SlowSlewRate,
517 /* Passive filter is disabled */
518 kPORT_PassiveFilterDisable,
519 /* Low drive strength is configured */
520 kPORT_LowDriveStrength,
521 /* Pin is configured as PTE31 */
522 kPORT_MuxAsGpio};
523 /* PORTE31 (pin 19) is configured as PTE31 */
524 PORT_SetPinConfig(BOARD_LED2_PORT, BOARD_LED2_PIN, &LED2);
525}
526
527/* clang-format off */
528/*
529 * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
530BOARD_InitDEBUG_UARTPins:
531- options: {callFromInitBoot: 'true', prefix: BOARD_, coreID: core0, enableClock: 'true'}
532- pin_list:
533 - {pin_num: '23', peripheral: LPUART0, signal: RX, pin_signal: PTA1/LPUART0_RX/TPM2_CH0, slew_rate: fast, pull_select: down, pull_enable: disable}
534 - {pin_num: '24', peripheral: LPUART0, signal: TX, pin_signal: PTA2/LPUART0_TX/TPM2_CH1, direction: OUTPUT, slew_rate: fast, pull_select: down, pull_enable: disable}
535 * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
536 */
537/* clang-format on */
538
539/* FUNCTION ************************************************************************************************************
540 *
541 * Function Name : BOARD_InitDEBUG_UARTPins
542 * Description : Configures pin routing and optionally pin electrical features.
543 *
544 * END ****************************************************************************************************************/
545void BOARD_InitDEBUG_UARTPins(void)
546{
547 /* Port A Clock Gate Control: Clock enabled */
548 CLOCK_EnableClock(kCLOCK_PortA);
549
550 const port_pin_config_t DEBUG_UART0_RX = {/* Internal pull-up/down resistor is disabled */
551 kPORT_PullDisable,
552 /* Fast slew rate is configured */
553 kPORT_FastSlewRate,
554 /* Passive filter is disabled */
555 kPORT_PassiveFilterDisable,
556 /* Low drive strength is configured */
557 kPORT_LowDriveStrength,
558 /* Pin is configured as LPUART0_RX */
559 kPORT_MuxAlt2};
560 /* PORTA1 (pin 23) is configured as LPUART0_RX */
561 PORT_SetPinConfig(BOARD_DEBUG_UART0_RX_PORT, BOARD_DEBUG_UART0_RX_PIN, &DEBUG_UART0_RX);
562
563 const port_pin_config_t DEBUG_UART0_TX = {/* Internal pull-up/down resistor is disabled */
564 kPORT_PullDisable,
565 /* Fast slew rate is configured */
566 kPORT_FastSlewRate,
567 /* Passive filter is disabled */
568 kPORT_PassiveFilterDisable,
569 /* Low drive strength is configured */
570 kPORT_LowDriveStrength,
571 /* Pin is configured as LPUART0_TX */
572 kPORT_MuxAlt2};
573 /* PORTA2 (pin 24) is configured as LPUART0_TX */
574 PORT_SetPinConfig(BOARD_DEBUG_UART0_TX_PORT, BOARD_DEBUG_UART0_TX_PIN, &DEBUG_UART0_TX);
575
576 SIM->SOPT5 = ((SIM->SOPT5 &
577 /* Mask bits to zero which are setting */
578 (~(SIM_SOPT5_LPUART0TXSRC_MASK | SIM_SOPT5_LPUART0RXSRC_MASK)))
579
580 /* LPUART0 Transmit Data Source Select: LPUART0_TX pin. */
581 | SIM_SOPT5_LPUART0TXSRC(SOPT5_LPUART0TXSRC_LPUART_TX)
582
583 /* LPUART0 Receive Data Source Select: LPUART_RX pin. */
584 | SIM_SOPT5_LPUART0RXSRC(SOPT5_LPUART0RXSRC_LPUART_RX));
585}
586
587/* clang-format off */
588/*
589 * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
590BOARD_InitUSBPins:
591- options: {prefix: BOARD_, coreID: core0, enableClock: 'true'}
592- pin_list:
593 - {pin_num: '5', peripheral: USB0, signal: DP, pin_signal: USB0_DP}
594 - {pin_num: '6', peripheral: USB0, signal: DM, pin_signal: USB0_DM}
595 - {pin_num: '8', peripheral: USB0, signal: VREGIN, pin_signal: VREGIN}
596 - {pin_num: '43', peripheral: USB0, signal: SOF_OUT, pin_signal: LCD_P20/ADC0_SE14/PTC0/EXTRG_IN/USB_SOF_OUT/CMP0_OUT, identifier: USB_SOF_OUT, slew_rate: fast,
597 pull_select: up, pull_enable: disable}
598 - {pin_num: '27', peripheral: USB0, signal: CLKIN, pin_signal: PTA5/USB_CLKIN/TPM0_CH2, slew_rate: fast, pull_select: up, pull_enable: disable}
599 * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
600 */
601/* clang-format on */
602
603/* FUNCTION ************************************************************************************************************
604 *
605 * Function Name : BOARD_InitUSBPins
606 * Description : Configures pin routing and optionally pin electrical features.
607 *
608 * END ****************************************************************************************************************/
609void BOARD_InitUSBPins(void)
610{
611 /* Port A Clock Gate Control: Clock enabled */
612 CLOCK_EnableClock(kCLOCK_PortA);
613 /* Port C Clock Gate Control: Clock enabled */
614 CLOCK_EnableClock(kCLOCK_PortC);
615
616 /* PORTA5 (pin 27) is configured as USB_CLKIN */
617 PORT_SetPinMux(BOARD_USB0_CLKIN_PORT, BOARD_USB0_CLKIN_PIN, kPORT_MuxAlt2);
618
619 PORTA->PCR[5] = ((PORTA->PCR[5] &
620 /* Mask bits to zero which are setting */
621 (~(PORT_PCR_PS_MASK | PORT_PCR_PE_MASK | PORT_PCR_SRE_MASK | PORT_PCR_ISF_MASK)))
622
623 /* Pull Select: Internal pullup resistor is enabled on the corresponding pin, if the
624 * corresponding PE field is set. */
625 | PORT_PCR_PS(kPORT_PullUp)
626
627 /* Pull Enable: Internal pullup or pulldown resistor is not enabled on the corresponding pin. */
628 | PORT_PCR_PE(kPORT_PullDisable)
629
630 /* Slew Rate Enable: Fast slew rate is configured on the corresponding pin, if the pin is
631 * configured as a digital output. */
632 | PORT_PCR_SRE(kPORT_FastSlewRate));
633
634 /* PORTC0 (pin 43) is configured as USB_SOF_OUT */
635 PORT_SetPinMux(BOARD_USB_SOF_OUT_PORT, BOARD_USB_SOF_OUT_PIN, kPORT_MuxAlt4);
636
637 PORTC->PCR[0] = ((PORTC->PCR[0] &
638 /* Mask bits to zero which are setting */
639 (~(PORT_PCR_PS_MASK | PORT_PCR_PE_MASK | PORT_PCR_SRE_MASK | PORT_PCR_ISF_MASK)))
640
641 /* Pull Select: Internal pullup resistor is enabled on the corresponding pin, if the
642 * corresponding PE field is set. */
643 | PORT_PCR_PS(kPORT_PullUp)
644
645 /* Pull Enable: Internal pullup or pulldown resistor is not enabled on the corresponding pin. */
646 | PORT_PCR_PE(kPORT_PullDisable)
647
648 /* Slew Rate Enable: Fast slew rate is configured on the corresponding pin, if the pin is
649 * configured as a digital output. */
650 | PORT_PCR_SRE(kPORT_FastSlewRate));
651}
652
653/* clang-format off */
654/*
655 * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
656BOARD_InitACCEL_I2CPins:
657- options: {prefix: BOARD_, coreID: core0, enableClock: 'true'}
658- pin_list:
659 - {pin_num: '20', peripheral: I2C0, signal: SCL, pin_signal: PTE24/TPM0_CH0/I2C0_SCL, slew_rate: fast, pull_select: up, pull_enable: enable}
660 - {pin_num: '21', peripheral: I2C0, signal: SDA, pin_signal: PTE25/TPM0_CH1/I2C0_SDA, slew_rate: fast, pull_select: up, pull_enable: enable}
661 - {pin_num: '58', peripheral: GPIOD, signal: 'GPIO, 1', pin_signal: LCD_P41/ADC0_SE5b/PTD1/SPI0_SCK/TPM0_CH1/FXIO0_D1, identifier: INT2_ACCEL, direction: INPUT,
662 slew_rate: fast, pull_select: up, pull_enable: disable}
663 - {pin_num: '54', peripheral: GPIOC, signal: 'GPIO, 5', pin_signal: LCD_P25/PTC5/LLWU_P9/SPI0_SCK/LPTMR0_ALT2/CMP0_OUT, direction: INPUT, slew_rate: fast, pull_select: up,
664 pull_enable: disable}
665 * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
666 */
667/* clang-format on */
668
669/* FUNCTION ************************************************************************************************************
670 *
671 * Function Name : BOARD_InitACCEL_I2CPins
672 * Description : Configures pin routing and optionally pin electrical features.
673 *
674 * END ****************************************************************************************************************/
675void BOARD_InitACCEL_I2CPins(void)
676{
677 /* Port C Clock Gate Control: Clock enabled */
678 CLOCK_EnableClock(kCLOCK_PortC);
679 /* Port D Clock Gate Control: Clock enabled */
680 CLOCK_EnableClock(kCLOCK_PortD);
681 /* Port E Clock Gate Control: Clock enabled */
682 CLOCK_EnableClock(kCLOCK_PortE);
683
684 gpio_pin_config_t INT1_ACCEL_config = {
685 .pinDirection = kGPIO_DigitalInput,
686 .outputLogic = 0U
687 };
688 /* Initialize GPIO functionality on pin PTC5 (pin 54) */
689 GPIO_PinInit(BOARD_INT1_ACCEL_GPIO, BOARD_INT1_ACCEL_PIN, &INT1_ACCEL_config);
690
691 gpio_pin_config_t INT2_ACCEL_config = {
692 .pinDirection = kGPIO_DigitalInput,
693 .outputLogic = 0U
694 };
695 /* Initialize GPIO functionality on pin PTD1 (pin 58) */
696 GPIO_PinInit(BOARD_INT2_ACCEL_GPIO, BOARD_INT2_ACCEL_PIN, &INT2_ACCEL_config);
697
698 /* PORTC5 (pin 54) is configured as PTC5 */
699 PORT_SetPinMux(BOARD_INT1_ACCEL_PORT, BOARD_INT1_ACCEL_PIN, kPORT_MuxAsGpio);
700
701 PORTC->PCR[5] = ((PORTC->PCR[5] &
702 /* Mask bits to zero which are setting */
703 (~(PORT_PCR_PS_MASK | PORT_PCR_PE_MASK | PORT_PCR_SRE_MASK | PORT_PCR_ISF_MASK)))
704
705 /* Pull Select: Internal pullup resistor is enabled on the corresponding pin, if the
706 * corresponding PE field is set. */
707 | PORT_PCR_PS(kPORT_PullUp)
708
709 /* Pull Enable: Internal pullup or pulldown resistor is not enabled on the corresponding pin. */
710 | PORT_PCR_PE(kPORT_PullDisable)
711
712 /* Slew Rate Enable: Fast slew rate is configured on the corresponding pin, if the pin is
713 * configured as a digital output. */
714 | PORT_PCR_SRE(kPORT_FastSlewRate));
715
716 /* PORTD1 (pin 58) is configured as PTD1 */
717 PORT_SetPinMux(BOARD_INT2_ACCEL_PORT, BOARD_INT2_ACCEL_PIN, kPORT_MuxAsGpio);
718
719 PORTD->PCR[1] = ((PORTD->PCR[1] &
720 /* Mask bits to zero which are setting */
721 (~(PORT_PCR_PS_MASK | PORT_PCR_PE_MASK | PORT_PCR_SRE_MASK | PORT_PCR_ISF_MASK)))
722
723 /* Pull Select: Internal pullup resistor is enabled on the corresponding pin, if the
724 * corresponding PE field is set. */
725 | PORT_PCR_PS(kPORT_PullUp)
726
727 /* Pull Enable: Internal pullup or pulldown resistor is not enabled on the corresponding pin. */
728 | PORT_PCR_PE(kPORT_PullDisable)
729
730 /* Slew Rate Enable: Fast slew rate is configured on the corresponding pin, if the pin is
731 * configured as a digital output. */
732 | PORT_PCR_SRE(kPORT_FastSlewRate));
733
734 const port_pin_config_t I2C0_SCL = {/* Internal pull-up resistor is enabled */
735 kPORT_PullUp,
736 /* Fast slew rate is configured */
737 kPORT_FastSlewRate,
738 /* Passive filter is disabled */
739 kPORT_PassiveFilterDisable,
740 /* Low drive strength is configured */
741 kPORT_LowDriveStrength,
742 /* Pin is configured as I2C0_SCL */
743 kPORT_MuxAlt5};
744 /* PORTE24 (pin 20) is configured as I2C0_SCL */
745 PORT_SetPinConfig(BOARD_I2C0_SCL_PORT, BOARD_I2C0_SCL_PIN, &I2C0_SCL);
746
747 const port_pin_config_t I2C0_SDA = {/* Internal pull-up resistor is enabled */
748 kPORT_PullUp,
749 /* Fast slew rate is configured */
750 kPORT_FastSlewRate,
751 /* Passive filter is disabled */
752 kPORT_PassiveFilterDisable,
753 /* Low drive strength is configured */
754 kPORT_LowDriveStrength,
755 /* Pin is configured as I2C0_SDA */
756 kPORT_MuxAlt5};
757 /* PORTE25 (pin 21) is configured as I2C0_SDA */
758 PORT_SetPinConfig(BOARD_I2C0_SDA_PORT, BOARD_I2C0_SDA_PIN, &I2C0_SDA);
759}
760
761/* clang-format off */
762/*
763 * TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
764BOARD_InitOSCPins:
765- options: {prefix: BOARD_, coreID: core0, enableClock: 'true'}
766- pin_list:
767 - {pin_num: '32', peripheral: OSC0, signal: EXTAL0, pin_signal: EXTAL0/PTA18/LPUART1_RX/TPM_CLKIN0, slew_rate: no_init, pull_select: no_init, pull_enable: no_init}
768 - {pin_num: '33', peripheral: OSC0, signal: XTAL0, pin_signal: XTAL0/PTA19/LPUART1_TX/TPM_CLKIN1/LPTMR0_ALT1, slew_rate: no_init, pull_select: no_init, pull_enable: no_init}
769 * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS ***********
770 */
771/* clang-format on */
772
773/* FUNCTION ************************************************************************************************************
774 *
775 * Function Name : BOARD_InitOSCPins
776 * Description : Configures pin routing and optionally pin electrical features.
777 *
778 * END ****************************************************************************************************************/
779void BOARD_InitOSCPins(void)
780{
781 /* Port A Clock Gate Control: Clock enabled */
782 CLOCK_EnableClock(kCLOCK_PortA);
783
784 /* PORTA18 (pin 32) is configured as EXTAL0 */
785 PORT_SetPinMux(BOARD_EXTAL_32KHZ_PORT, BOARD_EXTAL_32KHZ_PIN, kPORT_PinDisabledOrAnalog);
786
787 /* PORTA19 (pin 33) is configured as XTAL0 */
788 PORT_SetPinMux(BOARD_XTAL_32KHZ_PORT, BOARD_XTAL_32KHZ_PIN, kPORT_PinDisabledOrAnalog);
789}
790/***********************************************************************************************************************
791 * EOF
792 **********************************************************************************************************************/
diff --git a/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/pin_mux.h b/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/pin_mux.h
new file mode 100644
index 000000000..bdbf301f1
--- /dev/null
+++ b/lib/chibios-contrib/ext/mcux-sdk/devices/K32L2B11A/project_template/pin_mux.h
@@ -0,0 +1,271 @@
1/*
2 * Copyright 2019 NXP
3 * All rights reserved.
4 *
5 * SPDX-License-Identifier: BSD-3-Clause
6 */
7
8/***********************************************************************************************************************
9 * This file was generated by the MCUXpresso Config Tools. Any manual edits made to this file
10 * will be overwritten if the respective MCUXpresso Config Tools is used to update this file.
11 **********************************************************************************************************************/
12
13#ifndef _PIN_MUX_H_
14#define _PIN_MUX_H_
15
16/*!
17 * @addtogroup pin_mux
18 * @{
19 */
20
21/***********************************************************************************************************************
22 * API
23 **********************************************************************************************************************/
24
25#if defined(__cplusplus)
26extern "C" {
27#endif
28
29/*!
30 * @brief Calls initialization functions.
31 *
32 */
33void BOARD_InitBootPins(void);
34
35/*!
36 * @brief Configures pin routing and optionally pin electrical features.
37 *
38 */
39void BOARD_InitPins(void);
40
41/*! @name PORTB18 (number 41), J1[1]/LCD_P14
42 @{ */
43#define BOARD_LCD_P14_PORT PORTB /*!<@brief PORT device name: PORTB */
44#define BOARD_LCD_P14_PIN 18U /*!<@brief PORTB pin index: 18 */
45 /* @} */
46
47/*! @name PORTB19 (number 42), J1[3]/LCD_P15
48 @{ */
49#define BOARD_LCD_P15_PORT PORTB /*!<@brief PORT device name: PORTB */
50#define BOARD_LCD_P15_PIN 19U /*!<@brief PORTB pin index: 19 */
51 /* @} */
52
53/*! @name PORTC0 (number 43), J1[5]/LCD_P20/USB_SOF_OUT
54 @{ */
55#define BOARD_LCD_P20_PORT PORTC /*!<@brief PORT device name: PORTC */
56#define BOARD_LCD_P20_PIN 0U /*!<@brief PORTC pin index: 0 */
57 /* @} */
58
59/*! @name PORTC4 (number 53), J1[7]/LCD_P24
60 @{ */
61#define BOARD_LCD_P24_PORT PORTC /*!<@brief PORT device name: PORTC */
62#define BOARD_LCD_P24_PIN 4U /*!<@brief PORTC pin index: 4 */
63 /* @} */
64
65/*! @name PORTC6 (number 55), J1[9]/LCD_P26
66 @{ */
67#define BOARD_LCD_P26_PORT PORTC /*!<@brief PORT device name: PORTC */
68#define BOARD_LCD_P26_PIN 6U /*!<@brief PORTC pin index: 6 */
69 /* @} */
70
71/*! @name PORTC7 (number 56), J1[11]/USB_SOF_OUT/LCD_P27
72 @{ */
73#define BOARD_LCD_P27_PORT PORTC /*!<@brief PORT device name: PORTC */
74#define BOARD_LCD_P27_PIN 7U /*!<@brief PORTC pin index: 7 */
75 /* @} */
76
77/*! @name PORTD0 (number 57), LCD-09_P40
78 @{ */
79#define BOARD_LCD_P40_PORT PORTD /*!<@brief PORT device name: PORTD */
80#define BOARD_LCD_P40_PIN 0U /*!<@brief PORTD pin index: 0 */
81 /* @} */
82
83/*! @name PORTD2 (number 59), J2[4]/D9/LCD_P42
84 @{ */
85#define BOARD_LCD_P42_PORT PORTD /*!<@brief PORT device name: PORTD */
86#define BOARD_LCD_P42_PIN 2U /*!<@brief PORTD pin index: 2 */
87 /* @} */
88
89/*! @name PORTD3 (number 60), J1[6]/D2/LCD_P43
90 @{ */
91#define BOARD_LCD_P43_PORT PORTD /*!<@brief PORT device name: PORTD */
92#define BOARD_LCD_P43_PIN 3U /*!<@brief PORTD pin index: 3 */
93 /* @} */
94
95/*! @name PORTD4 (number 61), J2[6]/D10/SPI1_PCS0/LCD_P44
96 @{ */
97#define BOARD_LCD_P44_PORT PORTD /*!<@brief PORT device name: PORTD */
98#define BOARD_LCD_P44_PIN 4U /*!<@brief PORTD pin index: 4 */
99 /* @} */
100
101/*! @name PORTE20 (number 9), J4[1]/DIFF_ADC0_DP/LCD_P59
102 @{ */
103#define BOARD_LCD_P59_PORT PORTE /*!<@brief PORT device name: PORTE */
104#define BOARD_LCD_P59_PIN 20U /*!<@brief PORTE pin index: 20 */
105 /* @} */
106
107/*! @name PORTE21 (number 10), J4[3]/DIFF_ADC0_DM/LCD_P60
108 @{ */
109#define BOARD_LCD_P60_PORT PORTE /*!<@brief PORT device name: PORTE */
110#define BOARD_LCD_P60_PIN 21U /*!<@brief PORTE pin index: 21 */
111 /* @} */
112
113/*!
114 * @brief Configures pin routing and optionally pin electrical features.
115 *
116 */
117void BOARD_InitLCDPins(void);
118
119/*! @name PORTA4 (number 26), J1[10]/D4/SW1
120 @{ */
121#define BOARD_SW1_GPIO GPIOA /*!<@brief GPIO device name: GPIOA */
122#define BOARD_SW1_PORT PORTA /*!<@brief PORT device name: PORTA */
123#define BOARD_SW1_PIN 4U /*!<@brief PORTA pin index: 4 */
124 /* @} */
125
126/*! @name PORTC3 (number 46), SW3/LLWU_P7/LCD_P23
127 @{ */
128#define BOARD_SW3_GPIO GPIOC /*!<@brief GPIO device name: GPIOC */
129#define BOARD_SW3_PORT PORTC /*!<@brief PORT device name: PORTC */
130#define BOARD_SW3_PIN 3U /*!<@brief PORTC pin index: 3 */
131 /* @} */
132
133/*!
134 * @brief Configures pin routing and optionally pin electrical features.
135 *
136 */
137void BOARD_InitBUTTONSPins(void);
138
139/*! @name PORTE31 (number 19), LED2
140 @{ */
141#define BOARD_LED2_GPIO GPIOE /*!<@brief GPIO device name: GPIOE */
142#define BOARD_LED2_PORT PORTE /*!<@brief PORT device name: PORTE */
143#define BOARD_LED2_PIN 31U /*!<@brief PORTE pin index: 31 */
144 /* @} */
145
146/*! @name PORTD5 (number 62), J2[12]/D13/SPI1_SCK/LED1/LCD_P45
147 @{ */
148#define BOARD_LED1_GPIO GPIOD /*!<@brief GPIO device name: GPIOD */
149#define BOARD_LED1_PORT PORTD /*!<@brief PORT device name: PORTD */
150#define BOARD_LED1_PIN 5U /*!<@brief PORTD pin index: 5 */
151 /* @} */
152
153/*!
154 * @brief Configures pin routing and optionally pin electrical features.
155 *
156 */
157void BOARD_InitLEDsPins(void);
158
159#define SOPT5_LPUART0RXSRC_LPUART_RX 0x00u /*!<@brief LPUART0 Receive Data Source Select: LPUART_RX pin */
160#define SOPT5_LPUART0TXSRC_LPUART_TX 0x00u /*!<@brief LPUART0 Transmit Data Source Select: LPUART0_TX pin */
161
162/*! @name PORTA1 (number 23), J1[2]/D0/UART0_RX
163 @{ */
164#define BOARD_DEBUG_UART0_RX_PORT PORTA /*!<@brief PORT device name: PORTA */
165#define BOARD_DEBUG_UART0_RX_PIN 1U /*!<@brief PORTA pin index: 1 */
166 /* @} */
167
168/*! @name PORTA2 (number 24), J1[4]/D1/UART0_TX
169 @{ */
170#define BOARD_DEBUG_UART0_TX_PORT PORTA /*!<@brief PORT device name: PORTA */
171#define BOARD_DEBUG_UART0_TX_PIN 2U /*!<@brief PORTA pin index: 2 */
172 /* @} */
173
174/*!
175 * @brief Configures pin routing and optionally pin electrical features.
176 *
177 */
178void BOARD_InitDEBUG_UARTPins(void);
179
180/*! @name USB0_DP (number 5), J10[3]/USB_DP
181 @{ */
182/* @} */
183
184/*! @name USB0_DM (number 6), J10[2]/USB_DM
185 @{ */
186/* @} */
187
188/*! @name VREGIN (number 8), USB_REGIN
189 @{ */
190/* @} */
191
192/*! @name PORTC0 (number 43), J1[5]/LCD_P20/USB_SOF_OUT
193 @{ */
194#define BOARD_USB_SOF_OUT_PORT PORTC /*!<@brief PORT device name: PORTC */
195#define BOARD_USB_SOF_OUT_PIN 0U /*!<@brief PORTC pin index: 0 */
196 /* @} */
197
198/*! @name PORTA5 (number 27), J1[12]/D5/USB_CLKIN
199 @{ */
200#define BOARD_USB0_CLKIN_PORT PORTA /*!<@brief PORT device name: PORTA */
201#define BOARD_USB0_CLKIN_PIN 5U /*!<@brief PORTA pin index: 5 */
202 /* @} */
203
204/*!
205 * @brief Configures pin routing and optionally pin electrical features.
206 *
207 */
208void BOARD_InitUSBPins(void);
209
210/*! @name PORTE24 (number 20), U2[7]/U10[4]/I2C0_SCL
211 @{ */
212#define BOARD_I2C0_SCL_PORT PORTE /*!<@brief PORT device name: PORTE */
213#define BOARD_I2C0_SCL_PIN 24U /*!<@brief PORTE pin index: 24 */
214 /* @} */
215
216/*! @name PORTE25 (number 21), U2[6]/U10[6]/I2C0_SDA
217 @{ */
218#define BOARD_I2C0_SDA_PORT PORTE /*!<@brief PORT device name: PORTE */
219#define BOARD_I2C0_SDA_PIN 25U /*!<@brief PORTE pin index: 25 */
220 /* @} */
221
222/*! @name PORTD1 (number 58), U2[9]/U10[9]/INT2_ACCEL/INT1_MAG/LCD_P41
223 @{ */
224#define BOARD_INT2_ACCEL_GPIO GPIOD /*!<@brief GPIO device name: GPIOD */
225#define BOARD_INT2_ACCEL_PORT PORTD /*!<@brief PORT device name: PORTD */
226#define BOARD_INT2_ACCEL_PIN 1U /*!<@brief PORTD pin index: 1 */
227 /* @} */
228
229/*! @name PORTC5 (number 54), J1[15]/INT1_ACCEL/LCD_P25
230 @{ */
231#define BOARD_INT1_ACCEL_GPIO GPIOC /*!<@brief GPIO device name: GPIOC */
232#define BOARD_INT1_ACCEL_PORT PORTC /*!<@brief PORT device name: PORTC */
233#define BOARD_INT1_ACCEL_PIN 5U /*!<@brief PORTC pin index: 5 */
234 /* @} */
235
236/*!
237 * @brief Configures pin routing and optionally pin electrical features.
238 *
239 */
240void BOARD_InitACCEL_I2CPins(void);
241
242/*! @name PORTA18 (number 32), EXTAL_32KHZ
243 @{ */
244#define BOARD_EXTAL_32KHZ_PORT PORTA /*!<@brief PORT device name: PORTA */
245#define BOARD_EXTAL_32KHZ_PIN 18U /*!<@brief PORTA pin index: 18 */
246 /* @} */
247
248/*! @name PORTA19 (number 33), XTAL_32KHZ
249 @{ */
250#define BOARD_XTAL_32KHZ_PORT PORTA /*!<@brief PORT device name: PORTA */
251#define BOARD_XTAL_32KHZ_PIN 19U /*!<@brief PORTA pin index: 19 */
252 /* @} */
253
254/*!
255 * @brief Configures pin routing and optionally pin electrical features.
256 *
257 */
258void BOARD_InitOSCPins(void);
259
260#if defined(__cplusplus)
261}
262#endif
263
264/*!
265 * @}
266 */
267#endif /* _PIN_MUX_H_ */
268
269/***********************************************************************************************************************
270 * EOF
271 **********************************************************************************************************************/