summaryrefslogtreecommitdiff
path: root/board/src
diff options
context:
space:
mode:
Diffstat (limited to 'board/src')
-rw-r--r--board/src/board.c60
-rw-r--r--board/src/clock_config.c229
-rw-r--r--board/src/pin_mux.c219
3 files changed, 508 insertions, 0 deletions
diff --git a/board/src/board.c b/board/src/board.c
new file mode 100644
index 0000000..ba853ad
--- /dev/null
+++ b/board/src/board.c
@@ -0,0 +1,60 @@
+/*
+ * Copyright (c) 2013 - 2016, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of Freescale Semiconductor, Inc. nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
+ * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
+ * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/* This is a template for board specific configuration created by New Kinetis SDK 2.x Project Wizard. Enjoy! */
+
+#include <stdint.h>
+#include "board.h"
+#include "fsl_debug_console.h"
+
+/*!
+ * @brief initialize debug console to enable printf for this demo/example
+ */
+void BOARD_InitDebugConsole(void) {
+ uint32_t uartClkSrcFreq = BOARD_DEBUG_UART_CLK_FREQ;
+
+#ifdef USE_SWO
+ uint32_t SWOSpeed = 1000000; /* default 64k baud rate */
+ uint32_t SWOPrescaler = (uartClkSrcFreq / SWOSpeed) - 1; /* SWOSpeed in Hz, note that cpuCoreFreqHz is expected to be match the CPU core clock */
+ CoreDebug->DEMCR = CoreDebug_DEMCR_TRCENA_Msk; /* enable trace in core debug */
+ *((volatile unsigned *)(ITM_BASE + 0x400F0)) = 0x00000002; /* "Selected PIN Protocol Register": Select which protocol to use for trace output (2: SWO NRZ, 1: SWO Manchester encoding) */
+ *((volatile unsigned *)(ITM_BASE + 0x40010)) = SWOPrescaler; /* "Async Clock Prescaler Register". Scale the baud rate of the asynchronous output */
+ *((volatile unsigned *)(ITM_BASE + 0x00FB0)) = 0xC5ACCE55; /* ITM Lock Access Register, C5ACCE55 enables more write access to Control Register 0xE00 :: 0xFFC */
+ ITM->TCR = ITM_TCR_TraceBusID_Msk | ITM_TCR_SWOENA_Msk | ITM_TCR_SYNCENA_Msk | ITM_TCR_ITMENA_Msk; /* ITM Trace Control Register */
+ ITM->TPR = ITM_TPR_PRIVMASK_Msk; /* ITM Trace Privilege Register */
+ ITM->TER = 0x01; /* ITM Trace Enable Register. Enabled tracing on stimulus ports. One bit per stimulus port. */
+ *((volatile unsigned *)(ITM_BASE + 0x01000)) = 0x400003FE; /* DWT_CTRL */
+ *((volatile unsigned *)(ITM_BASE + 0x40304)) = 0x00000100; /* Formatter and Flush Control Register */
+
+#endif
+
+DbgConsole_Init(BOARD_DEBUG_UART_BASEADDR, BOARD_DEBUG_UART_BAUDRATE, BOARD_DEBUG_UART_TYPE, uartClkSrcFreq);
+}
+
diff --git a/board/src/clock_config.c b/board/src/clock_config.c
new file mode 100644
index 0000000..4da9ef5
--- /dev/null
+++ b/board/src/clock_config.c
@@ -0,0 +1,229 @@
+/*
+ * Copyright (c) 2013 - 2016, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of Freescale Semiconductor, Inc. nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
+ * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
+ * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/* This is a template for clock configuration created by New Kinetis SDK 2.x Project Wizard. Enjoy! */
+
+#include "fsl_device_registers.h"
+#include "fsl_common.h"
+#include "fsl_clock.h"
+#include "fsl_port.h"
+#include "clock_config.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+
+#define MCG_IRCLK_DISABLE 0U /*!< MCGIRCLK disabled */
+#define MCG_PLL_DISABLE 0U /*!< MCGPLLCLK disabled */
+#define OSC_CAP0P 0U /*!< Oscillator 0pF capacitor load */
+#define OSC_ER_CLK_DISABLE 0U /*!< Disable external reference clock */
+#define SIM_OSC32KSEL_OSC32KCLK_CLK 0U /*!< OSC32KSEL select: OSC32KCLK clock */
+#define SIM_PLLFLLSEL_MCGFLLCLK_CLK 0U /*!< PLLFLL select: MCGFLLCLK clock */
+#define SIM_PLLFLLSEL_MCGPLLCLK_CLK 1U /*!< PLLFLL select: MCGPLLCLK clock */
+#define BOARD_BOOTCLOCKRUN_CORE_CLOCK 100000000U /*!< Core clock frequency: 100000000Hz */
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+/* System clock frequency. */
+extern uint32_t SystemCoreClock;
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+/*FUNCTION**********************************************************************
+ *
+ * Function Name : CLOCK_CONFIG_SetFllExtRefDiv
+ * Description : Configure FLL external reference divider (FRDIV).
+ * Param frdiv : The value to set FRDIV.
+ *
+ *END**************************************************************************/
+static void CLOCK_CONFIG_SetFllExtRefDiv(uint8_t frdiv)
+{
+ MCG->C1 = ((MCG->C1 & ~MCG_C1_FRDIV_MASK) | MCG_C1_FRDIV(frdiv));
+}
+
+/*******************************************************************************
+ ************************ BOARD_InitBootClocks function ************************
+ ******************************************************************************/
+void BOARD_InitBootClocks(void)
+{
+ BOARD_BootClockRUN();
+}
+
+/*******************************************************************************
+ ********************** Configuration BOARD_BootClockRUN ***********************
+ ******************************************************************************/
+/* TEXT BELOW IS USED AS SETTING FOR TOOLS *************************************
+!!Configuration
+name: BOARD_BootClockRUN
+called_from_default_init: true
+outputs:
+- {id: Bus_clock.outFreq, value: 50 MHz}
+- {id: Core_clock.outFreq, value: 100 MHz, locked: true, accuracy: '0.001'}
+- {id: Flash_clock.outFreq, value: 25 MHz}
+- {id: FlexBus_clock.outFreq, value: 50 MHz}
+- {id: LPO_clock.outFreq, value: 1 kHz}
+- {id: MCGFFCLK.outFreq, value: 250 kHz}
+- {id: System_clock.outFreq, value: 100 MHz}
+settings:
+- {id: MCGMode, value: PEE}
+- {id: MCG.FRDIV.scale, value: '32'}
+- {id: MCG.IREFS.sel, value: MCG.FRDIV}
+- {id: MCG.PLLS.sel, value: MCG.PLL}
+- {id: MCG.PRDIV.scale, value: '2'}
+- {id: MCG.VDIV.scale, value: '25'}
+- {id: MCG_C2_OSC_MODE_CFG, value: ModeOscLowPower}
+- {id: MCG_C2_RANGE0_CFG, value: Very_high}
+- {id: MCG_C2_RANGE0_FRDIV_CFG, value: Very_high}
+- {id: SIM.OUTDIV2.scale, value: '2'}
+- {id: SIM.OUTDIV3.scale, value: '2'}
+- {id: SIM.OUTDIV4.scale, value: '4'}
+sources:
+- {id: OSC.OSC.outFreq, value: 8 MHz, enabled: true}
+ * BE CAREFUL MODIFYING THIS COMMENT - IT IS YAML SETTINGS FOR TOOLS **********/
+
+/*******************************************************************************
+ * Variables for BOARD_BootClockRUN configuration
+ ******************************************************************************/
+const mcg_config_t mcgConfig_BOARD_BootClockRUN =
+ {
+ .mcgMode = kMCG_ModePEE, /* PEE - PLL Engaged External */
+ .irclkEnableMode = MCG_IRCLK_DISABLE, /* MCGIRCLK disabled */
+ .ircs = kMCG_IrcSlow, /* Slow internal reference clock selected */
+ .fcrdiv = 0x1U, /* Fast IRC divider: divided by 2 */
+ .frdiv = 0x0U, /* FLL reference clock divider: divided by 32 */
+ .drs = kMCG_DrsLow, /* Low frequency range */
+ .dmx32 = kMCG_Dmx32Default, /* DCO has a default range of 25% */
+ .oscsel = kMCG_OscselOsc, /* Selects System Oscillator (OSCCLK) */
+ .pll0Config =
+ {
+ .enableMode = MCG_PLL_DISABLE, /* MCGPLLCLK disabled */
+ .prdiv = 0x1U, /* PLL Reference divider: divided by 2 */
+ .vdiv = 0x1U, /* VCO divider: multiplied by 25 */
+ },
+ };
+const sim_clock_config_t simConfig_BOARD_BootClockRUN =
+ {
+ .pllFllSel = SIM_PLLFLLSEL_MCGPLLCLK_CLK, /* PLLFLL select: MCGPLLCLK clock */
+ .er32kSrc = SIM_OSC32KSEL_OSC32KCLK_CLK, /* OSC32KSEL select: OSC32KCLK clock */
+ .clkdiv1 = 0x01130000U, /* SIM_CLKDIV1 - OUTDIV1: /1, OUTDIV2: /2, OUTDIV3: /2, OUTDIV4: /4 */
+ };
+const osc_config_t oscConfig_BOARD_BootClockRUN =
+ {
+ .freq = 8000000U, /* Oscillator frequency: 8000000Hz */
+ .capLoad = (OSC_CAP0P), /* Oscillator capacity load: 0pF */
+ .workMode = kOSC_ModeOscLowPower, /* Oscillator low power */
+ .oscerConfig =
+ {
+ .enableMode = OSC_ER_CLK_DISABLE, /* Disable external reference clock */
+ }
+ };
+
+
+/*******************************************************************************
+ * Code for BOARD_BootClockRUN configuration
+ ******************************************************************************/
+void BOARD_BootClockRUN(void)
+{
+ /* Set the system clock dividers in SIM to safe value. */
+ CLOCK_SetSimSafeDivs();
+ /* Initializes OSC0 according to board configuration. */
+ CLOCK_InitOsc0(&oscConfig_BOARD_BootClockRUN);
+ CLOCK_SetXtal0Freq(oscConfig_BOARD_BootClockRUN.freq);
+ /* Configure FLL external reference divider (FRDIV). */
+ CLOCK_CONFIG_SetFllExtRefDiv(mcgConfig_BOARD_BootClockRUN.frdiv);
+ /* Set MCG to PEE mode. */
+ CLOCK_BootToPeeMode(mcgConfig_BOARD_BootClockRUN.oscsel,
+ kMCG_PllClkSelPll0,
+ &mcgConfig_BOARD_BootClockRUN.pll0Config);
+ /* Set the clock configuration in SIM module. */
+ CLOCK_SetSimConfig(&simConfig_BOARD_BootClockRUN);
+ /* Set SystemCoreClock variable. */
+ SystemCoreClock = BOARD_BOOTCLOCKRUN_CORE_CLOCK;
+}
+
+#if 0
+void BOARD_InitOsc0(void)
+{
+ const osc_config_t oscConfig = {.freq = BOARD_XTAL0_CLK_HZ,
+ .capLoad = 0,
+ .workMode = kOSC_ModeOscLowPower,
+ .oscerConfig = {
+ .enableMode = kOSC_ErClkEnable,
+#if (defined(FSL_FEATURE_OSC_HAS_EXT_REF_CLOCK_DIVIDER) && FSL_FEATURE_OSC_HAS_EXT_REF_CLOCK_DIVIDER)
+ .erclkDiv = 0U,
+#endif
+ }};
+
+ CLOCK_InitOsc0(&oscConfig);
+
+ /* Passing the XTAL0 frequency to clock driver. */
+ CLOCK_SetXtal0Freq(BOARD_XTAL0_CLK_HZ);
+ /* Use RTC_CLKIN input clock directly. */
+ //CLOCK_SetXtal32Freq(BOARD_XTAL32K_CLK_HZ);
+}
+
+void BOARD_BootClockRUN(void)
+{
+ /*
+ * Core clock: 100MHz
+ * Bus clock: 50MHz
+ */
+ mcg_pll_config_t pll0Config = {
+ .enableMode = 0U, .prdiv = 0x3U, .vdiv = 0x18U,
+ };
+ const sim_clock_config_t simConfig = {
+ .pllFllSel = 1U, /* PLLFLLSEL select PLL. */
+ .er32kSrc = 2U, /* ERCLK32K selection, use RTC. */
+ .clkdiv1 = 0x01130000U, /* SIM_CLKDIV1. */
+ };
+
+ CLOCK_SetSimSafeDivs();
+ BOARD_InitOsc0();
+
+ CLOCK_CalcPllDiv(BOARD_XTAL0_CLK_HZ, 100000000U, &pll0Config.prdiv, &pll0Config.vdiv);
+ CLOCK_BootToPeeMode(kMCG_OscselOsc, kMCG_PllClkSelPll0, &pll0Config);
+
+ CLOCK_SetInternalRefClkConfig(kMCG_IrclkEnable, kMCG_IrcSlow, 0);
+ CLOCK_SetSimConfig(&simConfig);
+
+ SystemCoreClock = 100000000U;
+}
+#endif
+
diff --git a/board/src/pin_mux.c b/board/src/pin_mux.c
new file mode 100644
index 0000000..f7e1e94
--- /dev/null
+++ b/board/src/pin_mux.c
@@ -0,0 +1,219 @@
+/*
+ * Copyright (c) 2013 - 2016, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of Freescale Semiconductor, Inc. nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
+ * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
+ * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/* This is a template file for pins configuration created by New Kinetis SDK 2.x Project Wizard. Enjoy! */
+
+#include "fsl_device_registers.h"
+#include "fsl_common.h"
+#include "fsl_port.h"
+#include "fsl_gpio.h"
+#include "fsl_debug_console.h"
+#include "gpio_ext.h"
+
+const struct gpio_id gpio_list[] = {
+#ifndef USE_SWO
+ {PORTA, GPIOA, 3},
+#endif
+ {PORTA, GPIOA, 5},
+#ifdef TESTER_BUILD
+ {PORTA, GPIOA, 12},
+ {PORTA, GPIOA, 13},
+#endif
+ {PORTA, GPIOA, 17},
+#ifndef BOARD_USES_ADC
+ {PORTB, GPIOB, 0},
+ {PORTB, GPIOB, 1},
+ {PORTB, GPIOB, 2},
+ {PORTB, GPIOB, 3},
+#endif
+ {PORTB, GPIOB, 10},
+ {PORTB, GPIOB, 11},
+ {PORTB, GPIOB, 16},
+ {PORTB, GPIOB, 17},
+ {PORTB, GPIOB, 18},
+ {PORTB, GPIOB, 19},
+ {PORTC, GPIOC, 0},
+ {PORTC, GPIOC, 1},
+ {PORTC, GPIOC, 2},
+ {PORTC, GPIOC, 3},
+ {PORTC, GPIOC, 4},
+ {PORTC, GPIOC, 6},
+ {PORTC, GPIOC, 7},
+#ifdef TESTER_BUILD
+ {PORTC, GPIOC, 16},
+ {PORTC, GPIOC, 17},
+#endif
+ {PORTD, GPIOD, 0},
+ {PORTD, GPIOD, 1},
+ {PORTD, GPIOD, 2},
+ {PORTD, GPIOD, 3},
+ {PORTD, GPIOD, 4},
+ {PORTD, GPIOD, 5},
+ {PORTD, GPIOD, 6},
+ {PORTD, GPIOD, 7},
+ {PORTD, GPIOD, 8},
+ {PORTD, GPIOD, 9},
+ {PORTD, GPIOD, 11},
+ {PORTD, GPIOD, 12},
+ {PORTD, GPIOD, 13},
+ {PORTD, GPIOD, 14},
+ {PORTD, GPIOD, 15},
+#if !defined(SDK_DEBUGCONSOLE) || defined(TESTER_BUILD)
+ {PORTE, GPIOE, 0},
+ {PORTE, GPIOE, 1},
+#endif
+ {PORTE, GPIOE, 2},
+ {PORTE, GPIOE, 3},
+ {PORTE, GPIOE, 4},
+ {PORTE, GPIOE, 5},
+ {PORTE, GPIOE, 24},
+ {PORTE, GPIOE, 25}
+};
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+/*!
+ * @brief Initialize all pins used in this example
+ */
+void BOARD_InitPins(void)
+{
+ unsigned int i;
+ gpio_pin_config_t gpio_out_config = {
+ kGPIO_DigitalOutput, 0,
+ };
+ gpio_pin_config_t gpio_out_hi_config = {
+ kGPIO_DigitalOutput, 1,
+ };
+ gpio_pin_config_t gpio_in_config = {
+ kGPIO_DigitalInput,
+ };
+ port_pin_config_t od_config;
+ port_pin_config_t can_tx_config;
+ port_pin_config_t in_config;
+
+ CLOCK_EnableClock(kCLOCK_PortA);
+ CLOCK_EnableClock(kCLOCK_PortB);
+ CLOCK_EnableClock(kCLOCK_PortC);
+ CLOCK_EnableClock(kCLOCK_PortD);
+ CLOCK_EnableClock(kCLOCK_PortE);
+
+ /* Osc pins */
+ PORT_SetPinMux(PORTA, 18UL, kPORT_PinDisabledOrAnalog);
+ PORT_SetPinMux(PORTA, 19UL, kPORT_PinDisabledOrAnalog);
+#ifndef TESTER_BUILD
+
+ can_tx_config.mux = kPORT_MuxAlt2;
+ can_tx_config.openDrainEnable = kPORT_OpenDrainDisable;
+ can_tx_config.pullSelect = kPORT_PullUp;
+ can_tx_config.slewRate = kPORT_FastSlewRate;
+ can_tx_config.passiveFilterEnable = kPORT_PassiveFilterDisable;
+ can_tx_config.driveStrength = kPORT_LowDriveStrength;
+ can_tx_config.lockRegister = kPORT_UnlockRegister;
+
+ /* CAN0 pinmux config */
+ PORT_SetPinConfig(PORTA, 12u, &can_tx_config); /* CAN0 TX */
+ PORT_SetPinMux(PORTA, 13u, kPORT_MuxAlt2); /* CAN0 RX */
+
+ /* CAN1 pinmux config */
+ PORT_SetPinConfig(PORTC, 17u, &can_tx_config); /* CAN1 TX */
+ PORT_SetPinMux(PORTC, 16u, kPORT_MuxAlt2); /* CAN1 RX */
+
+#ifdef SDK_DEBUGCONSOLE
+ /* Debug UART3 pinmux config */
+ PORT_SetPinMux(PORTE, 0u, kPORT_MuxAlt3); /* UART1 TX */
+ PORT_SetPinMux(PORTE, 1u, kPORT_MuxAlt3); /* UART1 RX */
+#endif
+#endif
+
+#ifdef BOARD_USES_ADC
+ /* Resistive Touch panel pinmux config */
+ PORT_SetPinMux(PORTE, 6u, kPORT_MuxAsGpio);
+ GPIO_PinInit(GPIOE, 6u, &gpio_out_hi_config); /* Force X+*/
+ PORT_SetPinMux(PORTB, 9u, kPORT_MuxAsGpio);
+ GPIO_PinInit(GPIOB, 9u, &gpio_out_config); /* Force X-*/
+ PORT_SetPinMux(PORTC, 5u, kPORT_MuxAsGpio);
+ GPIO_PinInit(GPIOC, 5u, &gpio_out_hi_config); /* Force Y+*/
+ PORT_SetPinMux(PORTC, 13u, kPORT_MuxAsGpio);
+ GPIO_PinInit(GPIOC, 13u, &gpio_out_config); /* Force Y-*/
+ PORT_SetPinMux(PORTB, 6UL, kPORT_PinDisabledOrAnalog); /* Sense X+ */
+ GPIO_PinInit(GPIOB, 6u, &gpio_in_config);
+ PORT_SetPinMux(PORTB, 7UL, kPORT_PinDisabledOrAnalog); /* Sense X- */
+ GPIO_PinInit(GPIOB, 7u, &gpio_in_config);
+ PORT_SetPinMux(PORTC, 8UL, kPORT_PinDisabledOrAnalog); /* Sense Y+ */
+ GPIO_PinInit(GPIOC, 8u, &gpio_in_config);
+ PORT_SetPinMux(PORTC, 9UL, kPORT_PinDisabledOrAnalog); /* Sense Y- */
+ GPIO_PinInit(GPIOC, 9u, &gpio_in_config);
+
+ /* Apalis ADC pinmux config */
+ PORT_SetPinMux(PORTB, 0UL, kPORT_PinDisabledOrAnalog); /* ADC0 */
+ PORT_SetPinMux(PORTB, 1UL, kPORT_PinDisabledOrAnalog); /* ADC1 */
+ PORT_SetPinMux(PORTB, 2UL, kPORT_PinDisabledOrAnalog); /* ADC2 */
+ PORT_SetPinMux(PORTB, 3UL, kPORT_PinDisabledOrAnalog); /* ADC3 */
+#endif
+ /* SPI2 pinmux config */
+ PORT_SetPinMux(PORTB, 21u, kPORT_MuxAlt2); /* SPI2_SCK */
+ PORT_SetPinMux(PORTB, 22u, kPORT_MuxAlt2); /* SPI2_SOUT */
+ PORT_SetPinMux(PORTB, 23u, kPORT_MuxAlt2); /* SPI2_SIN */
+ PORT_SetPinMux(PORTB, 20u, kPORT_MuxAlt2); /* SPI2_SS */
+
+ /* Open Drain INT pins config */
+ od_config.mux = kPORT_MuxAsGpio;
+ od_config.openDrainEnable = kPORT_OpenDrainEnable;
+ od_config.pullSelect = kPORT_PullDisable;
+ od_config.slewRate = kPORT_FastSlewRate;
+ od_config.passiveFilterEnable = kPORT_PassiveFilterDisable;
+ od_config.driveStrength = kPORT_LowDriveStrength;
+ od_config.lockRegister = kPORT_UnlockRegister;
+ GPIO_PinInit(GPIOA, 16u, &gpio_out_hi_config);
+ PORT_SetPinConfig(PORTA, 16u, &od_config); /* MCU_INT1 */
+ GPIO_PinInit(GPIOA, 29u, &gpio_out_hi_config);
+ PORT_SetPinConfig(PORTA, 29u, &od_config); /* MCU_INT2 */
+ GPIO_PinInit(GPIOB, 8u, &gpio_out_config);
+ PORT_SetPinConfig(PORTB, 8u, &od_config); /* MCU_INT3 */
+ GPIO_PinInit(GPIOE, 26u, &gpio_out_config);
+ PORT_SetPinConfig(PORTE, 26u, &od_config); /* MCU_INT4 */
+ GPIO_PinInit(GPIOC, 19u, &gpio_out_hi_config);
+ PORT_SetPinConfig(PORTC, 19u, &od_config); /* PMIC_ONKEY */
+
+ /* GPIOs */
+ in_config.mux = kPORT_MuxAsGpio;
+ in_config.openDrainEnable = kPORT_OpenDrainDisable;
+ in_config.pullSelect = kPORT_PullDown;
+ in_config.slewRate = kPORT_FastSlewRate;
+ in_config.passiveFilterEnable = kPORT_PassiveFilterDisable;
+ in_config.driveStrength = kPORT_LowDriveStrength;
+ in_config.lockRegister = kPORT_UnlockRegister;
+ for (i = 0; i < sizeof(gpio_list)/sizeof(struct gpio_id); i++){
+ PORT_SetPinConfig(gpio_list[i].port, gpio_list[i].pin, &in_config);
+ GPIO_PinInit(gpio_list[i].gpio, gpio_list[i].pin, &gpio_in_config);
+ }
+
+}