diff options
author | David Barksdale <amatus@amatus.name> | 2015-09-27 13:36:12 -0500 |
---|---|---|
committer | David Barksdale <amatus@amatus.name> | 2015-09-27 13:36:12 -0500 |
commit | 950abe7cda833ab7e753dbd5c0a8f8cb8bf0f469 (patch) | |
tree | bd9a79e64eb66b63a056aece20b633e660885953 | |
parent | f0668e8033f3858c520d98bd787f951c3f9fb0fd (diff) |
Added hello world
-rwxr-xr-x | laser-tag software/CMakeLists.txt | 134 | ||||
-rw-r--r-- | laser-tag software/README | 17 | ||||
-rwxr-xr-x | laser-tag software/board.c | 175 | ||||
-rwxr-xr-x | laser-tag software/board.h | 220 | ||||
-rwxr-xr-x | laser-tag software/build_all.sh | 5 | ||||
-rwxr-xr-x | laser-tag software/build_debug.sh | 3 | ||||
-rwxr-xr-x | laser-tag software/build_release.sh | 3 | ||||
-rwxr-xr-x | laser-tag software/clean.sh | 3 | ||||
-rwxr-xr-x | laser-tag software/fsl_lptmr_irq.c | 47 | ||||
-rwxr-xr-x | laser-tag software/gpio_pins.c | 113 | ||||
-rwxr-xr-x | laser-tag software/gpio_pins.h | 103 | ||||
-rwxr-xr-x | laser-tag software/hardware_init.c | 57 | ||||
-rw-r--r-- | laser-tag software/howto build | 20 | ||||
-rwxr-xr-x | laser-tag software/main.c | 119 | ||||
-rwxr-xr-x | laser-tag software/pin_mux.c | 284 | ||||
-rwxr-xr-x | laser-tag software/pin_mux.h | 272 |
16 files changed, 1555 insertions, 20 deletions
diff --git a/laser-tag software/CMakeLists.txt b/laser-tag software/CMakeLists.txt new file mode 100755 index 0000000..5cfd2f9 --- /dev/null +++ b/laser-tag software/CMakeLists.txt @@ -0,0 +1,134 @@ +INCLUDE(CMakeForceCompiler)
+
+# CROSS COMPILER SETTING
+SET(CMAKE_SYSTEM_NAME Generic)
+CMAKE_MINIMUM_REQUIRED (VERSION 2.6)
+
+# THE VERSION NUMBER
+SET (Tutorial_VERSION_MAJOR 1)
+SET (Tutorial_VERSION_MINOR 0)
+
+# ENABLE ASM
+ENABLE_LANGUAGE(ASM)
+
+SET(CMAKE_STATIC_LIBRARY_PREFIX)
+SET(CMAKE_STATIC_LIBRARY_SUFFIX)
+
+SET(CMAKE_EXECUTABLE_LIBRARY_PREFIX)
+SET(CMAKE_EXECUTABLE_LIBRARY_SUFFIX)
+
+
+# CURRENT DIRECTORY
+SET(ProjDirPath ${CMAKE_CURRENT_SOURCE_DIR})
+
+# DEBUG LINK FILE
+set(CMAKE_EXE_LINKER_FLAGS_DEBUG "${CMAKE_EXE_LINKER_FLAGS_DEBUG} -T../KSDK_1.2.0/platform/devices/MKL27Z4/linker/gcc/MKL27Z256xxx4_flash.ld -static")
+
+# RELEASE LINK FILE
+set(CMAKE_EXE_LINKER_FLAGS_RELEASE "${CMAKE_EXE_LINKER_FLAGS_RELEASE} -T../KSDK_1.2.0/platform/devices/MKL27Z4/linker/gcc/MKL27Z256xxx4_flash.ld -static")
+
+# DEBUG ASM FLAGS
+SET(CMAKE_ASM_FLAGS_DEBUG "${CMAKE_ASM_FLAGS_DEBUG} -g -mcpu=cortex-m0plus -mthumb -Wall -fno-common -ffunction-sections -fdata-sections -ffreestanding -fno-builtin -Os -mapcs -std=gnu99")
+
+# DEBUG C FLAGS
+SET(CMAKE_C_FLAGS_DEBUG "${CMAKE_C_FLAGS_DEBUG} -g -mcpu=cortex-m0plus -mthumb -MMD -MP -Wall -fno-common -ffunction-sections -fdata-sections -ffreestanding -fno-builtin -Os -mapcs -std=gnu99")
+
+# DEBUG LD FLAGS
+SET(CMAKE_EXE_LINKER_FLAGS_DEBUG "${CMAKE_EXE_LINKER_FLAGS_DEBUG} -g --specs=nano.specs -lm -Wall -fno-common -ffunction-sections -fdata-sections -ffreestanding -fno-builtin -Os -mthumb -mapcs -Xlinker --gc-sections -Xlinker -static -Xlinker -z -Xlinker muldefs -Xlinker --defsym=__stack_size__=0x300 -Xlinker --defsym=__heap_size__=0x200")
+
+# RELEASE ASM FLAGS
+SET(CMAKE_ASM_FLAGS_RELEASE "${CMAKE_ASM_FLAGS_RELEASE} -mcpu=cortex-m0plus -mthumb -Wall -fno-common -ffunction-sections -fdata-sections -ffreestanding -fno-builtin -Os -mapcs -std=gnu99")
+
+# RELEASE C FLAGS
+SET(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -mcpu=cortex-m0plus -mthumb -MMD -MP -Wall -fno-common -ffunction-sections -fdata-sections -ffreestanding -fno-builtin -Os -mapcs -std=gnu99")
+
+# RELEASE LD FLAGS
+SET(CMAKE_EXE_LINKER_FLAGS_RELEASE "${CMAKE_EXE_LINKER_FLAGS_RELEASE} --specs=nano.specs -lm -Wall -fno-common -ffunction-sections -fdata-sections -ffreestanding -fno-builtin -Os -mthumb -mapcs -Xlinker --gc-sections -Xlinker -static -Xlinker -z -Xlinker muldefs -Xlinker --defsym=__stack_size__=0x300 -Xlinker --defsym=__heap_size__=0x200")
+
+# ASM MACRO
+SET(CMAKE_ASM_FLAGS_DEBUG "${CMAKE_ASM_FLAGS_DEBUG} -DDEBUG")
+
+# C MACRO
+SET(CMAKE_C_FLAGS_DEBUG "${CMAKE_C_FLAGS_DEBUG} -DDEBUG")
+SET(CMAKE_C_FLAGS_DEBUG "${CMAKE_C_FLAGS_DEBUG} -DCPU_MKL27Z256VLH4")
+SET(CMAKE_C_FLAGS_DEBUG "${CMAKE_C_FLAGS_DEBUG} -DFRDM_KL27Z")
+SET(CMAKE_C_FLAGS_DEBUG "${CMAKE_C_FLAGS_DEBUG} -DFREEDOM")
+SET(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -DNDEBUG")
+SET(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -DCPU_MKL27Z256VLH4")
+SET(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -DFRDM_KL27Z")
+SET(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -DFREEDOM")
+
+# CXX MACRO
+
+# INCLUDE_DIRECTORIES
+IF(CMAKE_BUILD_TYPE MATCHES Debug)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/osa/inc)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/utilities/inc)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/CMSIS/Include)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/devices)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/devices/MKL27Z4/include)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/devices/MKL27Z4/startup)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/hal/inc)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/drivers/inc)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/system/inc)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/utilities/inc)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/.)
+ELSEIF(CMAKE_BUILD_TYPE MATCHES Release)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/osa/inc)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/utilities/inc)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/CMSIS/Include)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/devices)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/devices/MKL27Z4/include)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/devices/MKL27Z4/startup)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/hal/inc)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/drivers/inc)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/system/inc)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../KSDK_1.2.0/platform/utilities/inc)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/.)
+ENDIF()
+
+# ADD_EXECUTABLE
+ADD_EXECUTABLE(hello_world
+ "${ProjDirPath}/../KSDK_1.2.0/platform/utilities/src/fsl_misc_utilities.c"
+ "${ProjDirPath}/../KSDK_1.2.0/platform/devices/MKL27Z4/startup/gcc/startup_MKL27Z4.S"
+ "${ProjDirPath}/../KSDK_1.2.0/platform/utilities/src/fsl_debug_console.c"
+ "${ProjDirPath}/../KSDK_1.2.0/platform/utilities/inc/fsl_debug_console.h"
+ "${ProjDirPath}/../KSDK_1.2.0/platform/utilities/src/print_scan.c"
+ "${ProjDirPath}/../KSDK_1.2.0/platform/utilities/src/print_scan.h"
+ "${ProjDirPath}/../KSDK_1.2.0/platform/devices/MKL27Z4/startup/system_MKL27Z4.c"
+ "${ProjDirPath}/../KSDK_1.2.0/platform/devices/startup.c"
+ "${ProjDirPath}/../KSDK_1.2.0/platform/devices/startup.h"
+ "${ProjDirPath}/gpio_pins.c"
+ "${ProjDirPath}/gpio_pins.h"
+ "${ProjDirPath}/pin_mux.c"
+ "${ProjDirPath}/pin_mux.h"
+ "${ProjDirPath}/board.c"
+ "${ProjDirPath}/board.h"
+ "${ProjDirPath}/hardware_init.c"
+ "${ProjDirPath}/main.c"
+ "${ProjDirPath}/fsl_lptmr_irq.c"
+)
+SET_TARGET_PROPERTIES(hello_world PROPERTIES OUTPUT_NAME "hello_world.elf")
+
+TARGET_LINK_LIBRARIES(hello_world -Wl,--start-group)
+# LIBRARIES
+IF(CMAKE_BUILD_TYPE MATCHES Debug)
+ TARGET_LINK_LIBRARIES(hello_world ${ProjDirPath}/../KSDK_1.2.0/lib/ksdk_platform_lib/armgcc/KL27Z4/debug/libksdk_platform.a)
+ELSEIF(CMAKE_BUILD_TYPE MATCHES Release)
+ TARGET_LINK_LIBRARIES(hello_world ${ProjDirPath}/../KSDK_1.2.0/lib/ksdk_platform_lib/armgcc/KL27Z4/release/libksdk_platform.a)
+ENDIF()
+
+# SYSTEM LIBRARIES
+TARGET_LINK_LIBRARIES(hello_world m)
+TARGET_LINK_LIBRARIES(hello_world c)
+TARGET_LINK_LIBRARIES(hello_world gcc)
+TARGET_LINK_LIBRARIES(hello_world nosys)
+TARGET_LINK_LIBRARIES(hello_world -Wl,--end-group)
+
+# MAP FILE
+SET(CMAKE_EXE_LINKER_FLAGS_DEBUG "${CMAKE_EXE_LINKER_FLAGS_DEBUG} -Xlinker -Map=debug/hello_world.map")
+SET(CMAKE_EXE_LINKER_FLAGS_RELEASE "${CMAKE_EXE_LINKER_FLAGS_RELEASE} -Xlinker -Map=release/hello_world.map")
+
+# BIN AND HEX
+ADD_CUSTOM_COMMAND(TARGET hello_world POST_BUILD COMMAND ${CMAKE_OBJCOPY} -Oihex ${EXECUTABLE_OUTPUT_PATH}/hello_world.elf ${EXECUTABLE_OUTPUT_PATH}/hello_world.hex)
+ADD_CUSTOM_COMMAND(TARGET hello_world POST_BUILD COMMAND ${CMAKE_OBJCOPY} -Obinary ${EXECUTABLE_OUTPUT_PATH}/hello_world.elf ${EXECUTABLE_OUTPUT_PATH}/hello_world.bin)
diff --git a/laser-tag software/README b/laser-tag software/README new file mode 100644 index 0000000..a0ebe43 --- /dev/null +++ b/laser-tag software/README @@ -0,0 +1,17 @@ +Build instructions for Ubuntu: +0) apt-get install cmake gcc-arm-none-eabi +1) export ARMGCC_DIR=/usr + cd KSDK_1.2.0/lib/ksdk_platform_lib/armgcc/KL27Z4 + ./build_debug.sh +2) cd "laser-tag software" + ./build_debug.sh + +Load instructions: +0) openocd + in another terminal: + telnet localhost 4444 + reset halt +1) in another terminal: + gdb-multiarch -x gdb.init debug/hello_world.elf + gdb) load + gdb) monitor reset diff --git a/laser-tag software/board.c b/laser-tag software/board.c new file mode 100755 index 0000000..703d447 --- /dev/null +++ b/laser-tag software/board.c @@ -0,0 +1,175 @@ +/* + * Copyright (c) 2013-2014, 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. + */ + +#include "board.h" +#include "fsl_clock_manager.h" +#include "fsl_smc_hal.h" +#include "fsl_debug_console.h" +#include "pin_mux.h" + +/* Configuration for enter VLPR mode. Core clock = 2MHz. */ +const clock_manager_user_config_t g_defaultClockConfigVlpr = +{ + .mcgliteConfig = + { + .mcglite_mode = kMcgliteModeLirc8M, // Work in LIRC_8M mode. + .irclkEnable = true, // MCGIRCLK enable. + .irclkEnableInStop = false, // MCGIRCLK disable in STOP mode. + .ircs = kMcgliteLircSel2M, // Select LIRC_2M. + .fcrdiv = kMcgliteLircDivBy1, // FCRDIV is 0. + .lircDiv2 = kMcgliteLircDivBy1, // LIRC_DIV2 is 0. + .hircEnableInNotHircMode = false, // HIRC disable. + }, + .simConfig = + { + .er32kSrc = kClockEr32kSrcOsc0, // ERCLK32K selection, use OSC. + .outdiv1 = 0U, + .outdiv4 = 1U, + }, + .oscerConfig = + { + .enable = false, // OSCERCLK disable. + .enableInStop = false, // OSCERCLK disable in STOP mode. + } +}; + +/* Configuration for enter RUN mode. Core clock = 48MHz. */ +const clock_manager_user_config_t g_defaultClockConfigRun = +{ + .mcgliteConfig = + { + .mcglite_mode = kMcgliteModeHirc48M, // Work in HIRC mode. + .irclkEnable = false, // MCGIRCLK disable. + .irclkEnableInStop = false, // MCGIRCLK disable in STOP mode. + .ircs = kMcgliteLircSel2M, // Select LIRC_2M. + .fcrdiv = kMcgliteLircDivBy1, // FCRDIV is 0. + .lircDiv2 = kMcgliteLircDivBy1, // LIRC_DIV2 is 0. + .hircEnableInNotHircMode = true, // HIRC disable. + }, + .simConfig = + { + .er32kSrc = kClockEr32kSrcOsc0, // ERCLK32K selection, use OSC. + .outdiv1 = 0U, + .outdiv4 = 1U, + }, + .oscerConfig = + { + .enable = false, // OSCERCLK disable. + .enableInStop = false, // OSCERCLK disable in STOP mode. + } +}; + +/* Function to initialize OSC0 base on board configuration. */ +void BOARD_InitOsc0(void) +{ + // OSC0 configuration. + osc_user_config_t osc0Config = + { + .freq = OSC0_XTAL_FREQ, + .hgo = MCG_HGO0, + .range = MCG_RANGE0, + .erefs = MCG_EREFS0, + .enableCapacitor2p = OSC0_SC2P_ENABLE_CONFIG, + .enableCapacitor4p = OSC0_SC4P_ENABLE_CONFIG, + .enableCapacitor8p = OSC0_SC8P_ENABLE_CONFIG, + .enableCapacitor16p = OSC0_SC16P_ENABLE_CONFIG, + }; + + CLOCK_SYS_OscInit(0U, &osc0Config); +} + +/* Function to initialize RTC external clock base on board configuration. */ +void BOARD_InitRtcOsc(void) +{ +#if ((OSC0_XTAL_FREQ != 32768U) && (RTC_OSC_ENABLE_CONFIG)) +#error Set RTC_OSC_ENABLE_CONFIG will override OSC0 configuration and OSC0 must be 32k. +#endif + rtc_osc_user_config_t rtcOscConfig = + { + .freq = RTC_XTAL_FREQ, + .enableCapacitor2p = RTC_SC2P_ENABLE_CONFIG, + .enableCapacitor4p = RTC_SC4P_ENABLE_CONFIG, + .enableCapacitor8p = RTC_SC8P_ENABLE_CONFIG, + .enableCapacitor16p = RTC_SC16P_ENABLE_CONFIG, + .enableOsc = RTC_OSC_ENABLE_CONFIG, + .enableClockOutput = RTC_CLK_OUTPUT_ENABLE_CONFIG, + }; + + CLOCK_SYS_RtcOscInit(0U, &rtcOscConfig); +} + +/* Initialize clock. */ +void BOARD_ClockInit(void) +{ + /* Set allowed power mode, allow all. */ + SMC_HAL_SetProtection(SMC, kAllowPowerModeAll); + + /* Setup board clock source. */ + // Setup OSC0 if used. + // Configure OSC0 pin mux. + PORT_HAL_SetMuxMode(EXTAL0_PORT, EXTAL0_PIN, EXTAL0_PINMUX); + PORT_HAL_SetMuxMode(XTAL0_PORT, XTAL0_PIN, XTAL0_PINMUX); + BOARD_InitOsc0(); + + // Setup RTC external clock if used. +#if RTC_XTAL_FREQ + // If RTC_CLKIN is connected, need to set pin mux. Another way for + // RTC clock is set RTC_OSC_ENABLE_CONFIG to use OSC0, please check + // reference manual for datails. + PORT_HAL_SetMuxMode(RTC_CLKIN_PORT, RTC_CLKIN_PIN, RTC_CLKIN_PINMUX); +#endif + BOARD_InitRtcOsc(); + + /* Set system clock configuration. */ +#if (CLOCK_INIT_CONFIG == CLOCK_VLPR) + CLOCK_SYS_SetConfiguration(&g_defaultClockConfigVlpr); +#else + CLOCK_SYS_SetConfiguration(&g_defaultClockConfigRun); +#endif +} + +void dbg_uart_init(void) +{ + configure_lpuart_pins(BOARD_DEBUG_UART_INSTANCE); + +#if (CLOCK_INIT_CONFIG == CLOCK_VLPR) + CLOCK_SYS_SetLpuartSrc(BOARD_DEBUG_UART_INSTANCE, kClockLpuartSrcMcgIrClk); +#else + CLOCK_SYS_SetLpuartSrc(BOARD_DEBUG_UART_INSTANCE, kClockLpuartSrcIrc48M); +#endif + + DbgConsole_Init(BOARD_DEBUG_UART_INSTANCE, BOARD_DEBUG_UART_BAUD, kDebugConsoleLPUART); +} + +/******************************************************************************* + * EOF + ******************************************************************************/ + + diff --git a/laser-tag software/board.h b/laser-tag software/board.h new file mode 100755 index 0000000..d3e0b27 --- /dev/null +++ b/laser-tag software/board.h @@ -0,0 +1,220 @@ +/* + * Copyright (c) 2013 - 2014, 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. + */ + +#if !defined(__BOARD_H__) +#define __BOARD_H__ + +#include <stdint.h> +#include "pin_mux.h" +#include "gpio_pins.h" + +/* The board name */ +#define BOARD_NAME "FRDM-KL27Z" + +#define CLOCK_VLPR 1U +#define CLOCK_RUN 2U +#define CLOCK_NUMBER_OF_CONFIGURATIONS 3U + +#ifndef CLOCK_INIT_CONFIG +#define CLOCK_INIT_CONFIG CLOCK_RUN +#endif + +/* OSC0 configuration. */ +#define OSC0_XTAL_FREQ 32768U +#define OSC0_SC2P_ENABLE_CONFIG false +#define OSC0_SC4P_ENABLE_CONFIG false +#define OSC0_SC8P_ENABLE_CONFIG false +#define OSC0_SC16P_ENABLE_CONFIG false +#define MCG_HGO0 kOscGainLow +#define MCG_RANGE0 kOscRangeLow +#define MCG_EREFS0 kOscSrcOsc + +/* EXTAL0 PTA18 */ +#define EXTAL0_PORT PORTA +#define EXTAL0_PIN 18 +#define EXTAL0_PINMUX kPortPinDisabled + +/* XTAL0 PTA19 */ +#define XTAL0_PORT PORTA +#define XTAL0_PIN 19 +#define XTAL0_PINMUX kPortPinDisabled + +/* RTC external clock configuration. */ +#define RTC_XTAL_FREQ 0U +#define RTC_SC2P_ENABLE_CONFIG false +#define RTC_SC4P_ENABLE_CONFIG false +#define RTC_SC8P_ENABLE_CONFIG false +#define RTC_SC16P_ENABLE_CONFIG false +#define RTC_OSC_ENABLE_CONFIG false +#define RTC_CLK_OUTPUT_ENABLE_CONFIG false + +/* RTC_CLKIN PTC1 */ +#define RTC_CLKIN_PORT PORTC +#define RTC_CLKIN_PIN 1 +#define RTC_CLKIN_PINMUX kPortMuxAsGpio + +/* The UART to use for debug messages. */ +#ifndef BOARD_DEBUG_UART_INSTANCE + #define BOARD_DEBUG_UART_INSTANCE 0 + #define BOARD_DEBUG_UART_BASEADDR LPUART0 +#endif +#ifndef BOARD_DEBUG_UART_BAUD + #define BOARD_DEBUG_UART_BAUD 115200 +#endif + +/* This define to use for power manager demo */ +#define BOARD_LOW_POWER_UART_BAUD 9600 + +/* Define feature for the low_power_demo */ +#define FSL_FEATURE_HAS_VLLS2 (1) + +/* Define the port interrupt number for the board switches */ +#define BOARD_SW_GPIO kGpioSW3 +#define BOARD_SW_IRQ_NUM PORTBCDE_IRQn +#define BOARD_SW_IRQ_HANDLER PORTBCDE_IRQHandler + +/* Define print statement to inform user which switch to press for + * power_manager_hal_demo and power_manager_rtos_demo + */ +#define PRINT_LLWU_SW_NUM \ + PRINTF("SW3") + + /* Defines the llwu pin number for board switch which is used in power_manager_demo. */ +/* SW3, PTC1, LLWU6 */ +#define BOARD_SW_HAS_LLWU_PIN 1 +#define BOARD_SW_LLWU_EXT_PIN kLlwuWakeupPin6 +/* Switch port base address and IRQ handler name. Used by power_manager_demo */ +#define BOARD_SW_LLWU_PIN 1 +#define BOARD_SW_LLWU_BASE PORTC +#define BOARD_SW_LLWU_IRQ_HANDLER PORTBCDE_IRQHandler +#define BOARD_SW_LLWU_IRQ_NUM PORTBCDE_IRQn + +#define BOARD_USE_LPUART +#define PM_DBG_UART_IRQ_HANDLER MODULE_IRQ_HANDLER(LPUART0) +#define PM_DBG_UART_IRQn LPUART0_IRQn + +#define BOARD_I2C_GPIO_SCL GPIO_MAKE_PIN(GPIOD_IDX, 7) +#define BOARD_I2C_GPIO_SDA GPIO_MAKE_PIN(GPIOD_IDX, 6) + +#define HWADC_INSTANCE 0 +#define ADC_IRQ_N ADC0_IRQn +#if (defined FSL_RTOS_MQX) +#define MQX_ADC_IRQHandler MQX_ADC0_IRQHandler +#endif + +/* The i2c instance used for i2c DAC demo */ +#define BOARD_DAC_I2C_INSTANCE 0 + +/* The i2c instance used for i2c communication demo */ +#define BOARD_I2C_COMM_INSTANCE 1 + +/* The Flextimer instance/channel used for board */ +#define BOARD_FTM_INSTANCE 0 +#define BOARD_FTM_CHANNEL 0 + +#define BOARD_ADC_HW_TRIGGER_CHAN 0 + +/* board led color mapping */ +#define BOARD_GPIO_LED_RED kGpioLED2 +#define BOARD_GPIO_LED_GREEN kGpioLED3 +#define BOARD_GPIO_LED_BLUE kGpioLED1 + +#define TX_DEBUG_CONSOLE_DIS PORT_HAL_SetMuxMode(PORTA, 2, kPortPinDisabled) +#define RX_DEBUG_CONSOLE_DIS PORT_HAL_SetMuxMode(PORTA, 1, kPortPinDisabled) + +#define SW_INT_DIS PORT_HAL_SetPinIntMode(PORTA, 4, kPortIntDisabled) +#define SW_DIS PORT_HAL_SetMuxMode(PORTA, 4, kPortPinDisabled) +#define SW_EN PORT_HAL_SetMuxMode(PORTA, 4, kPortMuxAsGpio) + +#define LED1_EN (GPIO_DRV_OutputPinInit(&ledPins[0])) /*!< Enable target LED1 */ +#define LED2_EN (GPIO_DRV_OutputPinInit(&ledPins[1])) /*!< Enable target LED2 */ +#define LED3_EN (GPIO_DRV_OutputPinInit(&ledPins[2])) /*!< Enable target LED3 */ + +#define LED1_DIS (PORT_HAL_SetMuxMode(PORTA, 13, kPortMuxAsGpio)) /*!< Enable target LED0 */ +#define LED2_DIS (PORT_HAL_SetMuxMode(PORTB, 18, kPortMuxAsGpio)) /*!< Enable target LED1 */ +#define LED3_DIS (PORT_HAL_SetMuxMode(PORTB, 19, kPortMuxAsGpio)) /*!< Enable target LED2 */ + +#define LED1_OFF (GPIO_DRV_WritePinOutput(ledPins[0].pinName, 1)) /*!< Turn off target LED1 */ +#define LED2_OFF (GPIO_DRV_WritePinOutput(ledPins[1].pinName, 1)) /*!< Turn off target LED2 */ +#define LED3_OFF (GPIO_DRV_WritePinOutput(ledPins[2].pinName, 1)) /*!< Turn off target LED3 */ + +#define LED1_ON (GPIO_DRV_WritePinOutput(ledPins[0].pinName, 0)) /*!< Turn on target LED1 */ +#define LED2_ON (GPIO_DRV_WritePinOutput(ledPins[1].pinName, 0)) /*!< Turn on target LED2 */ +#define LED3_ON (GPIO_DRV_WritePinOutput(ledPins[2].pinName, 0)) /*!< Turn on target LED3 */ + +#define LED1_TOGGLE (GPIO_DRV_TogglePinOutput(ledPins[0].pinName)) /*!< Toggle on target LED1 */ +#define LED2_TOGGLE (GPIO_DRV_TogglePinOutput(ledPins[1].pinName)) /*!< Toggle on target LED2 */ +#define LED3_TOGGLE (GPIO_DRV_TogglePinOutput(ledPins[2].pinName)) /*!< Toggle on target LED3 */ + +#define LED_RTOS_EN LED1_EN +#define LED_RTOS_TOGGLE LED1_TOGGLE +#define LED_CLOCK_EN LED2_EN +#define LED_CLOCK_TOGGLE LED2_TOGGLE + +#define OFF_ALL_LEDS \ + LED1_OFF;\ + LED2_OFF;\ + LED3_OFF; + +/* The rtc instance used for rtc_func */ +#define BOARD_RTC_FUNC_INSTANCE 0 + +/* The TPM instance/channel used for board */ +#define BOARD_TPM_INSTANCE 1 +#define BOARD_TPM_CHANNEL 1 + +/* The CMP instance used for board. */ +#define BOARD_CMP_INSTANCE 0 +/* The CMP channel used for board. */ +#define BOARD_CMP_CHANNEL 0 + +#if defined(__cplusplus) +extern "C" { +#endif /* __cplusplus */ + +void hardware_init(void); +void dbg_uart_init(void); +/*This function to used for power manager demo*/ +void disable_unused_pins(void); +void enable_unused_pins(void); +/* Function to initialize clock base on board configuration. */ +void BOARD_ClockInit(void); + +/* Function to initialize OSC0 base on board configuration. */ +void BOARD_InitOsc0(void); + +/* Function to initialize RTC external clock base on board configuration. */ +void BOARD_InitRtcOsc(void); + +#if defined(__cplusplus) +} +#endif /* __cplusplus */ + +#endif /* __BOARD_H__ */ diff --git a/laser-tag software/build_all.sh b/laser-tag software/build_all.sh new file mode 100755 index 0000000..0958334 --- /dev/null +++ b/laser-tag software/build_all.sh @@ -0,0 +1,5 @@ +#!/bin/sh +cmake -DCMAKE_TOOLCHAIN_FILE="../KSDK_1.2.0/tools/cmake_toolchain_files/armgcc.cmake" -G "Unix Makefiles" -DCMAKE_BUILD_TYPE=Debug . +make -j4 +cmake -DCMAKE_TOOLCHAIN_FILE="../KSDK_1.2.0/tools/cmake_toolchain_files/armgcc.cmake" -G "Unix Makefiles" -DCMAKE_BUILD_TYPE=Release . +make -j4 diff --git a/laser-tag software/build_debug.sh b/laser-tag software/build_debug.sh new file mode 100755 index 0000000..fe5c3e6 --- /dev/null +++ b/laser-tag software/build_debug.sh @@ -0,0 +1,3 @@ +#!/bin/sh +cmake -DCMAKE_TOOLCHAIN_FILE="../KSDK_1.2.0/tools/cmake_toolchain_files/armgcc.cmake" -G "Unix Makefiles" -DCMAKE_BUILD_TYPE=Debug . +make -j4 diff --git a/laser-tag software/build_release.sh b/laser-tag software/build_release.sh new file mode 100755 index 0000000..25eea88 --- /dev/null +++ b/laser-tag software/build_release.sh @@ -0,0 +1,3 @@ +#!/bin/sh +cmake -DCMAKE_TOOLCHAIN_FILE="../KSDK_1.2.0/tools/cmake_toolchain_files/armgcc.cmake" -G "Unix Makefiles" -DCMAKE_BUILD_TYPE=Release . +make -j4 diff --git a/laser-tag software/clean.sh b/laser-tag software/clean.sh new file mode 100755 index 0000000..795ad87 --- /dev/null +++ b/laser-tag software/clean.sh @@ -0,0 +1,3 @@ +#!/bin/sh +rm -rf debug release CMakeFiles +rm -rf Makefile cmake_install.cmake CMakeCache.txt diff --git a/laser-tag software/fsl_lptmr_irq.c b/laser-tag software/fsl_lptmr_irq.c new file mode 100755 index 0000000..ccabff1 --- /dev/null +++ b/laser-tag software/fsl_lptmr_irq.c @@ -0,0 +1,47 @@ +/* + * Copyright (c) 2013 -2014, 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. + */ + +#include <stdint.h> +#include <stdbool.h> +#include "fsl_lptmr_driver.h" + +/****************************************************************************** + * Code + *****************************************************************************/ +/* LPTMR IRQ handler that would cover the same name's APIs in startup code */ +void LPTMR0_IRQHandler(void) +{ + LPTMR_DRV_IRQHandler(0U); +} + +/****************************************************************************** + * EOF + *****************************************************************************/ + diff --git a/laser-tag software/gpio_pins.c b/laser-tag software/gpio_pins.c new file mode 100755 index 0000000..29d5d95 --- /dev/null +++ b/laser-tag software/gpio_pins.c @@ -0,0 +1,113 @@ +/* ################################################################### +** This component module is generated by Processor Expert. Do not modify it. +** Filename : gpio_pins.c +** Project : frdmk64f120m-pin +** Processor : MK64FN1M0VMD12 +** Component : fsl_gpio +** Version : Component 01.106, Driver 01.00, CPU db: 3.00.000 +** Compiler : GNU C Compiler +** Date/Time : 2014-06-09, 10:08, # CodeGen: 1 +** +** Copyright : 1997 - 2014 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. +** +** http: www.freescale.com +** mail: support@freescale.com +** ###################################################################*/ +/*! +** @file gpio_pins.c +** @version 01.00 +*/ +/*! +** @addtogroup gpio_pins_module gpio_pins module documentation +** @{ +*/ + +/* MODULE gpio_pins. */ + +#include "gpio_pins.h" +#include <stdbool.h> + +gpio_input_pin_user_config_t switchPins[] = { + { + .pinName = kGpioSW1, + .config.isPullEnable = true, + .config.pullSelect = kPortPullUp, + .config.isPassiveFilterEnabled = false, + .config.interrupt = kPortIntDisabled + }, + { + .pinName = kGpioSW3, + .config.isPullEnable = true, + .config.pullSelect = kPortPullUp, + .config.isPassiveFilterEnabled = false, + .config.interrupt = kPortIntDisabled + }, + { + .pinName = GPIO_PINS_OUT_OF_RANGE, + } +}; + +const gpio_output_pin_user_config_t ledPins[] = { + { + .pinName = kGpioLED1, + .config.outputLogic = 1, + .config.slewRate = kPortSlowSlewRate, + .config.driveStrength = kPortLowDriveStrength, + }, + { + .pinName = kGpioLED2, + .config.outputLogic = 1, + .config.slewRate = kPortSlowSlewRate, + .config.driveStrength = kPortLowDriveStrength, + }, + { + .pinName = kGpioLED3, + .config.outputLogic = 1, + .config.slewRate = kPortSlowSlewRate, + .config.driveStrength = kPortLowDriveStrength, + }, + { + .pinName = GPIO_PINS_OUT_OF_RANGE, + } +}; + + + +/* END gpio_pins. */ +/*! +** @} +*/ +/* +** ################################################################### +** +** This file was created by Processor Expert 10.4 [05.10] +** for the Freescale Kinetis series of microcontrollers. +** +** ################################################################### +*/ diff --git a/laser-tag software/gpio_pins.h b/laser-tag software/gpio_pins.h new file mode 100755 index 0000000..ee2467e --- /dev/null +++ b/laser-tag software/gpio_pins.h @@ -0,0 +1,103 @@ +/* ################################################################### +** This component module is generated by Processor Expert. Do not modify it. +** Filename : gpio_pins.h +** Project : frdmk64f120m-pin +** Processor : MK64FN1M0VMD12 +** Component : fsl_gpio +** Version : Component 01.106, Driver 01.00, CPU db: 3.00.000 +** Compiler : GNU C Compiler +** Date/Time : 2014-06-09, 10:08, # CodeGen: 1 +** Contents : +** GPIO_DRV_Init - void GPIO_DRV_Init(const gpio_input_pin_user_config_t * inputPins,const... +** GPIO_DRV_InputPinInit - void GPIO_DRV_InputPinInit(const gpio_input_pin_user_config_t * inputPin); +** GPIO_DRV_OutputPinInit - void GPIO_DRV_OutputPinInit(const gpio_output_pin_user_config_t * outputPin); +** GPIO_DRV_GetPinDir - gpio_pin_direction_t GPIO_DRV_GetPinDir(uint32_t pinName); +** GPIO_DRV_SetPinDir - void GPIO_DRV_SetPinDir(uint32_t pinName,gpio_pin_direction_t direction); +** GPIO_DRV_WritePinOutput - void GPIO_DRV_WritePinOutput(uint32_t pinName,uint32_t output); +** GPIO_DRV_SetPinOutput - void GPIO_DRV_SetPinOutput(uint32_t pinName); +** GPIO_DRV_ClearPinOutput - void GPIO_DRV_ClearPinOutput(uint32_t pinName); +** GPIO_DRV_TogglePinOutput - void GPIO_DRV_TogglePinOutput(uint32_t pinName); +** GPIO_DRV_ReadPinInput - uint32_t GPIO_DRV_ReadPinInput(uint32_t pinName); +** GPIO_DRV_ClearPinIntFlag - void GPIO_DRV_ClearPinIntFlag(uint32_t pinName); +** +** Copyright : 1997 - 2014 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. +** +** http: www.freescale.com +** mail: support@freescale.com +** ###################################################################*/ +/*! +** @file gpio_pins.h +** @version 01.00 +*/ +/*! +** @addtogroup gpio_pins_module gpio_pins module documentation +** @{ +*/ + +#ifndef __gpio_pins_H +#define __gpio_pins_H + +/* MODULE gpio_pins. */ + +/* Include inherited beans */ +#include "fsl_gpio_driver.h" + + +/*! @brief Configuration structure 0 for input pins */ +extern gpio_input_pin_user_config_t switchPins[]; + +/*! @brief Configuration structure 3 for input pins */ +extern const gpio_input_pin_user_config_t sdhcCdPin[]; + +/*! @brief Configuration structure 0 for output pins */ +extern const gpio_output_pin_user_config_t ledPins[]; + +/*! @brief Pin names */ +enum _gpio_pins_pinNames{ + kGpioSW1 = GPIO_MAKE_PIN(GPIOA_IDX, 4U), + kGpioSW3 = GPIO_MAKE_PIN(GPIOC_IDX, 1U), + kGpioLED1 = GPIO_MAKE_PIN(GPIOA_IDX, 13U), + kGpioLED2 = GPIO_MAKE_PIN(GPIOB_IDX, 18U), + kGpioLED3 = GPIO_MAKE_PIN(GPIOB_IDX, 19U), +}; + + +#endif + +/*! +** @} +*/ +/* +** ################################################################### +** +** This file was created by Processor Expert 10.4 [05.10] +** for the Freescale Kinetis series of microcontrollers. +** +** ################################################################### +*/ diff --git a/laser-tag software/hardware_init.c b/laser-tag software/hardware_init.c new file mode 100755 index 0000000..0c42541 --- /dev/null +++ b/laser-tag software/hardware_init.c @@ -0,0 +1,57 @@ +/* + * Copyright (c) 2013-2014, 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. + */ + +#include "board.h" +#include "pin_mux.h" +#include "fsl_clock_manager.h" +#include "fsl_debug_console.h" + +void hardware_init(void) { + +/* enable clock for PORTs */ + CLOCK_SYS_EnablePortClock(PORTA_IDX); + CLOCK_SYS_EnablePortClock(PORTC_IDX); + + /* Init board clock */ + BOARD_ClockInit(); + dbg_uart_init(); +} + +/*! +** @} +*/ +/* +** ################################################################### +** +** This file was created by Processor Expert 10.4 [05.10] +** for the Freescale Kinetis series of microcontrollers. +** +** ################################################################### +*/ diff --git a/laser-tag software/howto build b/laser-tag software/howto build deleted file mode 100644 index 9ecf74b..0000000 --- a/laser-tag software/howto build +++ /dev/null @@ -1,20 +0,0 @@ -This is how I got hello_world building on my Ubuntu box. -0) apt-get install cmake gcc-arm-none-eabi -1) Download the Freescale KSDK 1.2.0 Mainline for Linux tarball -2) Read KSDK_1.2.0/doc/Getting Started with Kinetis SDK (KSDK) v.1.2.pdf -3) export ARMGCC_DIR=/usr - cd KSDK_1.2.0/lib/ksdk_platform_lib/armgcc/KL27Z4 - ./build_debug.sh -4) cd KSDK_1.2.0/examples/frdmkl27z/demo_apps/hello_world/armgcc - cp CMakeLists.txt CMakeLists.txt.orig - sed -i 's/KL27Z644/KL27Z4/g' CMakeLists.txt - sed -i 's/MKL27Z64/MKL27Z256/g' CMakeLists.txt - ./build_debug.sh -5) openocd - in another terminal: - telnet localhost 4444 - reset halt -6) in another terminal: - gdb-multiarch -x gdb.init path/to/hello_world.elf - gdb) load - gdb) monitor reset diff --git a/laser-tag software/main.c b/laser-tag software/main.c new file mode 100755 index 0000000..0275726 --- /dev/null +++ b/laser-tag software/main.c @@ -0,0 +1,119 @@ +/* + * Copyright (c) 2013 - 2014, 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. + */ + +/////////////////////////////////////////////////////////////////////////////// +// Includes +/////////////////////////////////////////////////////////////////////////////// +// SDK Included Files +#include "board.h" +#include "fsl_lptmr_driver.h" +#include "fsl_debug_console.h" + +//////////////////////////////////////////////////////////////////////////////// +// Definitions +//////////////////////////////////////////////////////////////////////////////// +// Timer period: 500000uS +#define TMR_PERIOD 500000U +#if defined(TWR_KV46F150M) +#define LPTMR0_IDX LPTMR_IDX +#endif + + +const gpio_output_pin_user_config_t lcdBacklight = { + .pinName = GPIO_MAKE_PIN(GPIOE_IDX, 31U), + .config.outputLogic = 1, + .config.slewRate = kPortSlowSlewRate, + .config.driveStrength = kPortLowDriveStrength, +}; + +//////////////////////////////////////////////////////////////////////////////// +// Code +//////////////////////////////////////////////////////////////////////////////// +/*! + * @brief LPTMR interrupt call back function. + * The function is used to toggle LED1. + */ +void lptmr_call_back(void) +{ + // Toggle LED1 + GPIO_DRV_TogglePinOutput(lcdBacklight.pinName); +} + +/*! + * @brief Main function + */ +int main (void) +{ + // RX buffers + //! @param receiveBuff Buffer used to hold received data + uint8_t receiveBuff; + + // LPTMR configurations + lptmr_user_config_t lptmrConfig = + { + .timerMode = kLptmrTimerModeTimeCounter, + .freeRunningEnable = false, + .prescalerEnable = true, + .prescalerClockSource = kClockLptmrSrcLpoClk, + .prescalerValue = kLptmrPrescalerDivide2, + .isInterruptEnabled = true, + }; + // LPTMR driver state information + lptmr_state_t lptmrState; + + // Initialize standard SDK demo application pins + hardware_init(); + + // Initialize LPTMR + LPTMR_DRV_Init(LPTMR0_IDX, &lptmrState, &lptmrConfig); + // Set timer period for TMR_PERIOD seconds + LPTMR_DRV_SetTimerPeriodUs(LPTMR0_IDX, TMR_PERIOD); + // Install interrupt call back function for LPTMR + LPTMR_DRV_InstallCallback(LPTMR0_IDX, lptmr_call_back); + // Start LPTMR + LPTMR_DRV_Start(LPTMR0_IDX); + + // Initialize LED1 + GPIO_DRV_OutputPinInit(&lcdBacklight); + + // Print the initial banner + PRINTF("\r\nHello World!\n\n\r"); + + while(1) + { + // Main routine that simply echoes received characters forever + + // First, get character + receiveBuff = GETCHAR(); + + // Now echo the received character + PUTCHAR(receiveBuff); + } +} diff --git a/laser-tag software/pin_mux.c b/laser-tag software/pin_mux.c new file mode 100755 index 0000000..43655f8 --- /dev/null +++ b/laser-tag software/pin_mux.c @@ -0,0 +1,284 @@ +/* ################################################################### +** This component module is generated by Processor Expert. Do not modify it. +** Filename : pin_mux.c +** Project : frdmk64f120m-pin +** Processor : MK64FN1M0VMD12 +** Component : PinSettings +** Version : Component 01.007, Driver 1.2, CPU db: 3.00.000 +** Compiler : GNU C Compiler +** Date/Time : 2014-06-09, 10:17, # CodeGen: 3 +** Abstract : +** +** Settings : +** +** +** Copyright : 1997 - 2014 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. +** +** http: www.freescale.com +** mail: support@freescale.com +** ###################################################################*/ +/*! +** @file pin_mux.c +** @version 1.2 +** @brief +** +*/ +/*! +** @addtogroup pin_mux_module pin_mux module documentation +** @{ +*/ + +/* MODULE pin_mux. */ + + +#include "fsl_device_registers.h" +#include "fsl_port_hal.h" +#include "fsl_sim_hal.h" +#include "pin_mux.h" + + +void configure_gpio_pins(uint32_t instance) +{ + switch(instance) { + case PORTA_IDX: /* PORTA_IDX */ + /* Affects PORTA_PCR4 register */ + PORT_HAL_SetPassiveFilterCmd(PORTA,4u,false); + PORT_HAL_SetMuxMode(PORTA,4u,kPortMuxAsGpio); + PORT_HAL_SetPullMode(PORTA,4u,kPortPullUp); + PORT_HAL_SetPullCmd(PORTA,4u,true); + + /* Affects PORTA_PCR13 register */ + PORT_HAL_SetDriveStrengthMode(PORTA,13u,kPortLowDriveStrength); + PORT_HAL_SetMuxMode(PORTA,13u,kPortMuxAsGpio); + PORT_HAL_SetSlewRateMode(PORTA,13u,kPortSlowSlewRate); + break; + case PORTB_IDX: /* PORTB_IDX */ + /* Affects PORTB_PCR18 register */ + PORT_HAL_SetDriveStrengthMode(PORTB,18u,kPortLowDriveStrength); + PORT_HAL_SetMuxMode(PORTB,18u,kPortMuxAsGpio); + PORT_HAL_SetSlewRateMode(PORTB,18u,kPortSlowSlewRate); + /* Affects PORTB_PCR19 register */ + PORT_HAL_SetDriveStrengthMode(PORTB,19u,kPortLowDriveStrength); + PORT_HAL_SetMuxMode(PORTB,19u,kPortMuxAsGpio); + PORT_HAL_SetSlewRateMode(PORTB,19u,kPortSlowSlewRate); + break; + case PORTC_IDX: /* PORTC_IDX */ + /* PORTC_PCR1 */ + PORT_HAL_SetMuxMode(PORTC,1u,kPortMuxAsGpio); + + /* Affects PORTC_PCR2 register */ + PORT_HAL_SetPassiveFilterCmd(PORTC,2u,false); + PORT_HAL_SetMuxMode(PORTC,2u,kPortMuxAsGpio); + PORT_HAL_SetPullMode(PORTC,2u,kPortPullUp); + PORT_HAL_SetPullCmd(PORTC,2u,true); + + /* Affects PORTC_PCR3 register */ + PORT_HAL_SetPassiveFilterCmd(PORTC,3u,false); + PORT_HAL_SetMuxMode(PORTC,3u,kPortMuxAsGpio); + PORT_HAL_SetPullMode(PORTC,3u,kPortPullUp); + PORT_HAL_SetPullCmd(PORTC,3u,true); + + break; + case PORTE_IDX: /* PORTE_IDX */ + + break; + default: + break; + } +} + +void configure_i2c_pins(uint32_t instance) +{ + switch(instance) { + case I2C0_IDX: /* I2C0 */ + /* Affects PORTB_PCR0 register */ + PORT_HAL_SetMuxMode(PORTB,0u,kPortMuxAlt2); + /* Affects PORTB_PCR1 register */ + PORT_HAL_SetMuxMode(PORTB,1u,kPortMuxAlt2); + break; + case I2C1_IDX: /* I2C1 */ + /* Affects PORTD_PCR6 register */ + PORT_HAL_SetMuxMode(PORTD,6u,kPortMuxAlt4); + /* Affects PORTD_PCR7 register */ + PORT_HAL_SetMuxMode(PORTD,7u,kPortMuxAlt4); + break; + default: + break; + } +} + +void configure_rtc_pins(uint32_t instance) +{ + /* Affects PORTE_PCR0 register */ + PORT_HAL_SetMuxMode(PORTE,0u,kPortMuxAlt4); +} + +void configure_spi_pins(uint32_t instance) +{ + switch(instance) { + case SPI0_IDX: /* SPI0 */ + /* Affects PORTC_PCR4 register */ + PORT_HAL_SetMuxMode(PORTC,4u,kPortMuxAlt2); + /* Affects PORTC_PCR5 register */ + PORT_HAL_SetMuxMode(PORTC,5u,kPortMuxAlt2); + /* Affects PORTC_PCR6 register */ + PORT_HAL_SetMuxMode(PORTC,6u,kPortMuxAlt2); + /* Affects PORTC_PCR7 register */ + PORT_HAL_SetMuxMode(PORTC,7u,kPortMuxAlt2); + break; + case SPI1_IDX: /* SPI1 */ + /* Affects PORTD_PCR4 register */ + PORT_HAL_SetMuxMode(PORTD,4u,kPortMuxAlt2); + /* Affects PORTD_PCR7 register */ + PORT_HAL_SetMuxMode(PORTD,7u,kPortMuxAlt2); + /* Affects PORTD_PCR5 register */ + PORT_HAL_SetMuxMode(PORTD,5u,kPortMuxAlt2); + /* Affects PORTD_PCR6 register */ + PORT_HAL_SetMuxMode(PORTD,6u,kPortMuxAlt2); + break; + default: + break; + } +} + +void configure_lpuart_pins(uint32_t instance) +{ + switch(instance) { + case 0: /* LPUART0 */ + /* Affects PORTA_PCR1 register */ + PORT_HAL_SetMuxMode(PORTA,1u,kPortMuxAlt2); + /* Affects PORTA_PCR2 register */ + PORT_HAL_SetMuxMode(PORTA,2u,kPortMuxAlt2); + break; + case 1: /* LPUART0 */ + /* Affects PORTA_PCR1 register */ + PORT_HAL_SetMuxMode(PORTE,0u,kPortMuxAlt3); + /* Affects PORTA_PCR2 register */ + PORT_HAL_SetMuxMode(PORTE,1u,kPortMuxAlt3); + break; + default: + break; + } +} + +void configure_gpio_i2c_pins(uint32_t instance) +{ + PORT_HAL_SetMuxMode(PORTD,6u,kPortMuxAsGpio); + PORT_HAL_SetMuxMode(PORTD,7u,kPortMuxAsGpio); +} + +void configure_cmp_pins(uint32_t instance) +{ + PORT_HAL_SetMuxMode(PORTC, 6u, kPortPinDisabled); + PORT_HAL_SetMuxMode(PORTC, 5u, kPortMuxAlt6); +} + + +void config_adc_se0_pins(uint32_t instance) +{ + switch(instance) { + case 0: + PORT_HAL_SetMuxMode(PORTE, 20u, kPortPinDisabled); + break; + default: + break; + } +} + +void configure_tpm_pins(uint32_t instance) +{ + switch(instance) { + case 0: + PORT_HAL_SetMuxMode(PORTA,5u,kPortMuxAlt3); + break; + case 1: + PORT_HAL_SetMuxMode(PORTA,13u,kPortMuxAlt3); /* LED BLUE */ + break; + case 2: + + PORT_HAL_SetMuxMode(PORTB,18u,kPortMuxAlt3); /* LED RED */ + PORT_HAL_SetMuxMode(PORTB,19u,kPortMuxAlt3); /* LED GREEN */ + break; + default: + break; + } +} + +void configure_flexio_pins(uint32_t instance, uint32_t pinIdx) +{ + switch(instance) { + case 0: + switch(pinIdx) + { + case 0: + PORT_HAL_SetMuxMode(PORTD,0u,kPortMuxAlt6); + break; + case 1: + PORT_HAL_SetMuxMode(PORTD,1u,kPortMuxAlt6); + break; + case 2: + PORT_HAL_SetMuxMode(PORTD,2u,kPortMuxAlt6); + break; + case 3: + PORT_HAL_SetMuxMode(PORTD,3u,kPortMuxAlt6); + break; + case 4: + PORT_HAL_SetMuxMode(PORTD,4u,kPortMuxAlt6); + break; + case 5: + PORT_HAL_SetMuxMode(PORTD,5u,kPortMuxAlt6); + break; + case 6: + PORT_HAL_SetMuxMode(PORTD,6u,kPortMuxAlt6); + break; + case 7: + PORT_HAL_SetMuxMode(PORTD,7u,kPortMuxAlt6); + break; + default: + break; + } + + break; + default: + break; + } +} + +/* END pin_mux. */ +/*! +** @} +*/ +/* +** ################################################################### +** +** This file was created by Processor Expert 10.4 [05.10] +** for the Freescale Kinetis series of microcontrollers. +** +** ################################################################### +*/ diff --git a/laser-tag software/pin_mux.h b/laser-tag software/pin_mux.h new file mode 100755 index 0000000..6a4f36e --- /dev/null +++ b/laser-tag software/pin_mux.h @@ -0,0 +1,272 @@ +/* ################################################################### +** This component module is generated by Processor Expert. Do not modify it. +** Filename : pin_mux.h +** Project : frdmk64f120m-pin +** Processor : MK64FN1M0VMD12 +** Component : PinSettings +** Version : Component 01.007, Driver 1.2, CPU db: 3.00.000 +** Compiler : GNU C Compiler +** Date/Time : 2014-06-09, 10:08, # CodeGen: 1 +** Abstract : +** +** Settings : +** +** Contents : +** hardware_init - void hardware_init(void); +** configure_can_pins - void configure_can_pins(uint32_t instance); +** configure_cmp_pins - void configure_cmp_pins(uint32_t instance); +** configure_enet_pins - void configure_enet_pins(uint32_t instance); +** configure_gpio_pins - void configure_gpio_pins(uint32_t instance); +** configure_i2c_pins - void configure_i2c_pins(uint32_t instance); +** configure_i2s_pins - void configure_i2s_pins(uint32_t instance); +** configure_jtag_pins - void configure_jtag_pins(uint32_t instance); +** configure_llwu_pins - void configure_llwu_pins(uint32_t instance); +** configure_rtc_pins - void configure_rtc_pins(uint32_t instance); +** configure_sdhc_pins - void configure_sdhc_pins(uint32_t instance); +** configure_spi_pins - void configure_spi_pins(uint32_t instance); +** configure_tpiu_pins - void configure_tpiu_pins(uint32_t instance); +** configure_uart_pins - void configure_uart_pins(uint32_t instance); +** +** Copyright : 1997 - 2014 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. +** +** http: www.freescale.com +** mail: support@freescale.com +** ###################################################################*/ +/*! +** @file pin_mux.h +** @version 1.2 +** @brief +** +*/ +/*! +** @addtogroup pin_mux_module pin_mux module documentation +** @{ +*/ + +#ifndef pin_mux_H_ +#define pin_mux_H_ + +/* MODULE pin_mux. */ + + +/* +** =================================================================== +** Method : pin_mux_CAN (component PinSettings) +*/ +/*! +** @brief +** CAN method sets registers according routing settings. Call +** this method code to route desired pins into CAN0 periphery. +** @param +** uint32_t instance - CAN instance number (0 is expected) +*/ +/* ===================================================================*/ +void configure_can_pins(uint32_t instance); +/* +** =================================================================== +** Method : pin_mux_CMP (component PinSettings) +*/ +/*! +** @brief +** CMP method sets registers according routing settings. Call +** this method code to route desired pins into: +** CMP0, CMP1, CMP2 +** peripherals. +** @param +** uint32_t instance - CMP instance number 0..2 +*/ +/* ===================================================================*/ +void configure_cmp_pins(uint32_t instance); +/* +** =================================================================== +** Method : pin_mux_DMA (component PinSettings) +*/ +/*! +** @brief +** DMA method sets registers according routing settings. Call +** this method code to route desired pins into DMA periphery. +** @param +** uint32_t instance - DMA instance number (0 is expected) +*/ +/* ===================================================================*/ +void configure_dma_pins(uint32_t instance); +/* +** =================================================================== +** Method : pin_mux_ENET (component PinSettings) +*/ +/*! +** @brief +** ENET method sets registers according routing settings. Call +** this method code to route desired pins into ENET periphery. +** @param +** uint32_t instance - ENET instance number (0 is expected) +*/ +/* ===================================================================*/ +void configure_enet_pins(uint32_t instance); +/* +** =================================================================== +** Method : pin_mux_GPIO (component PinSettings) +*/ +/*! +** @brief +** GPIO method sets registers according routing settings. Call +** this method code to route desired pins into: +** PTA, PTB, PTC, PTD, PTE +** peripherals. +** @param +** uint32_t instance - GPIO instance number 0..4 +*/ +/* ===================================================================*/ +void configure_gpio_pins(uint32_t instance); +/* +** =================================================================== +** Method : pin_mux_I2C (component PinSettings) +*/ +/*! +** @brief +** I2C method sets registers according routing settings. Call +** this method code to route desired pins into: +** I2C0, I2C1, I2C2 +** peripherals. +** @param +** uint32_t instance - I2C instance number 0..2 +*/ +/* ===================================================================*/ +void configure_i2c_pins(uint32_t instance); +/* +** =================================================================== +** Method : pin_mux_I2S (component PinSettings) +*/ +/*! +** @brief +** I2S method sets registers according routing settings. Call +** this method code to route desired pins into I2S0 periphery. +** @param +** uint32_t instance - I2S instance number (0 is expected) +*/ +/* ===================================================================*/ +void configure_i2s_pins(uint32_t instance); +/* +** =================================================================== +** Method : pin_mux_RTC (component PinSettings) +*/ +/*! +** @brief +** RTC method sets registers according routing settings. Call +** this method code to route desired pins into RTC periphery. +** @param +** uint32_t instance - RTC instance number (0 is expected) +*/ +/* ===================================================================*/ +void configure_rtc_pins(uint32_t instance); +/* +** =================================================================== +** Method : pin_mux_SDHC (component PinSettings) +*/ +/*! +** @brief +** SDHC method sets registers according routing settings. Call +** this method code to route desired pins into SDHC periphery. +** @param +** uint32_t instance - SDHC instance number (0 is expected) +*/ +/* ===================================================================*/ +void configure_sdhc_pins(uint32_t instance); +/* +** =================================================================== +** Method : pin_mux_SPI (component PinSettings) +*/ +/*! +** @brief +** SPI method sets registers according routing settings. Call +** this method code to route desired pins into: +** SPI0, SPI1, SPI2 +** peripherals. +** @param +** uint32_t instance - SPI instance number 0..2 +*/ +/* ===================================================================*/ +void configure_spi_pins(uint32_t instance); +/* +** =================================================================== +** Method : pin_mux_TPIU (component PinSettings) +*/ +/*! +** @brief +** TPIU method sets registers according routing settings. Call +** this method code to route desired pins into TPIU periphery. +** @param +** uint32_t instance - TPIU instance number (0 is expected) +*/ +/* ===================================================================*/ +void configure_tpiu_pins(uint32_t instance); +/* +** =================================================================== +** Method : pin_mux_UART (component PinSettings) +*/ +/*! +** @brief +** UART method sets registers according routing settings. Call +** this method code to route desired pins into: +** UART0, UART1, UART2, UART3, UART4, UART5 +** peripherals. +** @param +** uint32_t instance - UART instance number 0..5 +*/ +/* ===================================================================*/ +void configure_lpuart_pins(uint32_t instance); + +void configure_spi_cs0_pins(uint32_t instance); + +void configure_spi_cs1_pins(uint32_t instance); + +void configure_gpio_i2c_pins(uint32_t instance); + +void configure_ftm_pins(uint32_t instance); + +void config_adc_se0_pins(uint32_t instance); + +void configure_tpm_pins(uint32_t instance); + +void configure_flexio_pins(uint32_t instance, uint32_t pinIdx); + + +/* END pin_mux. */ +#endif /* #ifndef __pin_mux_H_ */ +/*! +** @} +*/ +/* +** ################################################################### +** +** This file was created by Processor Expert 10.4 [05.10] +** for the Freescale Kinetis series of microcontrollers. +** +** ################################################################### +*/ |