summaryrefslogtreecommitdiff
path: root/examples/imx7_colibri_m4/demo_apps/sensor_demo
diff options
context:
space:
mode:
Diffstat (limited to 'examples/imx7_colibri_m4/demo_apps/sensor_demo')
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/CMakeLists.txt170
-rwxr-xr-xexamples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_all.bat5
-rwxr-xr-xexamples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_all.sh5
-rwxr-xr-xexamples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_debug.bat3
-rwxr-xr-xexamples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_debug.sh3
-rwxr-xr-xexamples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_release.bat3
-rwxr-xr-xexamples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_release.sh3
-rwxr-xr-xexamples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/clean.bat3
-rwxr-xr-xexamples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/clean.sh3
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/common/fxas21002.c118
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/common/fxas21002.h98
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/common/fxos8700.c158
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/common/fxos8700.h72
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/common/i2c_xfer.c326
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/common/i2c_xfer.h55
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/common/mma8451q.c185
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/common/mma8451q.h113
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/common/mpl3115.c112
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/common/mpl3115.h118
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/ds5/.cproject137
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/ds5/.project86
-rwxr-xr-xexamples/imx7_colibri_m4/demo_apps/sensor_demo/ds5/makedir.bat1
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/ds5/sensor_demo.wsd9
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/hardware_init.c60
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/iar/sensor_demo.ewd9419
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/iar/sensor_demo.ewp1891
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/iar/sensor_demo.eww4
-rw-r--r--examples/imx7_colibri_m4/demo_apps/sensor_demo/sensor_demo_imx7d/main.c237
28 files changed, 13397 insertions, 0 deletions
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/CMakeLists.txt b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/CMakeLists.txt
new file mode 100644
index 0000000..c2ab91e
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/CMakeLists.txt
@@ -0,0 +1,170 @@
+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${ProjDirPath}/../../../../../platform/devices/MCIMX7D/linker/gcc/MCIMX7D_M4_tcm.ld -static")
+
+# RELEASE LINK FILE
+set(CMAKE_EXE_LINKER_FLAGS_RELEASE "${CMAKE_EXE_LINKER_FLAGS_RELEASE} -T${ProjDirPath}/../../../../../platform/devices/MCIMX7D/linker/gcc/MCIMX7D_M4_tcm.ld -static")
+
+# DEBUG ASM FLAGS
+SET(CMAKE_ASM_FLAGS_DEBUG "${CMAKE_ASM_FLAGS_DEBUG} -g -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -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-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -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 -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 --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__=0x400 -Xlinker --defsym=__heap_size__=0x200")
+
+# RELEASE ASM FLAGS
+SET(CMAKE_ASM_FLAGS_RELEASE "${CMAKE_ASM_FLAGS_RELEASE} -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -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-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -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} -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 --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__=0x400 -Xlinker --defsym=__heap_size__=0x200")
+
+# ASM MACRO
+SET(CMAKE_ASM_FLAGS_DEBUG "${CMAKE_ASM_FLAGS_DEBUG} -D__DEBUG")
+
+# C MACRO
+SET(CMAKE_C_FLAGS_DEBUG "${CMAKE_C_FLAGS_DEBUG} -D__DEBUG")
+SET(CMAKE_C_FLAGS_DEBUG "${CMAKE_C_FLAGS_DEBUG} -DCPU_IMX7D_M4")
+SET(CMAKE_C_FLAGS_DEBUG "${CMAKE_C_FLAGS_DEBUG} -DPRINTF_FLOAT_ENABLE")
+SET(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -D__NDEBUG")
+SET(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -DCPU_IMX7D_M4")
+SET(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -DPRINTF_FLOAT_ENABLE")
+
+# CXX MACRO
+
+# INCLUDE_DIRECTORIES
+IF(CMAKE_BUILD_TYPE MATCHES Debug)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../..)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/portable/GCC/ARM_CM4F)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../../../../platform/CMSIS/Include)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../../../../platform/devices)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../../../../platform/devices/MCIMX7D/include)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../../../../platform/devices/MCIMX7D/startup)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../../../../platform/drivers/inc)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/include)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../../../../platform/utilities/inc)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../..)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../common)
+ELSEIF(CMAKE_BUILD_TYPE MATCHES Release)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../..)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/portable/GCC/ARM_CM4F)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../../../../platform/CMSIS/Include)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../../../../platform/devices)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../../../../platform/devices/MCIMX7D/include)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../../../../platform/devices/MCIMX7D/startup)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../../../../platform/drivers/inc)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/include)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../../../../platform/utilities/inc)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../../..)
+ INCLUDE_DIRECTORIES(${ProjDirPath}/../common)
+ENDIF()
+
+# ADD_EXECUTABLE
+ADD_EXECUTABLE(sensor_demo
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/portable/GCC/ARM_CM4F/portmacro.h"
+ "${ProjDirPath}/../../../../../platform/devices/MCIMX7D/startup/gcc/startup_MCIMX7D_M4.S"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/portable/MemMang/heap_2.c"
+ "${ProjDirPath}/../../../FreeRTOSConfig.h"
+ "${ProjDirPath}/../sensor_demo_imx7d/main.c"
+ "${ProjDirPath}/../common/i2c_xfer.c"
+ "${ProjDirPath}/../common/i2c_xfer.h"
+ "${ProjDirPath}/../common/mpl3115.c"
+ "${ProjDirPath}/../common/mpl3115.h"
+ "${ProjDirPath}/../common/fxos8700.c"
+ "${ProjDirPath}/../common/fxos8700.h"
+ "${ProjDirPath}/../common/fxas21002.c"
+ "${ProjDirPath}/../common/fxas21002.h"
+ "${ProjDirPath}/../../../../../platform/drivers/src/i2c_imx.c"
+ "${ProjDirPath}/../../../../../platform/drivers/inc/i2c_imx.h"
+ "${ProjDirPath}/../../../../../platform/drivers/src/uart_imx.c"
+ "${ProjDirPath}/../../../../../platform/drivers/inc/uart_imx.h"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/include/croutine.h"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/include/event_groups.h"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/include/FreeRTOS.h"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/include/list.h"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/include/mpu_wrappers.h"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/include/portable.h"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/include/projdefs.h"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/include/queue.h"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/include/semphr.h"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/include/StackMacros.h"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/include/task.h"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/include/timers.h"
+ "${ProjDirPath}/../../../../../platform/drivers/inc/ccm_analog_imx7d.h"
+ "${ProjDirPath}/../../../../../platform/drivers/inc/ccm_imx7d.h"
+ "${ProjDirPath}/../../../../../platform/drivers/inc/rdc.h"
+ "${ProjDirPath}/../../../../../platform/drivers/inc/rdc_defs_imx7d.h"
+ "${ProjDirPath}/../../../../../platform/drivers/inc/wdog_imx.h"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/croutine.c"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/event_groups.c"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/list.c"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/queue.c"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/tasks.c"
+ "${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/timers.c"
+ "${ProjDirPath}/../../../../../platform/drivers/src/ccm_analog_imx7d.c"
+ "${ProjDirPath}/../../../../../platform/drivers/src/ccm_imx7d.c"
+ "${ProjDirPath}/../../../../../platform/drivers/src/rdc.c"
+ "${ProjDirPath}/../../../../../platform/drivers/src/wdog_imx.c"
+ "${ProjDirPath}/../../../../../platform/utilities/src/debug_console_imx.c"
+ "${ProjDirPath}/../../../../../platform/utilities/inc/debug_console_imx.h"
+ "${ProjDirPath}/../../../../../platform/utilities/src/print_scan.c"
+ "${ProjDirPath}/../../../../../platform/utilities/src/print_scan.h"
+ "${ProjDirPath}/../../../../../platform/devices/MCIMX7D/startup/system_MCIMX7D_M4.c"
+ "${ProjDirPath}/../../../../../platform/devices/MCIMX7D/startup/system_MCIMX7D_M4.h"
+ "${ProjDirPath}/../../../pin_mux.c"
+ "${ProjDirPath}/../../../pin_mux.h"
+ "${ProjDirPath}/../../../board.c"
+ "${ProjDirPath}/../../../board.h"
+ "${ProjDirPath}/../../../clock_freq.c"
+ "${ProjDirPath}/../../../clock_freq.h"
+ "${ProjDirPath}/../hardware_init.c"
+)
+SET_TARGET_PROPERTIES(sensor_demo PROPERTIES OUTPUT_NAME "sensor_demo.elf")
+
+TARGET_LINK_LIBRARIES(sensor_demo -Wl,--start-group)
+# LIBRARIES
+IF(CMAKE_BUILD_TYPE MATCHES Debug)
+ELSEIF(CMAKE_BUILD_TYPE MATCHES Release)
+ENDIF()
+
+# SYSTEM LIBRARIES
+TARGET_LINK_LIBRARIES(sensor_demo m)
+TARGET_LINK_LIBRARIES(sensor_demo c)
+TARGET_LINK_LIBRARIES(sensor_demo gcc)
+TARGET_LINK_LIBRARIES(sensor_demo nosys)
+TARGET_LINK_LIBRARIES(sensor_demo -Wl,--end-group)
+
+# MAP FILE
+SET(CMAKE_EXE_LINKER_FLAGS_DEBUG "${CMAKE_EXE_LINKER_FLAGS_DEBUG} -Xlinker -Map=debug/sensor_demo.map")
+SET(CMAKE_EXE_LINKER_FLAGS_RELEASE "${CMAKE_EXE_LINKER_FLAGS_RELEASE} -Xlinker -Map=release/sensor_demo.map")
+
+# BIN AND HEX
+ADD_CUSTOM_COMMAND(TARGET sensor_demo POST_BUILD COMMAND ${CMAKE_OBJCOPY} -Oihex ${EXECUTABLE_OUTPUT_PATH}/sensor_demo.elf ${EXECUTABLE_OUTPUT_PATH}/sensor_demo.hex)
+ADD_CUSTOM_COMMAND(TARGET sensor_demo POST_BUILD COMMAND ${CMAKE_OBJCOPY} -Obinary ${EXECUTABLE_OUTPUT_PATH}/sensor_demo.elf ${EXECUTABLE_OUTPUT_PATH}/sensor_demo.bin)
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_all.bat b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_all.bat
new file mode 100755
index 0000000..6d41d86
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_all.bat
@@ -0,0 +1,5 @@
+cmake -DCMAKE_TOOLCHAIN_FILE="../../../../../tools/cmake_toolchain_files/armgcc.cmake" -G "MinGW Makefiles" -DCMAKE_BUILD_TYPE=Debug .
+mingw32-make -j4
+cmake -DCMAKE_TOOLCHAIN_FILE="../../../../../tools/cmake_toolchain_files/armgcc.cmake" -G "MinGW Makefiles" -DCMAKE_BUILD_TYPE=Release .
+mingw32-make -j4
+pause
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_all.sh b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_all.sh
new file mode 100755
index 0000000..ebb0c25
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_all.sh
@@ -0,0 +1,5 @@
+#!/bin/sh
+cmake -DCMAKE_TOOLCHAIN_FILE="../../../../../tools/cmake_toolchain_files/armgcc.cmake" -G "Unix Makefiles" -DCMAKE_BUILD_TYPE=Debug .
+make -j4
+cmake -DCMAKE_TOOLCHAIN_FILE="../../../../../tools/cmake_toolchain_files/armgcc.cmake" -G "Unix Makefiles" -DCMAKE_BUILD_TYPE=Release .
+make -j4
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_debug.bat b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_debug.bat
new file mode 100755
index 0000000..bf3b902
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_debug.bat
@@ -0,0 +1,3 @@
+cmake -DCMAKE_TOOLCHAIN_FILE="../../../../../tools/cmake_toolchain_files/armgcc.cmake" -G "MinGW Makefiles" -DCMAKE_BUILD_TYPE=Debug .
+mingw32-make -j4
+pause
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_debug.sh b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_debug.sh
new file mode 100755
index 0000000..571868b
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_debug.sh
@@ -0,0 +1,3 @@
+#!/bin/sh
+cmake -DCMAKE_TOOLCHAIN_FILE="../../../../../tools/cmake_toolchain_files/armgcc.cmake" -G "Unix Makefiles" -DCMAKE_BUILD_TYPE=Debug .
+make -j4
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_release.bat b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_release.bat
new file mode 100755
index 0000000..e229a83
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_release.bat
@@ -0,0 +1,3 @@
+cmake -DCMAKE_TOOLCHAIN_FILE="../../../../../tools/cmake_toolchain_files/armgcc.cmake" -G "MinGW Makefiles" -DCMAKE_BUILD_TYPE=Release .
+mingw32-make -j4
+pause
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_release.sh b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_release.sh
new file mode 100755
index 0000000..035ce4e
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/build_release.sh
@@ -0,0 +1,3 @@
+#!/bin/sh
+cmake -DCMAKE_TOOLCHAIN_FILE="../../../../../tools/cmake_toolchain_files/armgcc.cmake" -G "Unix Makefiles" -DCMAKE_BUILD_TYPE=Release .
+make -j4
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/clean.bat b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/clean.bat
new file mode 100755
index 0000000..ffea088
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/clean.bat
@@ -0,0 +1,3 @@
+RD /s /Q Debug Release CMakeFiles
+DEL /s /Q /F Makefile cmake_install.cmake CMakeCache.txt
+pause
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/clean.sh b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/clean.sh
new file mode 100755
index 0000000..795ad87
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/armgcc/clean.sh
@@ -0,0 +1,3 @@
+#!/bin/sh
+rm -rf debug release CMakeFiles
+rm -rf Makefile cmake_install.cmake CMakeCache.txt
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/fxas21002.c b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/fxas21002.c
new file mode 100644
index 0000000..4764390
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/fxas21002.c
@@ -0,0 +1,118 @@
+/*
+ * Copyright (c) 2015, 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 "board.h"
+#include "i2c_xfer.h"
+#include "fxas21002.h"
+
+/*FUNCTION****************************************************************
+*
+* Function Name : fxas21002_init
+* Returned Value : result
+* Comments : Initialize FXAS21002 Gyro sensor.
+*
+*END*********************************************************************/
+bool fxas21002_init(gyro_sensor_t* pThisGyro)
+{
+ uint8_t txBuffer;
+ uint8_t cmdBuffer[2];
+
+ pThisGyro->fDegPerSecPerCount = FXAS21002_DEGPERSECPERCOUNT;
+
+ // Write 0000 0000 = 0x00 to CTRL_REG1 to place FXOS21002 in Standby
+ // [7]: ZR_cond=0
+ // [6]: RST=0
+ // [5]: ST=0 self test disabled
+ // [4-2]: DR[2-0]=000 for 800Hz
+ // [1-0]: Active=0, Ready=0 for Standby mode
+ cmdBuffer[0] = BOARD_I2C_FXAS21002_ADDR << 1;
+ cmdBuffer[1] = FXAS21002_CTRL_REG1;
+ txBuffer = 0x00;
+ if (!I2C_XFER_SendDataBlocking(cmdBuffer, 2, &txBuffer, 1))
+ return false;
+
+ // write 0000 0000 = 0x00 to CTRL_REG0 to configure range and filters
+ // [7-6]: BW[1-0]=00, LPF disabled
+ // [5]: SPIW=0 4 wire SPI (irrelevant)
+ // [4-3]: SEL[1-0]=00 for 10Hz HPF at 200Hz ODR
+ // [2]: HPF_EN=0 disable HPF
+ // [1-0]: FS[1-0]=00 for 1600dps (TBD CHANGE TO 2000dps when final trimmed parts available)
+ cmdBuffer[0] = BOARD_I2C_FXAS21002_ADDR << 1;
+ cmdBuffer[1] = FXAS21002_CTRL_REG0;
+ txBuffer = 0x00;
+ if (!I2C_XFER_SendDataBlocking(cmdBuffer, 2, &txBuffer, 1))
+ return false;
+
+ // write 0000 0010 = 0x02 to CTRL_REG1 to configure 800Hz ODR and enter Active mode
+ // [7]: ZR_cond=0
+ // [6]: RST=0
+ // [5]: ST=0 self test disabled
+ // [4-2]: DR[2-0]=000 for 800Hz ODR
+ // [1-0]: Active=1, Ready=0 for Active mode
+ cmdBuffer[0] = BOARD_I2C_FXAS21002_ADDR << 1;
+ cmdBuffer[1] = FXAS21002_CTRL_REG1;
+ txBuffer = 0x02;
+ if (!I2C_XFER_SendDataBlocking(cmdBuffer, 2, &txBuffer, 1))
+ return false;
+
+ return true;
+}
+
+/*FUNCTION****************************************************************
+*
+* Function Name : fxas21002_read_data
+* Returned Value : result
+* Comments : Get current height and temperature from fxas21002.
+*
+*END*********************************************************************/
+bool fxas21002_read_data(gyro_sensor_t* pThisGyro)
+{
+ uint8_t rxBuffer[6];
+ uint8_t cmdBuffer[3];
+
+ // store the gain terms in the GyroSensor structure
+ cmdBuffer[0] = BOARD_I2C_FXAS21002_ADDR << 1;
+ cmdBuffer[1] = FXAS21002_OUT_X_MSB;
+ cmdBuffer[2] = (BOARD_I2C_FXAS21002_ADDR << 1) + 1;
+ if (!I2C_XFER_ReceiveDataBlocking(cmdBuffer, 3, rxBuffer, 6))
+ return false;
+
+ pThisGyro->iYpFast[0] = (rxBuffer[0] << 8) | rxBuffer[1];
+ pThisGyro->iYpFast[1] = (rxBuffer[2] << 8) | rxBuffer[3];
+ pThisGyro->iYpFast[2] = (rxBuffer[4] << 8) | rxBuffer[5];
+
+ return true;
+}
+
+/*******************************************************************************
+ * EOF
+ ******************************************************************************/
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/fxas21002.h b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/fxas21002.h
new file mode 100644
index 0000000..a3adbae
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/fxas21002.h
@@ -0,0 +1,98 @@
+/*
+ * Copyright (c) 2015, 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.
+ */
+
+#ifndef __FXAS21002_H__
+#define __FXAS21002_H__
+
+#define OVERSAMPLE_RATIO (64) // int32: 8x: 3DOF, 6DOF, 9DOF run at SENSORFS / OVERSAMPLE_RATIO Hz
+
+// place the gain in the gyro structure
+#define FXAS21002_COUNTSPERDEGPERSEC (16.0F) // for production 2000dps range (2000dps=32000)
+#define FXAS21002_DEGPERSECPERCOUNT (0.0625F) // must be reciprocal of FCOUNTSPERDEGPERSEC
+
+/* I2C Slave Address define */
+#define FXAS21002_ADDRESS_0 (0x20)
+#define FXAS21002_ADDRESS_1 (0x21)
+#define FXAS21002_ADDRESS_DEFAULT (FXAS21002_ADDRESS_0)
+
+/* FXAS21002 device ID number */
+#define FXAS21002_DEVICE_ID (0xD7)
+
+/* FXAS21002 Registers address definition */
+#define FXAS21002_STATUS (0x00)
+#define FXAS21002_OUT_X_MSB (0x01)
+#define FXAS21002_OUT_X_LSB (0x02)
+#define FXAS21002_OUT_Y_MSB (0x03)
+#define FXAS21002_OUT_Y_LSB (0x04)
+#define FXAS21002_OUT_Z_MSB (0x05)
+#define FXAS21002_OUT_Z_LSB (0x06)
+#define FXAS21002_DR_STATUS (0x07)
+#define FXAS21002_F_STATUS (0x08)
+#define FXAS21002_F_SETUP (0x09)
+#define FXAS21002_F_EVENT (0x0A)
+#define FXAS21002_INT_SRC_FLAG (0x0B)
+#define FXAS21002_WHO_AM_I (0x0C)
+#define FXAS21002_CTRL_REG0 (0x0D)
+#define FXAS21002_RT_CFG (0x0E)
+#define FXAS21002_RT_SRC (0x0F)
+#define FXAS21002_RT_THS (0x10)
+#define FXAS21002_RT_COUNT (0x11)
+#define FXAS21002_TEMP (0x12)
+#define FXAS21002_CTRL_REG1 (0x13)
+#define FXAS21002_CTRL_REG2 (0x14)
+#define FXAS21002_CTRL_REG3 (0x15)
+
+// gyro sensor structure definition
+typedef struct _gyro_sensor
+{
+ int32_t iSumYpFast[3]; // sum of fast measurements
+ float fYp[3]; // raw gyro sensor output (deg/s)
+ float fDegPerSecPerCount; // initialized to FDEGPERSECPERCOUNT
+ int16_t iYpFast[3]; // fast (typically 200Hz) readings
+ int16_t iYp[3]; // averaged gyro sensor output (counts)
+} gyro_sensor_t;
+
+/* Function prototypes */
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+bool fxas21002_init(gyro_sensor_t*);
+bool fxas21002_read_data(gyro_sensor_t*);
+
+#ifdef __cplusplus
+}
+#endif
+
+
+#endif /* __FXAS21002_H__ */
+/*******************************************************************************
+ * EOF
+ ******************************************************************************/
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/fxos8700.c b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/fxos8700.c
new file mode 100644
index 0000000..207c594
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/fxos8700.c
@@ -0,0 +1,158 @@
+/*
+ * Copyright (c) 2015, 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 "board.h"
+#include "i2c_xfer.h"
+#include "fxos8700.h"
+
+/*FUNCTION****************************************************************
+*
+* Function Name : fxos8700_init
+* Returned Value : result
+* Comments : Initialize FXOS8700 Acc and Mag sensor.
+*
+*END*********************************************************************/
+bool fxos8700_init(void)
+{
+ uint8_t txBuffer;
+ uint8_t cmdBuffer[2];
+
+ // write 0000 0000 = 0x00 to CTRL_REG1 to place FXOS8700 into standby
+ // [7-1] = 0000 000
+ // [0]: active=0
+ cmdBuffer[0] = BOARD_I2C_FXOS8700_ADDR << 1;
+ cmdBuffer[1] = FXOS8700_CTRL_REG1;
+ txBuffer = 0x00;
+ if (!I2C_XFER_SendDataBlocking(cmdBuffer, 2, &txBuffer, 1))
+ return false;
+
+ // write 0001 1111 = 0x1F to M_CTRL_REG1
+ // [7]: m_acal=0: auto calibration disabled
+ // [6]: m_rst=0: one-shot magnetic reset disabled
+ // [5]: m_ost=0: one-shot magnetic measurement disabled
+ // [4-2]: m_os=111=7: 8x oversampling (for 200Hz) to reduce magnetometer noise
+ // [1-0]: m_hms=11=3: select hybrid mode with accel and magnetometer active
+ cmdBuffer[0] = BOARD_I2C_FXOS8700_ADDR << 1;
+ cmdBuffer[1] = FXOS8700_M_CTRL_REG1;
+ txBuffer = 0x1F;
+ if (!I2C_XFER_SendDataBlocking(cmdBuffer, 2, &txBuffer, 1))
+ return false;
+
+ // write 0010 0000 = 0x20 to magnetometer control register 2
+ // [7]: reserved
+ // [6]: reserved
+ // [5]: hyb_autoinc_mode=1 to map the magnetometer registers to follow the accelerometer registers
+ // [4]: m_maxmin_dis=0 to retain default min/max latching even though not used
+ // [3]: m_maxmin_dis_ths=0
+ // [2]: m_maxmin_rst=0
+ // [1-0]: m_rst_cnt=00 to enable magnetic reset each cycle
+ cmdBuffer[0] = BOARD_I2C_FXOS8700_ADDR << 1;
+ cmdBuffer[1] = FXOS8700_M_CTRL_REG2;
+ txBuffer = 0x20;
+ if (!I2C_XFER_SendDataBlocking(cmdBuffer, 2, &txBuffer, 1))
+ return false;
+
+ // write 0000 0001= 0x01 to XYZ_DATA_CFG register
+ // [7]: reserved
+ // [6]: reserved
+ // [5]: reserved
+ // [4]: hpf_out=0
+ // [3]: reserved
+ // [2]: reserved
+ // [1-0]: fs=01 for 4g mode: 2048 counts / g = 8192 counts / g after 2 bit left shift
+ cmdBuffer[0] = BOARD_I2C_FXOS8700_ADDR << 1;
+ cmdBuffer[1] = FXOS8700_XYZ_DATA_CFG;
+ txBuffer = 0x01;
+ if (!I2C_XFER_SendDataBlocking(cmdBuffer, 2, &txBuffer, 1))
+ return false;
+
+ // write 0000 0010 = 0x02 to CTRL_REG2 to set MODS bits
+ // [7]: st=0: self test disabled
+ // [6]: rst=0: reset disabled
+ // [5]: unused
+ // [4-3]: smods=00
+ // [2]: slpe=0: auto sleep disabled
+ // [1-0]: mods=10 for high resolution (maximum over sampling)
+ cmdBuffer[0] = BOARD_I2C_FXOS8700_ADDR << 1;
+ cmdBuffer[1] = FXOS8700_CTRL_REG2;
+ txBuffer = 0x02;
+ if (!I2C_XFER_SendDataBlocking(cmdBuffer, 2, &txBuffer, 1))
+ return false;
+
+ // write 0000 1101 = 0x0D to accelerometer control register 1
+ // [7-6]: aslp_rate=00
+ // [5-3]: dr=001=1 for 200Hz data rate (when in hybrid mode)
+ // [2]: lnoise=1 for low noise mode (since we're in 4g mode)
+ // [1]: f_read=0 for normal 16 bit reads
+ // [0]: active=1 to take the part out of standby and enable sampling
+ cmdBuffer[0] = BOARD_I2C_FXOS8700_ADDR << 1;
+ cmdBuffer[1] = FXOS8700_CTRL_REG1;
+ txBuffer = 0x0D;
+ if (!I2C_XFER_SendDataBlocking(cmdBuffer, 2, &txBuffer, 1))
+ return false;
+
+ return true;
+}
+
+/*FUNCTION****************************************************************
+*
+* Function Name : fxos8700_read_data
+* Returned Value : result
+* Comments : Get current Acc and Mag from FXOS8700 6-axis sensor.
+*
+*END*********************************************************************/
+bool fxos8700_read_data(int16_t *Ax, int16_t *Ay, int16_t *Az,
+ int16_t *Mx, int16_t *My, int16_t *Mz)
+{
+ uint8_t rxBuffer[12];
+ uint8_t cmdBuffer[3];
+
+ // Fetch Current Acc and Mag in all Axis
+ cmdBuffer[0] = BOARD_I2C_FXOS8700_ADDR << 1;
+ cmdBuffer[1] = FXOS8700_OUT_X_MSB;
+ cmdBuffer[2] = (BOARD_I2C_FXOS8700_ADDR << 1) + 1;
+ if (!I2C_XFER_ReceiveDataBlocking(cmdBuffer, 3, rxBuffer, 12))
+ return false;
+
+ *Ax = (rxBuffer[2] << 8) | rxBuffer[3];
+ *Ay = (rxBuffer[0] << 8) | rxBuffer[1];
+ *Az = (rxBuffer[4] << 8) | rxBuffer[5];
+ *Mx = (rxBuffer[8] << 8) | rxBuffer[9];
+ *My = (rxBuffer[6] << 8) | rxBuffer[7];
+ *Mz = (rxBuffer[10] << 8) | rxBuffer[11];
+
+ return true;
+}
+
+/*******************************************************************************
+ * EOF
+ ******************************************************************************/
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/fxos8700.h b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/fxos8700.h
new file mode 100644
index 0000000..65e61cd
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/fxos8700.h
@@ -0,0 +1,72 @@
+/*
+ * Copyright (c) 2015, 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.
+ */
+
+#ifndef __FXOS8700_H__
+#define __FXOS8700_H__
+
+#include <stdint.h>
+#include <stdbool.h>
+
+/* I2C Slave Address define */
+#define FXOS8700_ADDRESS_0 (0x1C)
+#define FXOS8700_ADDRESS_1 (0x1D)
+#define FXOS8700_ADDRESS_2 (0x1E)
+#define FXOS8700_ADDRESS_3 (0x1F)
+#define FXOS8700_ADDRESS_DEFAULT (FXOS8700_ADDRESS_0)
+
+/* FXOS8700 device ID number */
+#define FXOS8700_DEVICE_ID (0xC7)
+
+/* FXOS8700 Registers address definition */
+#define FXOS8700_OUT_X_MSB (0x01)
+#define FXOS8700_WHO_AM_I (0x0D)
+#define FXOS8700_XYZ_DATA_CFG (0x0E)
+#define FXOS8700_CTRL_REG1 (0x2A)
+#define FXOS8700_CTRL_REG2 (0x2B)
+#define FXOS8700_M_CTRL_REG1 (0x5B)
+#define FXOS8700_M_CTRL_REG2 (0x5C)
+
+/* Function prototypes */
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+bool fxos8700_init(void);
+bool fxos8700_read_data(int16_t *, int16_t *, int16_t *, int16_t *, int16_t *, int16_t *);
+
+#ifdef __cplusplus
+}
+#endif
+
+
+#endif/* __FXOS8700_H__ */
+/*******************************************************************************
+ * EOF
+ ******************************************************************************/
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/i2c_xfer.c b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/i2c_xfer.c
new file mode 100644
index 0000000..b8410d4
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/i2c_xfer.c
@@ -0,0 +1,326 @@
+/*
+ * Copyright (c) 2015, 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 "FreeRTOS.h"
+#include "semphr.h"
+#include "device_imx.h"
+#include "i2c_imx.h"
+#include "board.h"
+
+typedef struct _i2c_state {
+ const uint8_t* cmdBuff; /*!< The buffer of I2C command. */
+ const uint8_t* txBuff; /*!< The buffer of data being sent.*/
+ uint8_t* rxBuff; /*!< The buffer of received data. */
+ uint32_t cmdSize; /*!< The remaining number of commands to be transmitted. */
+ uint32_t txSize; /*!< The remaining number of bytes to be transmitted. */
+ uint32_t rxSize; /*!< The remaining number of bytes to be received. */
+ bool isBusy; /*!< True if there is an active transmission. */
+ uint32_t operateDir; /*!< Overall I2C bus operating direction. */
+ uint32_t currentDir; /*!< Current Data transfer direction. */
+ uint32_t currentMode; /*!< Current I2C Bus role of this module. */
+ SemaphoreHandle_t xSemaphore; /*!< I2C internal synchronize semaphore. */
+} i2c_state_t;
+
+/* I2C runtime state structure */
+static volatile i2c_state_t i2cState;
+
+void I2C_XFER_Config(i2c_init_config_t* initConfig)
+{
+ /* Initialize I2C state structure content. */
+ i2cState.cmdBuff = 0;
+ i2cState.txBuff = 0;
+ i2cState.rxBuff = 0;
+ i2cState.cmdSize = 0;
+ i2cState.txSize = 0;
+ i2cState.rxSize = 0;
+ i2cState.isBusy = false;
+ i2cState.operateDir = i2cDirectionReceive;
+ i2cState.currentDir = i2cDirectionReceive;
+ i2cState.currentMode = i2cModeSlave;
+ i2cState.xSemaphore = xSemaphoreCreateBinary();
+
+ /* Initialize I2C baud rate, mode, transfer direction and slave address. */
+ I2C_Init(BOARD_I2C_BASEADDR, initConfig);
+
+ /* Set I2C Interrupt priority */
+ NVIC_SetPriority(BOARD_I2C_IRQ_NUM, 3);
+
+ /* Call core API to enable the IRQ. */
+ NVIC_EnableIRQ(BOARD_I2C_IRQ_NUM);
+
+ /* Finally, enable the I2C module */
+ I2C_Enable(BOARD_I2C_BASEADDR);
+}
+
+bool I2C_XFER_SendDataBlocking(const uint8_t* cmdBuff, uint32_t cmdSize,
+ const uint8_t* txBuffer, uint32_t txSize)
+{
+ if ((i2cState.isBusy) || (0 == txSize))
+ return false;
+
+ /* Initialize i2c transfer struct */
+ i2cState.cmdBuff = cmdBuff;
+ i2cState.cmdSize = cmdSize;
+ i2cState.txBuff = txBuffer;
+ i2cState.txSize = txSize;
+ i2cState.isBusy = true;
+ i2cState.operateDir = i2cDirectionTransmit;
+
+ /* Clear I2C interrupt flag to avoid spurious interrupt */
+ I2C_ClearStatusFlag(BOARD_I2C_BASEADDR, i2cStatusInterrupt);
+
+ if (I2C_GetStatusFlag(BOARD_I2C_BASEADDR, i2cStatusBusBusy))
+ {
+ /* Reset i2c transfer state. */
+ i2cState.operateDir = i2cDirectionReceive;
+ i2cState.isBusy = false;
+ return false;
+ }
+
+ /* Set I2C work under Tx mode */
+ I2C_SetDirMode(BOARD_I2C_BASEADDR, i2cDirectionTransmit);
+ i2cState.currentDir = i2cDirectionTransmit;
+
+ /* Switch to Master Mode and Send Start Signal. */
+ I2C_SetWorkMode(BOARD_I2C_BASEADDR, i2cModeMaster);
+ i2cState.currentMode = i2cModeMaster;
+
+ if (0 != cmdSize)
+ {
+ I2C_WriteByte(BOARD_I2C_BASEADDR, *i2cState.cmdBuff);
+ i2cState.cmdBuff++;
+ i2cState.cmdSize--;
+ }
+ else
+ {
+ I2C_WriteByte(BOARD_I2C_BASEADDR, *i2cState.txBuff);
+ i2cState.txBuff++;
+ i2cState.txSize--;
+ }
+
+ /* Enable I2C interrupt, subsequent data transfer will be handled in ISR. */
+ I2C_SetIntCmd(BOARD_I2C_BASEADDR, true);
+
+ /* Wait until send data finish. */
+ xSemaphoreTake(i2cState.xSemaphore, portMAX_DELAY);
+
+ return true;
+}
+
+uint32_t I2C_XFER_GetSendStatus(void)
+{
+ return i2cState.txSize;
+}
+
+bool I2C_XFER_ReceiveDataBlocking(const uint8_t* cmdBuff, uint32_t cmdSize,
+ uint8_t* rxBuffer, uint32_t rxSize)
+{
+ if ((i2cState.isBusy) || (0 == rxSize))
+ return false;
+
+ /* Initialize i2c transfer struct */
+ i2cState.cmdBuff = cmdBuff;
+ i2cState.cmdSize = cmdSize;
+ i2cState.rxBuff = rxBuffer;
+ i2cState.rxSize = rxSize;
+ i2cState.isBusy = true;
+ i2cState.operateDir = i2cDirectionReceive;
+
+ /* Clear I2C interrupt flag to avoid spurious interrupt */
+ I2C_ClearStatusFlag(BOARD_I2C_BASEADDR, i2cStatusInterrupt);
+
+ if (I2C_GetStatusFlag(BOARD_I2C_BASEADDR, i2cStatusBusBusy))
+ {
+ /* Reset i2c transfer state. */
+ i2cState.operateDir = i2cDirectionReceive;
+ i2cState.isBusy = false;
+ return false;
+ }
+
+ /* Set I2C work under Tx mode */
+ I2C_SetDirMode(BOARD_I2C_BASEADDR, i2cDirectionTransmit);
+ i2cState.currentDir = i2cDirectionTransmit;
+
+ /* Switch to Master Mode and Send Start Signal. */
+ I2C_SetWorkMode(BOARD_I2C_BASEADDR, i2cModeMaster);
+ i2cState.currentMode = i2cModeMaster;
+
+ /* Is there command to be sent before receive data? */
+ if (0 != i2cState.cmdSize)
+ {
+ if (1 == i2cState.cmdSize)
+ I2C_SendRepeatStart(BOARD_I2C_BASEADDR);
+ I2C_WriteByte(BOARD_I2C_BASEADDR, *i2cState.cmdBuff);
+ i2cState.cmdBuff++;
+ i2cState.cmdSize--;
+ }
+ else
+ {
+ /* Change to receive state. */
+ I2C_SetDirMode(BOARD_I2C_BASEADDR, i2cDirectionReceive);
+ i2cState.currentDir = i2cDirectionReceive;
+
+ if (1 == rxSize)
+ /* Send Nack */
+ I2C_SetAckBit(BOARD_I2C_BASEADDR, false);
+ else
+ /* Send Ack */
+ I2C_SetAckBit(BOARD_I2C_BASEADDR, true);
+ /* dummy read to clock in 1st byte */
+ I2C_ReadByte(BOARD_I2C_BASEADDR);
+ }
+
+ /* Enable I2C interrupt, subsequent data transfer will be handled in ISR. */
+ I2C_SetIntCmd(BOARD_I2C_BASEADDR, true);
+
+ /* Wait until receive data finish. */
+ xSemaphoreTake(i2cState.xSemaphore, portMAX_DELAY);
+
+ return true;
+}
+
+uint32_t I2C_XFER_GetReceiveStatus(void)
+{
+ return i2cState.rxSize;
+}
+
+void BOARD_I2C_HANDLER(void)
+{
+ BaseType_t xHigherPriorityTaskWoken = pdFALSE;
+
+ /* Clear interrupt flag. */
+ I2C_ClearStatusFlag(BOARD_I2C_BASEADDR, i2cStatusInterrupt);
+
+ /* Exit the ISR if no transfer is happening for this instance. */
+ if (!i2cState.isBusy)
+ return;
+
+ if (i2cModeMaster == i2cState.currentMode)
+ {
+ if (i2cDirectionTransmit == i2cState.currentDir)
+ {
+ if ((I2C_GetStatusFlag(BOARD_I2C_BASEADDR, i2cStatusReceivedAck)) ||
+ ((0 == i2cState.txSize) && (0 == i2cState.cmdSize)))
+ {
+ if ((i2cDirectionTransmit == i2cState.operateDir) ||
+ (I2C_GetStatusFlag(BOARD_I2C_BASEADDR, i2cStatusReceivedAck)))
+ {
+ /* Switch to Slave mode and Generate a Stop Signal. */
+ I2C_SetWorkMode(BOARD_I2C_BASEADDR, i2cModeSlave);
+ i2cState.currentMode = i2cModeSlave;
+
+ /* Switch back to Rx direction. */
+ I2C_SetDirMode(BOARD_I2C_BASEADDR, i2cDirectionReceive);
+ i2cState.currentDir = i2cDirectionReceive;
+
+ /* Close I2C interrupt. */
+ I2C_SetIntCmd(BOARD_I2C_BASEADDR, false);
+ /* Release I2C Bus. */
+ i2cState.isBusy = false;
+ xSemaphoreGiveFromISR(i2cState.xSemaphore, &xHigherPriorityTaskWoken);
+ }
+ else
+ {
+ /* Switch back to Rx direction. */
+ I2C_SetDirMode(BOARD_I2C_BASEADDR, i2cDirectionReceive);
+ i2cState.currentDir = i2cDirectionReceive;
+
+ if (1 == i2cState.rxSize)
+ /* Send Nack */
+ I2C_SetAckBit(BOARD_I2C_BASEADDR, false);
+ else
+ /* Send Ack */
+ I2C_SetAckBit(BOARD_I2C_BASEADDR, true);
+ /* dummy read to clock in 1st byte */
+ *i2cState.rxBuff = I2C_ReadByte(BOARD_I2C_BASEADDR);
+ }
+ }
+ else
+ {
+ if (0 != i2cState.cmdSize)
+ {
+ if ((1 == i2cState.cmdSize) && (i2cDirectionReceive == i2cState.operateDir))
+ I2C_SendRepeatStart(BOARD_I2C_BASEADDR);
+ I2C_WriteByte(BOARD_I2C_BASEADDR, *i2cState.cmdBuff);
+ i2cState.cmdBuff++;
+ i2cState.cmdSize--;
+ }
+ else
+ {
+ I2C_WriteByte(BOARD_I2C_BASEADDR, *i2cState.txBuff);
+ i2cState.txBuff++;
+ i2cState.txSize--;
+ }
+ }
+ }
+ else
+ {
+ /* Normal read operation. */
+ if (2 == i2cState.rxSize)
+ /* Send Nack */
+ I2C_SetAckBit(BOARD_I2C_BASEADDR, false);
+ else
+ /* Send Nack */
+ I2C_SetAckBit(BOARD_I2C_BASEADDR, true);
+
+ if (1 == i2cState.rxSize)
+ {
+ /* Switch back to Tx direction to avoid additional I2C bus read. */
+ I2C_SetDirMode(BOARD_I2C_BASEADDR, i2cDirectionTransmit);
+ i2cState.currentDir = i2cDirectionTransmit;
+ }
+ *i2cState.rxBuff = I2C_ReadByte(BOARD_I2C_BASEADDR);
+ i2cState.rxBuff++;
+ i2cState.rxSize--;
+
+ /* receive finished. */
+ if (0 == i2cState.rxSize)
+ {
+ /* Switch to Slave mode and Generate a Stop Signal. */
+ I2C_SetWorkMode(BOARD_I2C_BASEADDR, i2cModeSlave);
+ i2cState.currentMode = i2cModeSlave;
+
+ /* Switch back to Rx direction. */
+ I2C_SetDirMode(BOARD_I2C_BASEADDR, i2cDirectionReceive);
+ i2cState.currentDir = i2cDirectionReceive;
+
+ /* Close I2C interrupt. */
+ I2C_SetIntCmd(BOARD_I2C_BASEADDR, false);
+ /* Release I2C Bus. */
+ i2cState.isBusy = false;
+ /* Release I2C Sem4 */
+ xSemaphoreGiveFromISR(i2cState.xSemaphore, &xHigherPriorityTaskWoken);
+ }
+ }
+ }
+}
+
+/*******************************************************************************
+ * EOF
+ ******************************************************************************/
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/i2c_xfer.h b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/i2c_xfer.h
new file mode 100644
index 0000000..64b8f03
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/i2c_xfer.h
@@ -0,0 +1,55 @@
+/*
+ * Copyright (c) 2015, 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.
+ */
+#ifndef __I2C_XFER_H__
+#define __I2C_XFER_H__
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "i2c_imx.h"
+
+/* Function prototypes */
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+void I2C_XFER_Config(i2c_init_config_t* initConfig);
+bool I2C_XFER_SendDataBlocking(const uint8_t* cmdBuff, uint32_t cmdSize, const uint8_t* txBuffer, uint32_t txSize);
+uint32_t I2C_XFER_GetSendStatus(void);
+bool I2C_XFER_ReceiveDataBlocking(const uint8_t* cmdBuff, uint32_t cmdSize, uint8_t* rxBuffer, uint32_t rxSize);
+uint32_t I2C_XFER_GetReceiveStatus(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __I2C_XFER_H__ */
+/*******************************************************************************
+ * EOF
+ ******************************************************************************/
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/mma8451q.c b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/mma8451q.c
new file mode 100644
index 0000000..d44f63d
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/mma8451q.c
@@ -0,0 +1,185 @@
+/*
+ * Copyright (c) 2015, 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 "board.h"
+#include "debug_console_imx.h"
+#include "i2c_xfer.h"
+#include "mma8451q.h"
+
+static uint8_t mma8451qMode;
+
+/*FUNCTION****************************************************************
+*
+* Function Name : MMA8451Q_Init
+* Returned Value : true or false
+* Comments : Initialize MMA8451Q 3-axis accelerometer sensor.
+*
+*END*********************************************************************/
+bool MMA8451Q_Init(void)
+{
+ uint8_t txBuffer;
+ uint8_t rxBuffer;
+ uint8_t cmdBuffer[3];
+
+ /* Place the MMA8451Q in Standby */
+ PRINTF("Place the MMA8451Q in standby mode... ");
+ cmdBuffer[0] = BOARD_I2C_MMA8451Q_ADDR << 1;
+ cmdBuffer[1] = MMA8451Q_CTRL_REG1;
+ txBuffer = 0x00;
+ if (!I2C_XFER_SendDataBlocking(cmdBuffer, 2, &txBuffer, 1))
+ {
+ PRINTF("ERROR\n\r");
+ return false;
+ }
+ PRINTF("OK\n\r");
+
+ // write 0000 0000= 0x00 to MMA8451Q_XYZ_DATA_CFG register
+ // [7]: reserved
+ // [6]: reserved
+ // [5]: reserved
+ // [4]: hpf_out=0
+ // [3]: reserved
+ // [2]: reserved
+ // [1-0]: fs=00 for 2g mode.
+ PRINTF("Set the mode: 2G ... ");
+ cmdBuffer[0] = BOARD_I2C_MMA8451Q_ADDR << 1;
+ cmdBuffer[1] = MMA8451Q_XYZ_DATA_CFG;
+ txBuffer = 0x00;
+ if (!I2C_XFER_SendDataBlocking(cmdBuffer, 2, &txBuffer, 1))
+ {
+ PRINTF("ERROR\n\r");
+ return false;
+ }
+ mma8451qMode = 0U;
+ PRINTF("OK\n\r");
+
+ // write 0000 0001 = 0x01 to MMA8451Q_CTRL_REG1
+ // [7-6]: aslp_rate=00
+ // [5-3]: dr=000
+ // [2]: lnoise=0
+ // [1]: f_read=0 for normal read mode
+ // [0]: active=1 to take the part out of standby and enable sampling
+ PRINTF("Fast read clear and active mode ... ");
+ cmdBuffer[0] = BOARD_I2C_MMA8451Q_ADDR << 1;
+ cmdBuffer[1] = MMA8451Q_CTRL_REG1;
+ txBuffer = 0x01;
+ if (!I2C_XFER_SendDataBlocking(cmdBuffer, 2, &txBuffer, 1))
+ {
+ PRINTF("ERROR\n\r");
+ return false;
+ }
+ PRINTF("OK\n\r");
+
+ // read WHO_AM_I device register, 0x1A
+ PRINTF("Test WHO_AM_I check... ");
+ cmdBuffer[0] = BOARD_I2C_MMA8451Q_ADDR << 1;
+ cmdBuffer[1] = MMA8451Q_WHO_AM_I;
+ cmdBuffer[2] = (BOARD_I2C_MMA8451Q_ADDR << 1) + 1;
+ if (!I2C_XFER_ReceiveDataBlocking(cmdBuffer, 3, &rxBuffer, 1))
+ {
+ PRINTF("ERROR\n\r");
+ return false;
+ }
+ if(rxBuffer == MMA8451Q_DEVICE_ID)
+ PRINTF("OK\n\r");
+ else
+ {
+ PRINTF("ERROR\n\r");
+ return false;
+ }
+ return true;
+}
+
+/*FUNCTION****************************************************************
+*
+* Function Name : MMA8451Q_ReadData
+* Returned Value : true or false
+* Comments : Get current acceleration from MMA8451Q.
+*
+*END*********************************************************************/
+bool MMA8451Q_ReadData(int16_t *x, int16_t *y, int16_t *z)
+{
+ uint8_t rxBuffer[7];
+ uint8_t cmdBuffer[3];
+
+ cmdBuffer[0] = BOARD_I2C_MMA8451Q_ADDR << 1;
+ cmdBuffer[1] = MMA8451Q_OUT_X_MSB;
+ cmdBuffer[2] = (BOARD_I2C_MMA8451Q_ADDR << 1) + 1;
+ if (!I2C_XFER_ReceiveDataBlocking(cmdBuffer, 3, rxBuffer, 7))
+ return false;
+
+ *x = ((rxBuffer[0] << 8) & 0xff00) | rxBuffer[1];
+ *y = ((rxBuffer[2] << 8) & 0xff00) | rxBuffer[3];
+ *z = ((rxBuffer[4] << 8) & 0xff00) | rxBuffer[5];
+ *x = (int16_t)(*x) >> 2;
+ *y = (int16_t)(*y) >> 2;
+ *z = (int16_t)(*z) >> 2;
+
+ if(mma8451qMode == mma8451qMode_4G)
+ {
+ (*x) = (*x) << 1;
+ (*y) = (*y) << 1;
+ (*z) = (*z) << 1;
+ }
+ else if(mma8451qMode == mma8451qMode_8G)
+ {
+ (*x) = (*x) << 2;
+ (*y) = (*y) << 2;
+ (*z) = (*z) << 2;
+ }
+
+ return true;
+}
+
+ /*FUNCTION****************************************************************
+*
+* Function Name : MMA8451Q_ChangeMode
+* Returned Value : true or false
+* Comments : Change the current mode.
+*
+*END*********************************************************************/
+bool MMA8451Q_ChangeMode(uint8_t mode)
+{
+ uint8_t txBuffer;
+ uint8_t cmdBuffer[2];
+
+ cmdBuffer[0] = BOARD_I2C_MMA8451Q_ADDR << 1;
+ cmdBuffer[1] = MMA8451Q_XYZ_DATA_CFG;
+ txBuffer = mode;
+ if (!I2C_XFER_SendDataBlocking(cmdBuffer, 2, &txBuffer, 1))
+ return false;
+ return true;
+}
+
+/*******************************************************************************
+ * EOF
+ ******************************************************************************/
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/mma8451q.h b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/mma8451q.h
new file mode 100644
index 0000000..b371bbd
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/mma8451q.h
@@ -0,0 +1,113 @@
+/*
+ * Copyright (c) 2015, 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.
+ */
+
+#ifndef __MMA8451Q_H__
+#define __MMA8451Q_H__
+
+#include <stdint.h>
+#include <stdbool.h>
+
+/* I2C Slave Address define */
+#define MMA8451Q_ADDRESS_0 (0x1C) /* SA0 = 0, low logic */
+#define MMA8451Q_ADDRESS_1 (0x1D) /* SA0 = 1, high logic */
+
+/* MMA8451Q device ID number */
+#define MMA8451Q_DEVICE_ID (0x1A)
+
+/* MMA8451Q Registers address definition */
+#define MMA8451Q_STATUS (0x00)
+#define MMA8451Q_OUT_X_MSB (0x01)
+#define MMA8451Q_OUT_X_LSB (0x02)
+#define MMA8451Q_OUT_Y_MSB (0x03)
+#define MMA8451Q_OUT_Y_LSB (0x04)
+#define MMA8451Q_OUT_Z_MSB (0x05)
+#define MMA8451Q_OUT_Z_LSB (0x06)
+#define MMA8451Q_F_SETUP (0x09)
+#define MMA8451Q_TRIG_CFG (0x0A)
+#define MMA8451Q_SYSMOD (0x0B)
+#define MMA8451Q_INT_SOURCE (0x0C)
+#define MMA8451Q_WHO_AM_I (0x0D)
+#define MMA8451Q_XYZ_DATA_CFG (0x0E)
+#define MMA8451Q_HP_FILTER_CUTOFF (0x0F)
+#define MMA8451Q_PL_STATUS (0x10)
+#define MMA8451Q_PL_CFG (0x11)
+#define MMA8451Q_PL_COUNT (0x12)
+#define MMA8451Q_PL_BF_ZCOMP (0x13)
+#define MMA8451Q_PL_THS_REG (0x14)
+#define MMA8451Q_FF_MT_CFG (0x15)
+#define MMA8451Q_FF_MT_SRC (0x16)
+#define MMA8451Q_FF_MT_THS (0x17)
+#define MMA8451Q_FF_MT_COUNT (0x18)
+#define MMA8451Q_TRANSIENT_CFG (0x1D)
+#define MMA8451Q_TRANSIENT_SRC (0x1E)
+#define MMA8451Q_TRANSIENT_THS (0x1F)
+#define MMA8451Q_TRANSIENT_COUNT (0x20)
+#define MMA8451Q_PULSE_CFG (0x21)
+#define MMA8451Q_PULSE_SRC (0x22)
+#define MMA8451Q_PULSE_THSX (0x23)
+#define MMA8451Q_PULSE_THSY (0x24)
+#define MMA8451Q_PULSE_THSZ (0x25)
+#define MMA8451Q_PULSE_TMLT (0x26)
+#define MMA8451Q_PULSE_LTCY (0x27)
+#define MMA8451Q_PULSE_WIND (0x28)
+#define MMA8451Q_ASLP_COUNT (0x29)
+#define MMA8451Q_CTRL_REG1 (0x2A)
+#define MMA8451Q_CTRL_REG2 (0x2B)
+#define MMA8451Q_CTRL_REG3 (0x2C)
+#define MMA8451Q_CTRL_REG4 (0x2D)
+#define MMA8451Q_CTRL_REG5 (0x2E)
+#define MMA8451Q_OFF_X (0x2F)
+#define MMA8451Q_OFF_Y (0x30)
+#define MMA8451Q_OFF_Z (0x31)
+
+enum _mma8451q_mode
+{
+ mma8451qMode_2G = 0U,
+ mma8451qMode_4G = 1U,
+ mma8451qMode_8G = 2U
+};
+
+/* Function prototypes */
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+bool MMA8451Q_Init(void);
+bool MMA8451Q_ReadData(int16_t *x, int16_t *y, int16_t *z);
+bool MMA8451Q_ChangeMode(uint8_t mode);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __MMA8451Q_H__ */
+/*******************************************************************************
+ * EOF
+ ******************************************************************************/
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/mpl3115.c b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/mpl3115.c
new file mode 100644
index 0000000..f5dcddb
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/mpl3115.c
@@ -0,0 +1,112 @@
+/*
+ * Copyright (c) 2015, 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 "board.h"
+#include "i2c_xfer.h"
+#include "mpl3115.h"
+
+#define MPL3115_MPERCOUNT 0.0000152587890625F // 1/65536 fixed range for MPL3115
+#define MPL3115_CPERCPOUNT 0.00390625F // 1/256 fixed range for MPL3115
+
+/*FUNCTION****************************************************************
+*
+* Function Name : mpl3115_init
+* Returned Value : result
+* Comments : Initialize MPL3115 pressure and temperature sensor.
+*
+*END*********************************************************************/
+bool mpl3115_init(pressure_sensor_t* pThisPressure)
+{
+ uint8_t txBuffer;
+ uint8_t cmdBuffer[2];
+
+ pThisPressure->fmPerCount = MPL3115_MPERCOUNT;
+ pThisPressure->fCPerCount = MPL3115_CPERCPOUNT;
+
+ /* Place the MPL3115 in Standby */
+ cmdBuffer[0] = MPL3115_ADDRESS << 1;
+ cmdBuffer[1] = MPL3115_CTRL_REG1;
+ txBuffer = 0x00;
+ if (!I2C_XFER_SendDataBlocking(cmdBuffer, 2, &txBuffer, 1))
+ return false;
+
+ /* Enable Data Flags in PT_DATA_CFG */
+ cmdBuffer[0] = MPL3115_ADDRESS << 1;
+ cmdBuffer[1] = MPL3115_PT_DATA_CFG;
+ txBuffer = 0x07;
+ if (!I2C_XFER_SendDataBlocking(cmdBuffer, 2, &txBuffer, 1))
+ return false;
+
+ // write 1011 1001 = 0xB9 to configure MPL3115 and enter Active mode
+ // [7]: ALT=1 for altitude measurements
+ // [6]: RAW=0 to disable raw measurements
+ // [5-3]: OS=111 for OS ratio=128 for maximum internal averaging with 512ms output interval
+ // [2]: RST=0 do not enter reset
+ // [1]: OST=0 do not initiate a reading
+ // [0]: SBYB=1 to enter active mode
+ cmdBuffer[0] = MPL3115_ADDRESS << 1;
+ cmdBuffer[1] = MPL3115_CTRL_REG1;
+ txBuffer = 0xB9;
+ if (!I2C_XFER_SendDataBlocking(cmdBuffer, 2, &txBuffer, 1))
+ return false;
+
+ return true;
+}
+
+/*FUNCTION****************************************************************
+*
+* Function Name : mpl3115_read_data
+* Returned Value : result
+* Comments : Get current height and temperature from mpl3115.
+*
+*END*********************************************************************/
+bool mpl3115_read_data(pressure_sensor_t* pThisPressure)
+{
+ uint8_t rxBuffer[5];
+ uint8_t cmdBuffer[3];
+
+ cmdBuffer[0] = MPL3115_ADDRESS << 1;
+ cmdBuffer[1] = MPL3115_OUT_P_MSB;
+ cmdBuffer[2] = (MPL3115_ADDRESS << 1) + 1;
+ if (!I2C_XFER_ReceiveDataBlocking(cmdBuffer, 3, rxBuffer, 5))
+ return false;
+
+ // place the read buffer into the 32 bit altitude and 16 bit temperature
+ pThisPressure->iHpFast = (rxBuffer[0] << 24) | (rxBuffer[1] << 16) | (rxBuffer[2] << 8);
+ pThisPressure->iTpFast = (rxBuffer[3] << 8) | rxBuffer[4];
+
+ return true;
+}
+
+/*******************************************************************************
+ * EOF
+ ******************************************************************************/
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/mpl3115.h b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/mpl3115.h
new file mode 100644
index 0000000..7606e7b
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/common/mpl3115.h
@@ -0,0 +1,118 @@
+/*
+ * Copyright (c) 2015, 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.
+ */
+
+#ifndef __MPL3115_H__
+#define __MPL3115_H__
+
+#include <stdint.h>
+#include <stdbool.h>
+
+/* I2C Slave Address define */
+#define MPL3115_ADDRESS (0x60)
+
+/* MPL3115 device ID number */
+#define MPL3115_DEVICE_ID (0xC4)
+
+/* MPL3115 Registers address definition */
+#define MPL3115_STATUS (0x00)
+#define MPL3115_OUT_P_MSB (0x01)
+#define MPL3115_OUT_P_CSB (0x02)
+#define MPL3115_OUT_P_LSB (0x03)
+#define MPL3115_OUT_T_MSB (0x04)
+#define MPL3115_OUT_T_LSB (0x05)
+#define MPL3115_DR_STATUS (0x06)
+#define MPL3115_OUT_P_DELTA_MSB (0x07)
+#define MPL3115_OUT_P_DELTA_CSB (0x08)
+#define MPL3115_OUT_P_DELTA_LSB (0x09)
+#define MPL3115_OUT_T_DELTA_MSB (0x0A)
+#define MPL3115_OUT_T_DELTA_LSB (0x0B)
+#define MPL3115_WHO_AM_I (0x0C)
+#define MPL3115_F_STATUS (0x0D)
+#define MPL3115_F_DATA (0x0E)
+#define MPL3115_F_SETUP (0x0F)
+#define MPL3115_TIME_DLY (0x10)
+#define MPL3115_SYSMOD (0x11)
+#define MPL3115_INT_SOURCE (0x12)
+#define MPL3115_PT_DATA_CFG (0x13)
+#define MPL3115_BAR_IN_MSB (0x14)
+#define MPL3115_BAR_IN_LSB (0x15)
+#define MPL3115_P_TGT_MSB (0x16)
+#define MPL3115_P_TGT_LSB (0x17)
+#define MPL3115_T_TGT (0x18)
+#define MPL3115_P_WND_MSB (0x19)
+#define MPL3115_P_WND_LSB (0x1A)
+#define MPL3115_T_WND (0x1B)
+#define MPL3115_P_MIN_MSB (0x1C)
+#define MPL3115_P_MIN_CSB (0x1D)
+#define MPL3115_P_MIN_LSB (0x1E)
+#define MPL3115_T_MIN_MSB (0x1F)
+#define MPL3115_T_MIN_LSB (0x20)
+#define MPL3115_P_MAX_MSB (0x21)
+#define MPL3115_P_MAX_CSB (0x22)
+#define MPL3115_P_MAX_LSB (0x23)
+#define MPL3115_T_MAX_MSB (0x24)
+#define MPL3115_T_MAX_LSB (0x25)
+#define MPL3115_CTRL_REG1 (0x26)
+#define MPL3115_CTRL_REG2 (0x27)
+#define MPL3115_CTRL_REG3 (0x28)
+#define MPL3115_CTRL_REG4 (0x29)
+#define MPL3115_CTRL_REG5 (0x2A)
+#define MPL3115_OFF_P (0x2B)
+#define MPL3115_OFF_T (0x2C)
+#define MPL3115_OFF_H (0x2D)
+
+typedef struct _pressure_sensor
+{
+ int32_t iHp; // slow (typically 25Hz) height (counts)
+ int32_t iHpFast; // fast (typically 200Hz) height (counts)
+ int16_t iTp; // slow (typically 25Hz) temperature (count)
+ int16_t iTpFast; // fast (typically 200Hz) temperature (counts)
+ float fHp; // slow (typically 25Hz) height (m)
+ float fTp; // slow (typically 25Hz) temperature (C)
+ float fmPerCount; // initialized to FMPERCOUNT
+ float fCPerCount; // initialized to FCPERCPOUNT
+} pressure_sensor_t;
+
+/* Function prototypes */
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+bool mpl3115_init(pressure_sensor_t*);
+bool mpl3115_read_data(pressure_sensor_t*);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __MPL3115_H__ */
+/*******************************************************************************
+ * EOF
+ ******************************************************************************/
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/ds5/.cproject b/examples/imx7_colibri_m4/demo_apps/sensor_demo/ds5/.cproject
new file mode 100644
index 0000000..24a8553
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/ds5/.cproject
@@ -0,0 +1,137 @@
+<?xml version="1.0" encoding="UTF-8" standalone="no"?>
+<?fileVersion 4.0.0?>
+<cproject storage_type_id="org.eclipse.cdt.core.XmlProjectDescriptionStorage">
+ <storageModule moduleId="org.eclipse.cdt.core.settings">
+ <cconfiguration id="com.arm.eclipse.build.config.baremetal.exe.debug.893051445.1002809623">
+ <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="com.arm.eclipse.build.config.baremetal.exe.debug.893051445.1002809623" moduleId="org.eclipse.cdt.core.settings" name="Int Ram Debug">
+ <externalSettings/>
+ <extensions>
+ <extension id="com.arm.eclipse.builder.armcc.error" point="org.eclipse.cdt.core.ErrorParser"/>
+ </extensions>
+ </storageModule>
+ <storageModule moduleId="cdtBuildSystem" version="4.0.0">
+ <configuration artifactExtension="axf" artifactName="${ProjName}" buildArtefactType="com.arm.eclipse.build.artefact.baremetal.exe" buildProperties="org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.debug,org.eclipse.cdt.build.core.buildArtefactType=com.arm.eclipse.build.artefact.baremetal.exe" cleanCommand="clean" description="" id="com.arm.eclipse.build.config.baremetal.exe.debug.893051445.1002809623" name="Int Ram Debug" parent="com.arm.eclipse.build.config.baremetal.exe.debug">
+ <folderInfo id="com.arm.eclipse.build.config.baremetal.exe.debug.893051445.1002809623." name="/" resourcePath="">
+ <toolChain errorParsers="com.arm.eclipse.builder.armcc.error" id="com.arm.toolchain.baremetal.exe.debug.505048968" name="ARM Compiler" nonInternalBuilderId="com.arm.toolchain.baremetal.builder" superClass="com.arm.toolchain.baremetal.exe.debug">
+ <targetPlatform binaryParser="" id="com.arm.toolchain.baremetal.exe.debug.505048968.350348883" name=""/>
+ <builder autoBuildTarget="all" buildPath="${workspace_loc:/app/Int Ram Debug}" cleanBuildTarget="clean" id="org.eclipse.cdt.build.core.internal.builder.38020294" incrementalBuildTarget="all" keepEnvironmentInBuildfile="false" managedBuildOn="true" name="CDT Internal Builder" superClass="org.eclipse.cdt.build.core.internal.builder"/>
+ <tool command="armcc" commandLinePattern="${COMMAND} ${FLAGS} ${OUTPUT_FLAG} ${OUTPUT_PREFIX}${OUTPUT} ${INPUTS}" errorParsers="" id="com.arm.tool.c.compiler.baremetal.exe.debug.1725848509" name="ARM C Compiler" superClass="com.arm.tool.c.compiler.baremetal.exe.debug">
+ <option id="com.arm.tool.c.compiler.option.incpath.349366493" name="Include path (-I)" superClass="com.arm.tool.c.compiler.option.incpath"><listOptionValue builtIn="false" value="${ProjDirPath}/../../../../../platform/CMSIS/Include"/><listOptionValue builtIn="false" value="${ProjDirPath}/../../../../../platform/devices"/><listOptionValue builtIn="false" value="${ProjDirPath}/../../../../../platform/devices/MCIMX7D/include"/><listOptionValue builtIn="false" value="${ProjDirPath}/../../../../../platform/devices/MCIMX7D/startup"/><listOptionValue builtIn="false" value="${ProjDirPath}/../../../../../platform/drivers/inc"/><listOptionValue builtIn="false" value="${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/portable/RVDS/ARM_CM4F"/><listOptionValue builtIn="false" value="${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/include"/><listOptionValue builtIn="false" value="${ProjDirPath}/../../../../../platform/utilities/inc"/><listOptionValue builtIn="false" value="${ProjDirPath}/../../.."/><listOptionValue builtIn="false" value="${ProjDirPath}/../common"/></option>
+ <option id="com.arm.tool.c.compiler.option.defmac.1627388367" name="Define macro (-D)" superClass="com.arm.tool.c.compiler.option.defmac"><listOptionValue builtIn="false" value="__DEBUG"/><listOptionValue builtIn="false" value="CPU_IMX7D_M4"/><listOptionValue builtIn="false" value="PRINTF_FLOAT_ENABLE"/></option>
+ <option id="com.arm.tool.c.compiler.option.targetcpu.1309268616" name="Target CPU (--cpu)" superClass="com.arm.tool.c.compiler.option.targetcpu" value="Cortex-M4" valueType="string"/>
+ <option id="com.arm.tool.c.compiler.option.targetfpu.1098489790" name="Target FPU (--fpu)" superClass="com.arm.tool.c.compiler.option.targetfpu" value="FPv4-SP" valueType="string"/>
+ <option id="com.arm.tool.c.compiler.option.fpmode.1539082142" name="Floating-point mode (--fpmode)" superClass="com.arm.tool.c.compiler.option.fpmode" value="com.arm.tool.c.compiler.option.fpmode.default" valueType="enumerated"/>
+ <option id="com.arm.tool.c.compiler.option.fppcs.928968199" name="Floating-point PCS (--apcs)" superClass="com.arm.tool.c.compiler.option.fppcs" value="com.arm.tool.c.compiler.option.fppcs.auto" valueType="enumerated"/>
+ <option id="com.arm.tool.c.compiler.option.flags.49715708" name="Other flags" superClass="com.arm.tool.c.compiler.option.flags" value="--c99 --split_sections " valueType="string"/>
+ <option id="com.arm.tool.c.compiler.options.debug.enabled.652416105" name="Enable debug (-g)" superClass="com.arm.tool.c.compiler.options.debug.enabled" value="true" valueType="boolean"/>
+ <option id="com.arm.tool.assembler.option.preproc.664063762" name="Preprocess input before assembling (--cpreproc)" superClass="com.arm.tool.assembler.option.preproc" value="false" valueType="boolean"/>
+ <option id="com.arm.tool.c.compiler.option.endian.2486374826" name="Byte order" superClass="com.arm.tool.c.compiler.option.endian" value="com.arm.tool.c.compiler.option.endian.auto" valueType="enumerated"/>
+ <inputType id="com.arm.tool.c.compiler.input.1814530651" superClass="com.arm.tool.c.compiler.input"/>
+ <inputType id="com.arm.tool.cpp.compiler.input.988841684" superClass="com.arm.tool.cpp.compiler.input"/>
+ <option id="com.arm.tool.c.compiler.option.gnu.3497485844" superClass="com.arm.tool.c.compiler.option.gnu" valueType="boolean" value="true"/><option id="com.arm.tool.c.compiler.option.charsize.5506194745" superClass="com.arm.tool.c.compiler.option.charsize" valueType="enumerated" value="com.arm.tool.c.compiler.option.enum.auto"/><option id="com.arm.tool.c.compiler.option.optfor.9639754755" superClass="com.arm.tool.c.compiler.option.optfor" valueType="enumerated" value="com.arm.tool.c.compiler.option.optfor.auto"/><option id="com.arm.tool.c.compile.option.lang.9745762701" superClass="com.arm.tool.c.compile.option.lang" valueType="enumerated" value="com.arm.tool.c.compile.option.lang.auto"/><option id="com.arm.tool.c.compiler.option.strict.8251997081" superClass="com.arm.tool.c.compiler.option.strict" valueType="enumerated" value="com.arm.tool.c.compiler.option.strict.auto"/><option id="com.arm.tool.c.compiler.option.suppress.455818764" superClass="com.arm.tool.c.compiler.option.suppress" valueType="string" value="1296,66"/><option id="com.arm.tool.c.compiler.options.debug.format.5225990344" superClass="com.arm.tool.c.compiler.options.debug.format" valueType="enumerated" value="com.arm.tool.c.compiler.options.debug.format.auto"/><option id="com.arm.tool.c.compiler.option.inst.6457195183" superClass="com.arm.tool.c.compiler.option.inst" valueType="enumerated" value="com.arm.tool.c.compiler.option.inst.auto"/><option id="com.arm.tool.c.compiler.option.inter.2967151367" superClass="com.arm.tool.c.compiler.option.inter" valueType="boolean" value="false"/><option id="com.arm.tool.c.compiler.option.unalign.4694748102" superClass="com.arm.tool.c.compiler.option.unalign" valueType="boolean" value="false"/><option id="com.arm.tool.c.compiler.option.vector.4771139837" superClass="com.arm.tool.c.compiler.option.vector" valueType="boolean" value="false"/><option id="com.arm.tool.c.compiler.option.enum.7111008498" superClass="com.arm.tool.c.compiler.option.enum" valueType="boolean" value="false"/><option id="com.arm.tool.c.compiler.option.suppresswarn.6887703325" superClass="com.arm.tool.c.compiler.option.suppresswarn" valueType="boolean" value="false"/><option id="com.arm.tool.c.compiler.option.warnaserr.496762710" superClass="com.arm.tool.c.compiler.option.warnaserr" valueType="boolean" value="false"/><option id="com.arm.tool.c.compiler.option.enablerem.1472955508" superClass="com.arm.tool.c.compiler.option.enablerem" valueType="boolean" value="false"/></tool>
+ <tool id="com.arm.tool.cpp.compiler.baremetal.exe.debug.1769458477" name="ARM C++ Compiler" superClass="com.arm.tool.cpp.compiler.baremetal.exe.debug">
+ <option id="com.arm.tool.c.compiler.option.flags.125692915" name="Other flags" superClass="com.arm.tool.c.compiler.option.flags" value="--c99 --split_sections " valueType="string"/>
+ </tool>
+ <tool command="armasm" commandLinePattern="${COMMAND} ${FLAGS} ${OUTPUT_FLAG} ${OUTPUT_PREFIX}${OUTPUT} ${INPUTS}" errorParsers="" id="com.arm.tool.assembler.1155958963" name="ARM Assembler" superClass="com.arm.tool.assembler">
+ <option id="com.arm.tool.assembler.option.cpu.423475341" name="Target CPU (--cpu)" superClass="com.arm.tool.assembler.option.cpu" value="Cortex-M4" valueType="string"/>
+ <option id="com.arm.tool.assembler.option.fpu.560570852" name="Target FPU (--fpu)" superClass="com.arm.tool.assembler.option.fpu" value="FPv4-SP" valueType="string"/>
+ <option id="com.arm.tool.assembler.option.fpmode.2114797651" name="Floating-point mode (--fpmode)" superClass="com.arm.tool.assembler.option.fpmode" value="com.arm.tool.c.compiler.option.fpmode.default" valueType="enumerated"/>
+ <option id="com.arm.tool.assembler.option.fppcs.2043711002" name="Floating-point PCS (--apcs)" superClass="com.arm.tool.assembler.option.fppcs" value="com.arm.tool.c.compiler.option.fppcs.auto" valueType="enumerated"/>
+ <option id="com.arm.tool.assembler.option.flags.2068342579" name="Other flags" superClass="com.arm.tool.assembler.option.flags" value="-I&quot;${ProjDirPath}/../../..&quot; " valueType="string"/>
+ <option id="com.arm.tool.assembler.option.preproc.664063762" name="Preprocess input before assembling (--cpreproc)" superClass="com.arm.tool.assembler.option.preproc" value="true" valueType="boolean"/>
+ <option id="com.arm.tool.assembler.option.preprocflags.5151740646" superClass="com.arm.tool.assembler.option.preprocflags" valueType="string" value="-D__DEBUG"/><option id="com.arm.tool.assembler.option.unalign.376527144" superClass="com.arm.tool.assembler.option.unalign" valueType="boolean" value="false"/><option id="com.arm.tool.assembler.option.inter.7483413829" superClass="com.arm.tool.assembler.option.inter" valueType="boolean" value="false"/><option id="com.arm.tool.assembler.option.inst.1990722997" superClass="com.arm.tool.assembler.option.inst" valueType="enumerated" value="com.arm.tool.c.compiler.option.inst.auto"/><option id="com.arm.tool.assembler.option.endian.4848227715" superClass="com.arm.tool.assembler.option.endian" valueType="enumerated" value="com.arm.tool.c.compiler.option.endian.little"/><option id="com.arm.tool.assembler.option.debug.format.4612366819" superClass="com.arm.tool.assembler.option.debug.format" valueType="enumerated" value="com.arm.tool.c.compiler.options.debug.format.auto"/><option id="com.arm.tool.assembler.option.sup.5604051428" superClass="com.arm.tool.assembler.option.sup" valueType="string" value="1296,66"/></tool>
+ <tool command="armlink" commandLinePattern="${COMMAND} ${FLAGS} ${OUTPUT_FLAG} ${OUTPUT_PREFIX}${OUTPUT} ${INPUTS}" errorParsers="" id="com.arm.tool.c.linker.1088675316" name="ARM Linker" superClass="com.arm.tool.c.linker">
+ <option id="com.arm.tool.c.linker.option.cpu.267638742" name="Target CPU (--cpu)" superClass="com.arm.tool.c.linker.option.cpu" value="Cortex-M4" valueType="string"/>
+ <option id="com.arm.tool.c.linker.option.scatter.1868789905" name="Scatter file (--scatter)" superClass="com.arm.tool.c.linker.option.scatter" value="${ProjDirPath}/../../../../../platform/devices/MCIMX7D/linker/arm/MCIMX7D_M4_tcm.scf" valueType="string"/>
+ <option id="com.arm.tool.c.linker.option.libs.1325797835" name="Libraries (--library)" superClass="com.arm.tool.c.linker.option.libs"/>
+ <option id="com.arm.tool.c.linker.option.libsearch.1542315655" name="Library search path (--userlibpath)" superClass="com.arm.tool.c.linker.option.libsearch"/>
+ <option id="com.arm.tool.c.linker.libs.491659161" name="Other library files" superClass="com.arm.tool.c.linker.libs"/>
+ <option id="com.arm.tool.c.linker.option.entry.1665317816" name="Image entry point (--entry)" superClass="com.arm.tool.c.linker.option.entry" value="Reset_Handler" valueType="string"/>
+ <option id="com.arm.tool.c.linker.option.imagemap.909474066" name="Generate image map (--map)" superClass="com.arm.tool.c.linker.option.imagemap" value="false" valueType="boolean"/>
+ <option id="com.arm.tool.c.linker.option.syslibs.948170747" name="Standard library search path (--libpath)" superClass="com.arm.tool.c.linker.option.syslibs"/>
+
+ <inputType id="com.arm.tool.c.linker.input.334720080" superClass="com.arm.tool.c.linker.input">
+ <additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
+ <additionalInput kind="additionalinput" paths="$(LIBS)"/>
+ </inputType>
+ <option id="com.arm.tool.c.linker.option.fpu.8785877687" superClass="com.arm.tool.c.linker.option.fpu" valueType="string" value="FPv4-SP"/><option id="com.arm.tool.c.linker.option.sizes.9662900755" superClass="com.arm.tool.c.linker.option.sizes" valueType="boolean" value="false"/><option id="com.arm.tool.c.linker.option.totals.6146471485" superClass="com.arm.tool.c.linker.option.totals" valueType="boolean" value="false"/><option id="com.arm.tool.c.linker.option.compress.7753240059" superClass="com.arm.tool.c.linker.option.compress" valueType="boolean" value="false"/><option id="com.arm.tool.c.linker.option.stack.7244409760" superClass="com.arm.tool.c.linker.option.stack" valueType="boolean" value="false"/><option id="com.arm.tool.c.linker.option.inlineinfo.4830718063" superClass="com.arm.tool.c.linker.option.inlineinfo" valueType="boolean" value="false"/><option id="com.arm.tool.c.linker.option.elim.4010497074" superClass="com.arm.tool.c.linker.option.elim" valueType="boolean" value="false"/></tool>
+ <tool id="com.arm.tool.librarian.109887334" name="ARM Librarian" superClass="com.arm.tool.librarian"/>
+ </toolChain>
+ </folderInfo>
+ </configuration>
+ </storageModule>
+ <storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
+ </cconfiguration>
+ <cconfiguration id="com.arm.eclipse.build.config.baremetal.exe.debug.2022285397.1552618666">
+ <storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="com.arm.eclipse.build.config.baremetal.exe.debug.2022285397.1552618666" moduleId="org.eclipse.cdt.core.settings" name="Int Ram Release">
+ <externalSettings/>
+ <extensions>
+ <extension id="com.arm.eclipse.builder.armcc.error" point="org.eclipse.cdt.core.ErrorParser"/>
+ </extensions>
+ </storageModule>
+ <storageModule moduleId="cdtBuildSystem" version="4.0.0">
+ <configuration artifactExtension="axf" artifactName="${ProjName}" buildArtefactType="com.arm.eclipse.build.artefact.baremetal.exe" buildProperties="org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.debug,org.eclipse.cdt.build.core.buildArtefactType=com.arm.eclipse.build.artefact.baremetal.exe" cleanCommand="clean" description="" id="com.arm.eclipse.build.config.baremetal.exe.debug.2022285397.1552618666" name="Int Ram Release" parent="com.arm.eclipse.build.config.baremetal.exe.debug">
+ <folderInfo id="com.arm.eclipse.build.config.baremetal.exe.debug.2022285397.1552618666." name="/" resourcePath="">
+ <toolChain id="com.arm.toolchain.baremetal.exe.debug.1871020344" name="ARM Compiler" nonInternalBuilderId="com.arm.toolchain.baremetal.builder" superClass="com.arm.toolchain.baremetal.exe.debug">
+ <targetPlatform id="com.arm.toolchain.baremetal.exe.debug.1871020344.229212655" name=""/>
+ <builder autoBuildTarget="all" buildPath="${workspace_loc:/app/Int Ram Release}" cleanBuildTarget="clean" id="org.eclipse.cdt.build.core.internal.builder.1172218807" incrementalBuildTarget="all" keepEnvironmentInBuildfile="false" managedBuildOn="true" name="CDT Internal Builder" superClass="org.eclipse.cdt.build.core.internal.builder"/>
+ <tool id="com.arm.tool.c.compiler.baremetal.exe.debug.724686906" name="ARM C Compiler" superClass="com.arm.tool.c.compiler.baremetal.exe.debug">
+ <option id="com.arm.tool.c.compiler.option.incpath.2126170575" name="Include path (-I)" superClass="com.arm.tool.c.compiler.option.incpath"><listOptionValue builtIn="false" value="${ProjDirPath}/../../../../../platform/CMSIS/Include"/><listOptionValue builtIn="false" value="${ProjDirPath}/../../../../../platform/devices"/><listOptionValue builtIn="false" value="${ProjDirPath}/../../../../../platform/devices/MCIMX7D/include"/><listOptionValue builtIn="false" value="${ProjDirPath}/../../../../../platform/devices/MCIMX7D/startup"/><listOptionValue builtIn="false" value="${ProjDirPath}/../../../../../platform/drivers/inc"/><listOptionValue builtIn="false" value="${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/portable/RVDS/ARM_CM4F"/><listOptionValue builtIn="false" value="${ProjDirPath}/../../../../../rtos/FreeRTOS/Source/include"/><listOptionValue builtIn="false" value="${ProjDirPath}/../../../../../platform/utilities/inc"/><listOptionValue builtIn="false" value="${ProjDirPath}/../../.."/><listOptionValue builtIn="false" value="${ProjDirPath}/../common"/></option>
+ <option id="com.arm.tool.c.compiler.option.defmac.741292309" name="Define macro (-D)" superClass="com.arm.tool.c.compiler.option.defmac"><listOptionValue builtIn="false" value="__NDEBUG"/><listOptionValue builtIn="false" value="CPU_IMX7D_M4"/><listOptionValue builtIn="false" value="PRINTF_FLOAT_ENABLE"/></option>
+ <option id="com.arm.tool.c.compiler.option.targetcpu.499083253" name="Target CPU (--cpu)" superClass="com.arm.tool.c.compiler.option.targetcpu" value="Cortex-M4" valueType="string"/>
+ <option id="com.arm.tool.c.compiler.option.targetfpu.747092604" name="Target FPU (--fpu)" superClass="com.arm.tool.c.compiler.option.targetfpu" value="FPv4-SP" valueType="string"/>
+ <option id="com.arm.tool.c.compiler.option.fpmode.885590841" name="Floating-point mode (--fpmode)" superClass="com.arm.tool.c.compiler.option.fpmode" value="com.arm.tool.c.compiler.option.fpmode.default" valueType="enumerated"/>
+ <option id="com.arm.tool.c.compiler.option.fppcs.1131381472" name="Floating-point PCS (--apcs)" superClass="com.arm.tool.c.compiler.option.fppcs" value="com.arm.tool.c.compiler.option.fppcs.auto" valueType="enumerated"/>
+ <option id="com.arm.tool.c.compiler.baremetal.exe.debug.option.opt.445197165" name="Optimization level" superClass="com.arm.tool.c.compiler.baremetal.exe.debug.option.opt" value="com.arm.tool.c.compiler.option.optlevel.max" valueType="enumerated"/>
+ <option id="com.arm.tool.c.compiler.option.flags.1769123778" name="Other flags" superClass="com.arm.tool.c.compiler.option.flags" value="--c99 --split_sections " valueType="string"/>
+ <inputType id="com.arm.tool.c.compiler.input.1270990193" superClass="com.arm.tool.c.compiler.input"/>
+ <inputType id="com.arm.tool.cpp.compiler.input.840085126" superClass="com.arm.tool.cpp.compiler.input"/>
+ <option id="com.arm.tool.c.compiler.option.gnu.4876189873" superClass="com.arm.tool.c.compiler.option.gnu" valueType="boolean" value="true"/><option id="com.arm.tool.c.compiler.option.charsize.349859668" superClass="com.arm.tool.c.compiler.option.charsize" valueType="enumerated" value="com.arm.tool.c.compiler.option.enum.auto"/><option id="com.arm.tool.c.compiler.option.optfor.4826775941" superClass="com.arm.tool.c.compiler.option.optfor" valueType="enumerated" value="com.arm.tool.c.compiler.option.optfor.auto"/><option id="com.arm.tool.c.compile.option.lang.1279477349" superClass="com.arm.tool.c.compile.option.lang" valueType="enumerated" value="com.arm.tool.c.compile.option.lang.auto"/><option id="com.arm.tool.c.compiler.option.strict.1080707203" superClass="com.arm.tool.c.compiler.option.strict" valueType="enumerated" value="com.arm.tool.c.compiler.option.strict.auto"/><option id="com.arm.tool.c.compiler.options.debug.enabled.6124952578" superClass="com.arm.tool.c.compiler.options.debug.enabled" valueType="boolean" value="true"/><option id="com.arm.tool.c.compiler.option.suppress.1252393965" superClass="com.arm.tool.c.compiler.option.suppress" valueType="string" value="1296,66"/><option id="com.arm.tool.c.compiler.options.debug.format.9949416662" superClass="com.arm.tool.c.compiler.options.debug.format" valueType="enumerated" value="com.arm.tool.c.compiler.options.debug.format.auto"/><option id="com.arm.tool.c.compiler.option.inst.7894040800" superClass="com.arm.tool.c.compiler.option.inst" valueType="enumerated" value="com.arm.tool.c.compiler.option.inst.auto"/><option id="com.arm.tool.c.compiler.option.endian.8380841049" superClass="com.arm.tool.c.compiler.option.endian" valueType="enumerated" value="com.arm.tool.c.compiler.option.endian.auto"/><option id="com.arm.tool.c.compiler.option.inter.3709057348" superClass="com.arm.tool.c.compiler.option.inter" valueType="boolean" value="false"/><option id="com.arm.tool.c.compiler.option.unalign.8498318600" superClass="com.arm.tool.c.compiler.option.unalign" valueType="boolean" value="false"/><option id="com.arm.tool.c.compiler.option.vector.8459945549" superClass="com.arm.tool.c.compiler.option.vector" valueType="boolean" value="false"/><option id="com.arm.tool.c.compiler.option.enum.1422362622" superClass="com.arm.tool.c.compiler.option.enum" valueType="boolean" value="false"/><option id="com.arm.tool.c.compiler.option.suppresswarn.458753387" superClass="com.arm.tool.c.compiler.option.suppresswarn" valueType="boolean" value="false"/><option id="com.arm.tool.c.compiler.option.warnaserr.2383048496" superClass="com.arm.tool.c.compiler.option.warnaserr" valueType="boolean" value="false"/><option id="com.arm.tool.c.compiler.option.enablerem.8133219091" superClass="com.arm.tool.c.compiler.option.enablerem" valueType="boolean" value="false"/></tool>
+ <tool id="com.arm.tool.cpp.compiler.baremetal.exe.debug.1278927352" name="ARM C++ Compiler" superClass="com.arm.tool.cpp.compiler.baremetal.exe.debug">
+ <option id="com.arm.tool.c.compiler.option.flags.191883218" name="Other flags" superClass="com.arm.tool.c.compiler.option.flags" value="--c99 --split_sections " valueType="string"/>
+ </tool>
+ <tool id="com.arm.tool.assembler.782505281" name="ARM Assembler" superClass="com.arm.tool.assembler">
+ <option id="com.arm.tool.assembler.option.cpu.1791675215" name="Target CPU (--cpu)" superClass="com.arm.tool.assembler.option.cpu" value="Cortex-M4" valueType="string"/>
+ <option id="com.arm.tool.assembler.option.fpu.1669042968" name="Target FPU (--fpu)" superClass="com.arm.tool.assembler.option.fpu" value="FPv4-SP" valueType="string"/>
+ <option id="com.arm.tool.assembler.option.fpmode.150044025" name="Floating-point mode (--fpmode)" superClass="com.arm.tool.assembler.option.fpmode" value="com.arm.tool.c.compiler.option.fpmode.default" valueType="enumerated"/>
+ <option id="com.arm.tool.assembler.option.fppcs.1033303317" name="Floating-point PCS (--apcs)" superClass="com.arm.tool.assembler.option.fppcs" value="com.arm.tool.c.compiler.option.fppcs.auto" valueType="enumerated"/>
+ <option id="com.arm.tool.assembler.option.flags.1985199179" name="Other flags" superClass="com.arm.tool.assembler.option.flags" value="-I&quot;${ProjDirPath}/../../..&quot; " valueType="string"/>
+ <option id="com.arm.tool.assembler.option.preproc.664063763" name="Preprocess input before assembling (--cpreproc)" superClass="com.arm.tool.assembler.option.preproc" value="false" valueType="boolean"/>
+ <option id="com.arm.tool.assembler.option.preprocflags.6013192839" superClass="com.arm.tool.assembler.option.preprocflags" valueType="string" value=""/><option id="com.arm.tool.assembler.option.unalign.2721257917" superClass="com.arm.tool.assembler.option.unalign" valueType="boolean" value="false"/><option id="com.arm.tool.assembler.option.inter.6858114792" superClass="com.arm.tool.assembler.option.inter" valueType="boolean" value="false"/><option id="com.arm.tool.assembler.option.inst.1072509271" superClass="com.arm.tool.assembler.option.inst" valueType="enumerated" value="com.arm.tool.c.compiler.option.inst.auto"/><option id="com.arm.tool.assembler.option.endian.5168481165" superClass="com.arm.tool.assembler.option.endian" valueType="enumerated" value="com.arm.tool.c.compiler.option.endian.little"/><option id="com.arm.tool.assembler.option.debug.format.2205359837" superClass="com.arm.tool.assembler.option.debug.format" valueType="enumerated" value="com.arm.tool.c.compiler.options.debug.format.auto"/><option id="com.arm.tool.assembler.option.sup.1184070070" superClass="com.arm.tool.assembler.option.sup" valueType="string" value="1296,66"/></tool>
+ <tool id="com.arm.tool.c.linker.1301355868" name="ARM Linker" superClass="com.arm.tool.c.linker">
+ <option id="com.arm.tool.c.linker.option.cpu.522518248" name="Target CPU (--cpu)" superClass="com.arm.tool.c.linker.option.cpu" value="Cortex-M4" valueType="string"/>
+ <option id="com.arm.tool.c.linker.option.scatter.208008498" name="Scatter file (--scatter)" superClass="com.arm.tool.c.linker.option.scatter" value="${ProjDirPath}/../../../../../platform/devices/MCIMX7D/linker/arm/MCIMX7D_M4_tcm.scf" valueType="string"/>
+ <option id="com.arm.tool.c.linker.option.libs.1119897339" name="Libraries (--library)" superClass="com.arm.tool.c.linker.option.libs"/>
+ <option id="com.arm.tool.c.linker.option.libsearch.226638094" name="Library search path (--userlibpath)" superClass="com.arm.tool.c.linker.option.libsearch"/>
+ <option id="com.arm.tool.c.linker.libs.962860959" name="Other library files" superClass="com.arm.tool.c.linker.libs"/>
+ <option id="com.arm.tool.c.linker.option.entry.2139204104" name="Image entry point (--entry)" superClass="com.arm.tool.c.linker.option.entry" value="Reset_Handler" valueType="string"/>
+ <option id="com.arm.tool.c.linker.option.imagemap.754891612" name="Generate image map (--map)" superClass="com.arm.tool.c.linker.option.imagemap" value="false" valueType="boolean"/>
+ <option id="com.arm.tool.c.linker.option.syslibs.948170748" name="Standard library search path (--libpath)" superClass="com.arm.tool.c.linker.option.syslibs"/>
+
+ <inputType id="com.arm.tool.c.linker.input.2130990920" superClass="com.arm.tool.c.linker.input">
+ <additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
+ <additionalInput kind="additionalinput" paths="$(LIBS)"/>
+ </inputType>
+ <option id="com.arm.tool.c.linker.option.fpu.3626882584" superClass="com.arm.tool.c.linker.option.fpu" valueType="string" value="FPv4-SP"/><option id="com.arm.tool.c.linker.option.sizes.8348280916" superClass="com.arm.tool.c.linker.option.sizes" valueType="boolean" value="false"/><option id="com.arm.tool.c.linker.option.totals.7881691679" superClass="com.arm.tool.c.linker.option.totals" valueType="boolean" value="false"/><option id="com.arm.tool.c.linker.option.compress.175156943" superClass="com.arm.tool.c.linker.option.compress" valueType="boolean" value="false"/><option id="com.arm.tool.c.linker.option.stack.7489455492" superClass="com.arm.tool.c.linker.option.stack" valueType="boolean" value="false"/><option id="com.arm.tool.c.linker.option.inlineinfo.819258053" superClass="com.arm.tool.c.linker.option.inlineinfo" valueType="boolean" value="false"/><option id="com.arm.tool.c.linker.option.elim.3906842176" superClass="com.arm.tool.c.linker.option.elim" valueType="boolean" value="false"/></tool>
+ <tool id="com.arm.tool.librarian.2006874949" name="ARM Librarian" superClass="com.arm.tool.librarian"/>
+ </toolChain>
+ </folderInfo>
+ </configuration>
+ </storageModule>
+ <storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
+ </cconfiguration>
+ </storageModule>
+ <storageModule moduleId="cdtBuildSystem" version="4.0.0">
+ <project id="com.arm.eclipse.build.project.baremetal.exe.1023008919" name="Bare-metal Executable" projectType="com.arm.eclipse.build.project.baremetal.exe"/>
+ </storageModule>
+ <storageModule moduleId="scannerConfiguration">
+ <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
+ <scannerConfigBuildInfo instanceId="com.arm.eclipse.build.config.baremetal.exe.debug.893051445;com.arm.eclipse.build.config.baremetal.exe.debug.893051445.;com.arm.tool.c.compiler.baremetal.exe.debug.1501911384;com.arm.tool.c.compiler.input.905747706">
+ <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId="com.arm.eclipse.builder.armcc.ARMCompilerDiscoveryProfile"/>
+ </scannerConfigBuildInfo>
+ </storageModule>
+ <storageModule moduleId="refreshScope" versionNumber="1">
+ <resource resourceType="PROJECT" workspacePath="/app"/>
+ </storageModule>
+ <storageModule moduleId="org.eclipse.cdt.internal.ui.text.commentOwnerProjectMappings"/>
+</cproject>
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/ds5/.project b/examples/imx7_colibri_m4/demo_apps/sensor_demo/ds5/.project
new file mode 100644
index 0000000..858b6e0
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/ds5/.project
@@ -0,0 +1,86 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<projectDescription>
+ <name>sensor_demo_imx7d_sdb_m4</name>
+ <comment/>
+ <projects>
+ </projects>
+ <buildSpec>
+ <buildCommand>
+ <name>org.eclipse.cdt.managedbuilder.core.genmakebuilder</name>
+ <triggers>clean,full,incremental,</triggers>
+ <arguments>
+ <dictionary>
+ <key>?name?</key>
+ <value/>
+ </dictionary>
+ <dictionary>
+ <key>org.eclipse.cdt.make.core.append_environment</key>
+ <value>true</value>
+ </dictionary>
+ <dictionary>
+ <key>org.eclipse.cdt.make.core.autoBuildTarget</key>
+ <value>all</value>
+ </dictionary>
+ <dictionary>
+ <key>org.eclipse.cdt.make.core.buildArguments</key>
+ <value/>
+ </dictionary>
+ <dictionary>
+ <key>org.eclipse.cdt.make.core.buildCommand</key>
+ <value>make</value>
+ </dictionary>
+ <dictionary>
+ <key>org.eclipse.cdt.make.core.buildLocation</key>
+ <value/>
+ </dictionary>
+ <dictionary>
+ <key>org.eclipse.cdt.make.core.cleanBuildTarget</key>
+ <value>clean</value>
+ </dictionary>
+ <dictionary>
+ <key>org.eclipse.cdt.make.core.contents</key>
+ <value>org.eclipse.cdt.make.core.activeConfigSettings</value>
+ </dictionary>
+ <dictionary>
+ <key>org.eclipse.cdt.make.core.enableAutoBuild</key>
+ <value>false</value>
+ </dictionary>
+ <dictionary>
+ <key>org.eclipse.cdt.make.core.enableCleanBuild</key>
+ <value>true</value>
+ </dictionary>
+ <dictionary>
+ <key>org.eclipse.cdt.make.core.enableFullBuild</key>
+ <value>true</value>
+ </dictionary>
+ <dictionary>
+ <key>org.eclipse.cdt.make.core.fullBuildTarget</key>
+ <value>all</value>
+ </dictionary>
+ <dictionary>
+ <key>org.eclipse.cdt.make.core.stopOnError</key>
+ <value>true</value>
+ </dictionary>
+ <dictionary>
+ <key>org.eclipse.cdt.make.core.useDefaultBuildCmd</key>
+ <value>true</value>
+ </dictionary>
+ </arguments>
+ </buildCommand>
+ <buildCommand>
+ <name>org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder</name>
+ <triggers>full,incremental,</triggers>
+ <arguments>
+ </arguments>
+ </buildCommand>
+ </buildSpec>
+ <natures>
+ <nature>org.eclipse.cdt.core.cnature</nature>
+ <nature>org.eclipse.cdt.managedbuilder.core.managedBuildNature</nature>
+ <nature>org.eclipse.cdt.managedbuilder.core.ScannerConfigNature</nature>
+ </natures>
+ <linkedResources>
+ <link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/port.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/portable/RVDS/ARM_CM4F/port.c</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/portmacro.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/portable/RVDS/ARM_CM4F/portmacro.h</locationURI></link><link><name>startup</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>startup/startup_MCIMX7D_M4.s</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/devices/MCIMX7D/startup/arm/startup_MCIMX7D_M4.s</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/heap_2.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/portable/MemMang/heap_2.c</locationURI></link><link><name>board</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>board/FreeRTOSConfig.h</name><type>1</type><locationURI>PARENT-3-PROJECT_LOC/FreeRTOSConfig.h</locationURI></link><link><name>source</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>source/main.c</name><type>1</type><locationURI>PARENT-1-PROJECT_LOC/sensor_demo_imx7d/main.c</locationURI></link><link><name>source</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>source/i2c_xfer.c</name><type>1</type><locationURI>PARENT-1-PROJECT_LOC/common/i2c_xfer.c</locationURI></link><link><name>source</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>source/i2c_xfer.h</name><type>1</type><locationURI>PARENT-1-PROJECT_LOC/common/i2c_xfer.h</locationURI></link><link><name>source</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>source/mpl3115.c</name><type>1</type><locationURI>PARENT-1-PROJECT_LOC/common/mpl3115.c</locationURI></link><link><name>source</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>source/mpl3115.h</name><type>1</type><locationURI>PARENT-1-PROJECT_LOC/common/mpl3115.h</locationURI></link><link><name>source</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>source/fxos8700.c</name><type>1</type><locationURI>PARENT-1-PROJECT_LOC/common/fxos8700.c</locationURI></link><link><name>source</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>source/fxos8700.h</name><type>1</type><locationURI>PARENT-1-PROJECT_LOC/common/fxos8700.h</locationURI></link><link><name>source</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>source/fxas21002.c</name><type>1</type><locationURI>PARENT-1-PROJECT_LOC/common/fxas21002.c</locationURI></link><link><name>source</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>source/fxas21002.h</name><type>1</type><locationURI>PARENT-1-PROJECT_LOC/common/fxas21002.h</locationURI></link><link><name>driver</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>driver/i2c_imx.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/drivers/src/i2c_imx.c</locationURI></link><link><name>driver</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>driver/i2c_imx.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/drivers/inc/i2c_imx.h</locationURI></link><link><name>driver</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>driver/uart_imx.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/drivers/src/uart_imx.c</locationURI></link><link><name>driver</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>driver/uart_imx.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/drivers/inc/uart_imx.h</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/croutine.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/include/croutine.h</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/event_groups.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/include/event_groups.h</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/FreeRTOS.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/include/FreeRTOS.h</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/list.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/include/list.h</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/mpu_wrappers.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/include/mpu_wrappers.h</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/portable.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/include/portable.h</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/projdefs.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/include/projdefs.h</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/queue.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/include/queue.h</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/semphr.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/include/semphr.h</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/StackMacros.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/include/StackMacros.h</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/task.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/include/task.h</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/timers.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/include/timers.h</locationURI></link><link><name>system</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>system/ccm_analog_imx7d.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/drivers/inc/ccm_analog_imx7d.h</locationURI></link><link><name>system</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>system/ccm_imx7d.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/drivers/inc/ccm_imx7d.h</locationURI></link><link><name>system</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>system/rdc.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/drivers/inc/rdc.h</locationURI></link><link><name>system</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>system/rdc_defs_imx7d.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/drivers/inc/rdc_defs_imx7d.h</locationURI></link><link><name>system</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>system/wdog_imx.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/drivers/inc/wdog_imx.h</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/croutine.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/croutine.c</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/event_groups.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/event_groups.c</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/list.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/list.c</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/queue.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/queue.c</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/tasks.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/tasks.c</locationURI></link><link><name>freertos</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>freertos/timers.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/rtos/FreeRTOS/Source/timers.c</locationURI></link><link><name>system</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>system/ccm_analog_imx7d.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/drivers/src/ccm_analog_imx7d.c</locationURI></link><link><name>system</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>system/ccm_imx7d.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/drivers/src/ccm_imx7d.c</locationURI></link><link><name>system</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>system/rdc.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/drivers/src/rdc.c</locationURI></link><link><name>system</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>system/wdog_imx.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/drivers/src/wdog_imx.c</locationURI></link><link><name>utilities</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>utilities/debug_console_imx.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/utilities/src/debug_console_imx.c</locationURI></link><link><name>utilities</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>utilities/debug_console_imx.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/utilities/inc/debug_console_imx.h</locationURI></link><link><name>utilities</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>utilities/print_scan.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/utilities/src/print_scan.c</locationURI></link><link><name>utilities</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>utilities/print_scan.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/utilities/src/print_scan.h</locationURI></link><link><name>startup</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>startup/system_MCIMX7D_M4.c</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/devices/MCIMX7D/startup/system_MCIMX7D_M4.c</locationURI></link><link><name>startup</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>startup/system_MCIMX7D_M4.h</name><type>1</type><locationURI>PARENT-5-PROJECT_LOC/platform/devices/MCIMX7D/startup/system_MCIMX7D_M4.h</locationURI></link><link><name>board</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>board/pin_mux.c</name><type>1</type><locationURI>PARENT-3-PROJECT_LOC/pin_mux.c</locationURI></link><link><name>board</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>board/pin_mux.h</name><type>1</type><locationURI>PARENT-3-PROJECT_LOC/pin_mux.h</locationURI></link><link><name>board</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>board/board.c</name><type>1</type><locationURI>PARENT-3-PROJECT_LOC/board.c</locationURI></link><link><name>board</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>board/board.h</name><type>1</type><locationURI>PARENT-3-PROJECT_LOC/board.h</locationURI></link><link><name>board</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>board/clock_freq.c</name><type>1</type><locationURI>PARENT-3-PROJECT_LOC/clock_freq.c</locationURI></link><link><name>board</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>board/clock_freq.h</name><type>1</type><locationURI>PARENT-3-PROJECT_LOC/clock_freq.h</locationURI></link><link><name>board</name><type>2</type><locationURI>virtual:/virtual</locationURI></link><link><name>board/hardware_init.c</name><type>1</type><locationURI>PARENT-1-PROJECT_LOC/hardware_init.c</locationURI></link></linkedResources>
+ <variableList>
+ </variableList>
+</projectDescription>
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/ds5/makedir.bat b/examples/imx7_colibri_m4/demo_apps/sensor_demo/ds5/makedir.bat
new file mode 100755
index 0000000..4860035
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/ds5/makedir.bat
@@ -0,0 +1 @@
+IF NOT EXIST "%1" mkdir "%1"
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/ds5/sensor_demo.wsd b/examples/imx7_colibri_m4/demo_apps/sensor_demo/ds5/sensor_demo.wsd
new file mode 100644
index 0000000..0e22b0b
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/ds5/sensor_demo.wsd
@@ -0,0 +1,9 @@
+<?xml version="1.0"?>
+<workspace xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="workingsets.xsd">
+ <projects>
+ <project><name>sensor_demo_imx7d_sdb_m4</name><path>.</path><open>true</open><activeconfig>release</activeconfig><buildreferences config="release">false</buildreferences><activeconfig>debug</activeconfig><buildreferences config="debug">false</buildreferences></project></projects>
+ <workingsets>
+ <workingSet editPageId="org.eclipse.cdt.ui.CElementWorkingSetPage" id="1323268527287_1" label="sensor_demo" name="sensor_demo"><item factoryID="org.eclipse.cdt.ui.PersistableCElementFactory" path="/sensor_demo_imx7d_sdb_m4" type="4"/></workingSet></workingsets>
+ <cdtconfigurations>
+ <workingSet name="sensor_demo"><config name="release"><project config="com.freescale.arm.cdt.toolchain.config.arm.release.695495605" name="sensor_demo_imx7d_sdb_m4" configName="release"/></config><config name="debug"><project config="com.freescale.arm.cdt.toolchain.config.arm.release.695495605" name="sensor_demo_imx7d_sdb_m4" configName="debug"/></config></workingSet></cdtconfigurations>
+</workspace>
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/hardware_init.c b/examples/imx7_colibri_m4/demo_apps/sensor_demo/hardware_init.c
new file mode 100644
index 0000000..3ffd205
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/hardware_init.c
@@ -0,0 +1,60 @@
+/*
+ * Copyright (c) 2015, 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"
+
+void hardware_init(void)
+{
+ /* Board specific RDC settings */
+ BOARD_RdcInit();
+
+ /* Board specific clock settings */
+ BOARD_ClockInit();
+
+ /* initialize debug uart */
+ dbg_uart_init();
+
+ /* In this example, we need to grasp board I2C exclusively */
+ RDC_SetPdapAccess(RDC, BOARD_I2C_RDC_PDAP, 3 << (BOARD_DOMAIN_ID * 2), false, false);
+
+ /* Select I2C clock derived from OSC clock(24M) */
+ CCM_UpdateRoot(CCM, BOARD_I2C_CCM_ROOT, ccmRootmuxI2cOsc24m, 0, 0);
+ /* Enable I2C clock */
+ CCM_EnableRoot(CCM, BOARD_I2C_CCM_ROOT);
+ CCM_ControlGate(CCM, BOARD_I2C_CCM_CCGR, ccmClockNeededRunWait);
+
+ /* I2C Pin setting */
+ configure_i2c_pins(BOARD_I2C_BASEADDR);
+}
+
+/*******************************************************************************
+ * EOF
+ ******************************************************************************/
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/iar/sensor_demo.ewd b/examples/imx7_colibri_m4/demo_apps/sensor_demo/iar/sensor_demo.ewd
new file mode 100644
index 0000000..7f9ea8c
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/iar/sensor_demo.ewd
@@ -0,0 +1,9419 @@
+<?xml version="1.0" encoding="iso-8859-1"?>
+<project>
+ <fileVersion>2</fileVersion>
+ <configuration>
+ <name>Debug</name>
+ <toolchain>
+ <name>ARM</name>
+ </toolchain>
+ <debug>1</debug>
+ <settings>
+ <name>C-SPY</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>26</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CInput</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CEndian</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCVariant</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>MemOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MemFile</name>
+ <state>$TOOLKIT_DIR$\CONFIG\debugger\Freescale\MK70FN1M0xxx12.ddf</state>
+ </option>
+ <option>
+ <name>RunToEnable</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RunToName</name>
+ <state>main</state>
+ </option>
+ <option>
+ <name>CExtraOptionsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CExtraOptions</name>
+ <state/>
+ </option>
+ <option>
+ <name>CFpuProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCDDFArgumentProducer</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCDownloadSuppressDownload</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDownloadVerifyAll</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCProductVersion</name>
+ <state>6.50.6.4952</state>
+ </option>
+ <option>
+ <name>OCDynDriverList</name>
+ <state>JLINK_ID</state>
+ </option>
+ <option>
+ <name>OCLastSavedByProductVersion</name>
+ <state>7.10.1.6733</state>
+ </option>
+ <option>
+ <name>OCDownloadAttachToProgram</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>UseFlashLoader</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CLowLevel</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCBE8Slave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>MacFile2</name>
+ <state/>
+ </option>
+ <option>
+ <name>CDevice</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>FlashLoadersV3</name>
+ <state>$TOOLKIT_DIR$\config\flashloader\Freescale\FlashK70Fxxx128K.board</state>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck1</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath1</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath2</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck3</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath3</name>
+ <state/>
+ </option>
+ <option>
+ <name>OverrideDefFlashBoard</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesOffset1</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesOffset2</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesOffset3</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesUse1</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesUse2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesUse3</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDeviceConfigMacroFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCDebuggerExtraOption</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCAllMTBOptions</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCMulticoreNrOfCores</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCMulticoreMaster</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCMulticorePort</name>
+ <state>53461</state>
+ </option>
+ <option>
+ <name>OCMulticoreWorkspace</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCMulticoreSlaveProject</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCMulticoreSlaveConfiguration</name>
+ <state/>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>ARMSIM_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCSimDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCSimEnablePSP</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCSimPspOverrideConfig</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCSimPspConfigFile</name>
+ <state/>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>ANGEL_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CCAngelHeartbeat</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CAngelCommunication</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CAngelCommBaud</name>
+ <version>0</version>
+ <state>3</state>
+ </option>
+ <option>
+ <name>CAngelCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ANGELTCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoAngelLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AngelLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>CMSISDAP_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CMSISDAPAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCIarProbeScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CMSISDAPResetList</name>
+ <version>1</version>
+ <state>10</state>
+ </option>
+ <option>
+ <name>CMSISDAPHWResetDuration</name>
+ <state>300</state>
+ </option>
+ <option>
+ <name>CMSISDAPHWResetDelay</name>
+ <state>200</state>
+ </option>
+ <option>
+ <name>CMSISDAPDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CMSISDAPInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiTargetEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPJtagSpeedList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPRestoreBreakpointsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPUpdateBreakpointsEdit</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>RDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchMMERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchNOCPERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCHKERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchSTATERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchBUSERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchINTERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchHARDERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiCPUEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiCPUNumber</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeCfgOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeConfig</name>
+ <state/>
+ </option>
+ <option>
+ <name>CMSISDAPProbeConfigRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPSelectedCPUBehaviour</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ICpuName</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCJetEmuParams</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>GDBSERVER_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCJTagBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>IARROM_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CRomLogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRomLogFileEditB</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CRomCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRomCommBaud</name>
+ <version>0</version>
+ <state>7</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>IJET_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>3</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCIarProbeScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetResetList</name>
+ <version>1</version>
+ <state>10</state>
+ </option>
+ <option>
+ <name>IjetHWResetDuration</name>
+ <state>300</state>
+ </option>
+ <option>
+ <name>IjetHWResetDelay</name>
+ <state>200</state>
+ </option>
+ <option>
+ <name>IjetPowerFromProbe</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetPowerRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>IjetInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiTargetEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetScanChainNonARMDevices</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetIRLength</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetJtagSpeedList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetProtocolRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetSwoPin</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>IjetSwoPrescalerList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetRestoreBreakpointsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetUpdateBreakpointsEdit</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>RDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchUndef</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchData</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchPrefetch</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchMMERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchNOCPERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchCHKERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchSTATERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchBUSERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchINTERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchHARDERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeCfgOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeConfig</name>
+ <state/>
+ </option>
+ <option>
+ <name>IjetProbeConfigRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiCPUEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiCPUNumber</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetSelectedCPUBehaviour</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ICpuName</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCJetEmuParams</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>JLINK_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>15</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>JLinkSpeed</name>
+ <state>32</state>
+ </option>
+ <option>
+ <name>CCJLinkDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCJLinkHWResetDelay</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>JLinkInitialSpeed</name>
+ <state>32</state>
+ </option>
+ <option>
+ <name>CCDoJlinkMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCScanChainNonARMDevices</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkIRLength</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkCommRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkTCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>CCJLinkSpeedRadioV2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCUSBDevice</name>
+ <version>1</version>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCRDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>CCJLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCJLinkResetList</name>
+ <version>6</version>
+ <state>5</state>
+ </option>
+ <option>
+ <name>CCJLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchMMERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchNOCPERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchCHRERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchSTATERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchBUSERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchINTERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchHARDERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCJLinkUsbSerialNo</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCTcpIpAlt</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkTcpIpSerialNo</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>CCSwoClockAuto</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSwoClockEdit</name>
+ <state>2000</state>
+ </option>
+ <option>
+ <name>OCJLinkTraceSource</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkTraceSourceDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkDeviceName</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>LMIFTDI_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>LmiftdiSpeed</name>
+ <state>500</state>
+ </option>
+ <option>
+ <name>CCLmiftdiDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCLmiftdiLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCLmiFtdiInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCLmiFtdiInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>MACRAIGOR_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>3</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>jtag</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>EmuSpeed</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>DoEmuMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>EmuMultiTarget</name>
+ <state>0@ARM7TDMI</state>
+ </option>
+ <option>
+ <name>EmuHWReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CEmuCommBaud</name>
+ <version>0</version>
+ <state>4</state>
+ </option>
+ <option>
+ <name>CEmuCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>jtago</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>UnusedAddr</name>
+ <state>0x00800000</state>
+ </option>
+ <option>
+ <name>CCMacraigorHWResetDelay</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCJTagBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>CCMacraigorInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCMacraigorInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>PEMICRO_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCPEMicroAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCPEMicroInterfaceList</name>
+ <version>0</version>
+ <state>7</state>
+ </option>
+ <option>
+ <name>CCPEMicroResetDelay</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCPEMicroJtagSpeed</name>
+ <state>5000</state>
+ </option>
+ <option>
+ <name>CCJPEMicroShowSettings</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCPEMicroUSBDevice</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPEMicroSerialPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJPEMicroTCPIPAutoScanNetwork</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCPEMicroTCPIP</name>
+ <state>10.0.0.1</state>
+ </option>
+ <option>
+ <name>CCPEMicroCommCmdLineProducer</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceRadio</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>RDI_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CRDIDriverDll</name>
+ <state>###Uninitialized###</state>
+ </option>
+ <option>
+ <name>CRDILogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRDILogFileEdit</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCRDIHWReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>STLINK_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkResetList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>CCSwoClockAuto</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSwoClockEdit</name>
+ <state>2000</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>THIRDPARTY_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CThirdPartyDriverDll</name>
+ <state>###Uninitialized###</state>
+ </option>
+ <option>
+ <name>CThirdPartyLogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CThirdPartyLogFileEditB</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>XDS100_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCXDS100AttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TIPackageOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>TIPackage</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCXds100InterfaceList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>BoardFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ </data>
+ </settings>
+ <debuggerPlugins>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\middleware\HCCWare\HCCWare.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\AVIX\AVIX.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\CMX\CmxArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\CMX\CmxTinyArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\embOS\embOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\MQX\MQXRtosPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\OpenRTOS\OpenRTOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\SafeRTOS\SafeRTOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\ThreadX\ThreadXArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\TI-RTOS\tirtosplugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-286-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-III\uCOS-III-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\CodeCoverage\CodeCoverage.ENU.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\Orti\Orti.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\SymList\SymList.ENU.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\uCProbe\uCProbePlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ </debuggerPlugins>
+ </configuration>
+ <configuration>
+ <name>Release</name>
+ <toolchain>
+ <name>ARM</name>
+ </toolchain>
+ <debug>0</debug>
+ <settings>
+ <name>C-SPY</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>26</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>CInput</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CEndian</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCVariant</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>MemOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MemFile</name>
+ <state>$TOOLKIT_DIR$\CONFIG\debugger\Freescale\MK70FN1M0xxx12.ddf</state>
+ </option>
+ <option>
+ <name>RunToEnable</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RunToName</name>
+ <state>main</state>
+ </option>
+ <option>
+ <name>CExtraOptionsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CExtraOptions</name>
+ <state/>
+ </option>
+ <option>
+ <name>CFpuProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCDDFArgumentProducer</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCDownloadSuppressDownload</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDownloadVerifyAll</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCProductVersion</name>
+ <state>6.50.6.4952</state>
+ </option>
+ <option>
+ <name>OCDynDriverList</name>
+ <state>JLINK_ID</state>
+ </option>
+ <option>
+ <name>OCLastSavedByProductVersion</name>
+ <state>6.70.3.6347</state>
+ </option>
+ <option>
+ <name>OCDownloadAttachToProgram</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>UseFlashLoader</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CLowLevel</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCBE8Slave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>MacFile2</name>
+ <state/>
+ </option>
+ <option>
+ <name>CDevice</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>FlashLoadersV3</name>
+ <state>$TOOLKIT_DIR$\config\flashloader\Freescale\FlashK70Fxxx128K.board</state>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck1</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath1</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath2</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck3</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath3</name>
+ <state/>
+ </option>
+ <option>
+ <name>OverrideDefFlashBoard</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesOffset1</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesOffset2</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesOffset3</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesUse1</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesUse2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesUse3</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDeviceConfigMacroFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCDebuggerExtraOption</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCAllMTBOptions</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCMulticoreNrOfCores</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCMulticoreMaster</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCMulticorePort</name>
+ <state>53461</state>
+ </option>
+ <option>
+ <name>OCMulticoreWorkspace</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCMulticoreSlaveProject</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCMulticoreSlaveConfiguration</name>
+ <state/>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>ARMSIM_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCSimDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCSimEnablePSP</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCSimPspOverrideConfig</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCSimPspConfigFile</name>
+ <state/>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>ANGEL_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>CCAngelHeartbeat</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CAngelCommunication</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CAngelCommBaud</name>
+ <version>0</version>
+ <state>3</state>
+ </option>
+ <option>
+ <name>CAngelCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ANGELTCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoAngelLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AngelLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>CMSISDAP_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CMSISDAPAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCIarProbeScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CMSISDAPResetList</name>
+ <version>1</version>
+ <state>10</state>
+ </option>
+ <option>
+ <name>CMSISDAPHWResetDuration</name>
+ <state>300</state>
+ </option>
+ <option>
+ <name>CMSISDAPHWResetDelay</name>
+ <state>200</state>
+ </option>
+ <option>
+ <name>CMSISDAPDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CMSISDAPInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiTargetEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPJtagSpeedList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPRestoreBreakpointsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPUpdateBreakpointsEdit</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>RDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchMMERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchNOCPERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCHKERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchSTATERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchBUSERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchINTERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchHARDERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiCPUEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiCPUNumber</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeCfgOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeConfig</name>
+ <state/>
+ </option>
+ <option>
+ <name>CMSISDAPProbeConfigRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPSelectedCPUBehaviour</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ICpuName</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCJetEmuParams</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>GDBSERVER_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCJTagBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>IARROM_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>CRomLogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRomLogFileEditB</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CRomCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRomCommBaud</name>
+ <version>0</version>
+ <state>7</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>IJET_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>3</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCIarProbeScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetResetList</name>
+ <version>1</version>
+ <state>10</state>
+ </option>
+ <option>
+ <name>IjetHWResetDuration</name>
+ <state>300</state>
+ </option>
+ <option>
+ <name>IjetHWResetDelay</name>
+ <state>200</state>
+ </option>
+ <option>
+ <name>IjetPowerFromProbe</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetPowerRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>IjetInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiTargetEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetScanChainNonARMDevices</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetIRLength</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetJtagSpeedList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetProtocolRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetSwoPin</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>IjetSwoPrescalerList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetRestoreBreakpointsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetUpdateBreakpointsEdit</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>RDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchUndef</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchData</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchPrefetch</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchMMERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchNOCPERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchCHKERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchSTATERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchBUSERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchINTERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchHARDERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeCfgOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeConfig</name>
+ <state/>
+ </option>
+ <option>
+ <name>IjetProbeConfigRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiCPUEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiCPUNumber</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetSelectedCPUBehaviour</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ICpuName</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCJetEmuParams</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>JLINK_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>15</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>JLinkSpeed</name>
+ <state>32</state>
+ </option>
+ <option>
+ <name>CCJLinkDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCJLinkHWResetDelay</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>JLinkInitialSpeed</name>
+ <state>32</state>
+ </option>
+ <option>
+ <name>CCDoJlinkMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCScanChainNonARMDevices</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkIRLength</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkCommRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkTCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>CCJLinkSpeedRadioV2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCUSBDevice</name>
+ <version>1</version>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCRDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>CCJLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCJLinkResetList</name>
+ <version>6</version>
+ <state>5</state>
+ </option>
+ <option>
+ <name>CCJLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchMMERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchNOCPERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchCHRERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchSTATERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchBUSERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchINTERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchHARDERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCJLinkUsbSerialNo</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCTcpIpAlt</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkTcpIpSerialNo</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>CCSwoClockAuto</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSwoClockEdit</name>
+ <state>2000</state>
+ </option>
+ <option>
+ <name>OCJLinkTraceSource</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkTraceSourceDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkDeviceName</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>LMIFTDI_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>LmiftdiSpeed</name>
+ <state>500</state>
+ </option>
+ <option>
+ <name>CCLmiftdiDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCLmiftdiLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCLmiFtdiInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCLmiFtdiInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>MACRAIGOR_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>3</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>jtag</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>EmuSpeed</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>DoEmuMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>EmuMultiTarget</name>
+ <state>0@ARM7TDMI</state>
+ </option>
+ <option>
+ <name>EmuHWReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CEmuCommBaud</name>
+ <version>0</version>
+ <state>4</state>
+ </option>
+ <option>
+ <name>CEmuCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>jtago</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>UnusedAddr</name>
+ <state>0x00800000</state>
+ </option>
+ <option>
+ <name>CCMacraigorHWResetDelay</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCJTagBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>CCMacraigorInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCMacraigorInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>PEMICRO_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCPEMicroAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCPEMicroInterfaceList</name>
+ <version>0</version>
+ <state>7</state>
+ </option>
+ <option>
+ <name>CCPEMicroResetDelay</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCPEMicroJtagSpeed</name>
+ <state>5000</state>
+ </option>
+ <option>
+ <name>CCJPEMicroShowSettings</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCPEMicroUSBDevice</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPEMicroSerialPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJPEMicroTCPIPAutoScanNetwork</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCPEMicroTCPIP</name>
+ <state>10.0.0.1</state>
+ </option>
+ <option>
+ <name>CCPEMicroCommCmdLineProducer</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceRadio</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>RDI_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>CRDIDriverDll</name>
+ <state>###Uninitialized###</state>
+ </option>
+ <option>
+ <name>CRDILogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRDILogFileEdit</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCRDIHWReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>STLINK_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkResetList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>CCSwoClockAuto</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSwoClockEdit</name>
+ <state>2000</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>THIRDPARTY_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>CThirdPartyDriverDll</name>
+ <state>###Uninitialized###</state>
+ </option>
+ <option>
+ <name>CThirdPartyLogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CThirdPartyLogFileEditB</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>XDS100_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCXDS100AttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TIPackageOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>TIPackage</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCXds100InterfaceList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>BoardFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ </data>
+ </settings>
+ <debuggerPlugins>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\middleware\HCCWare\HCCWare.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\AVIX\AVIX.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\CMX\CmxArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\CMX\CmxTinyArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\embOS\embOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\MQX\MQXRtosPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\OpenRTOS\OpenRTOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\SafeRTOS\SafeRTOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\ThreadX\ThreadXArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\TI-RTOS\tirtosplugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-286-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-III\uCOS-III-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\CodeCoverage\CodeCoverage.ENU.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\Orti\Orti.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\SymList\SymList.ENU.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\uCProbe\uCProbePlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ </debuggerPlugins>
+ </configuration>
+ <configuration>
+ <name>Int Flash SramData Debug</name>
+ <toolchain>
+ <name>ARM</name>
+ </toolchain>
+ <debug>1</debug>
+ <settings>
+ <name>C-SPY</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>26</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CInput</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CEndian</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCVariant</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>MemOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MemFile</name>
+ <state>$TOOLKIT_DIR$\CONFIG\debugger\Freescale\MK70FN1M0xxx12.ddf</state>
+ </option>
+ <option>
+ <name>RunToEnable</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RunToName</name>
+ <state>main</state>
+ </option>
+ <option>
+ <name>CExtraOptionsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CExtraOptions</name>
+ <state/>
+ </option>
+ <option>
+ <name>CFpuProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCDDFArgumentProducer</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCDownloadSuppressDownload</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDownloadVerifyAll</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProductVersion</name>
+ <state>5.50.0.51907</state>
+ </option>
+ <option>
+ <name>OCDynDriverList</name>
+ <state>JLINK_ID</state>
+ </option>
+ <option>
+ <name>OCLastSavedByProductVersion</name>
+ <state>6.40.2.53991</state>
+ </option>
+ <option>
+ <name>OCDownloadAttachToProgram</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>UseFlashLoader</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CLowLevel</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCBE8Slave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>MacFile2</name>
+ <state/>
+ </option>
+ <option>
+ <name>CDevice</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>FlashLoadersV3</name>
+ <state>$TOOLKIT_DIR$\config\flashloader\Freescale\FlashK70Fxxx128K.board</state>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck1</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath1</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath2</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck3</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath3</name>
+ <state/>
+ </option>
+ <option>
+ <name>OverrideDefFlashBoard</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesOffset1</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesOffset2</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesOffset3</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesUse1</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesUse2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesUse3</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDeviceConfigMacroFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCDebuggerExtraOption</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCAllMTBOptions</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCMulticoreNrOfCores</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCMulticoreMaster</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCMulticorePort</name>
+ <state>53461</state>
+ </option>
+ <option>
+ <name>OCMulticoreWorkspace</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCMulticoreSlaveProject</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCMulticoreSlaveConfiguration</name>
+ <state/>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>ARMSIM_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCSimDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCSimEnablePSP</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCSimPspOverrideConfig</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCSimPspConfigFile</name>
+ <state/>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>ANGEL_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CCAngelHeartbeat</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CAngelCommunication</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CAngelCommBaud</name>
+ <version>0</version>
+ <state>3</state>
+ </option>
+ <option>
+ <name>CAngelCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ANGELTCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoAngelLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AngelLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>CMSISDAP_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CMSISDAPAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCIarProbeScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CMSISDAPResetList</name>
+ <version>1</version>
+ <state>10</state>
+ </option>
+ <option>
+ <name>CMSISDAPHWResetDuration</name>
+ <state>300</state>
+ </option>
+ <option>
+ <name>CMSISDAPHWResetDelay</name>
+ <state>200</state>
+ </option>
+ <option>
+ <name>CMSISDAPDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CMSISDAPInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiTargetEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPJtagSpeedList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPRestoreBreakpointsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPUpdateBreakpointsEdit</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>RDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchUndef</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchData</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchPrefetch</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchMMERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchNOCPERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchCHKERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchSTATERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchBUSERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchINTERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchHARDERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiCPUEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiCPUNumber</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeCfgOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeConfig</name>
+ <state/>
+ </option>
+ <option>
+ <name>CMSISDAPProbeConfigRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPSelectedCPUBehaviour</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ICpuName</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCJetEmuParams</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>GDBSERVER_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCJTagBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>IARROM_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CRomLogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRomLogFileEditB</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CRomCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRomCommBaud</name>
+ <version>0</version>
+ <state>7</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>IJET_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>3</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCIarProbeScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetResetList</name>
+ <version>1</version>
+ <state>10</state>
+ </option>
+ <option>
+ <name>IjetHWResetDuration</name>
+ <state>300</state>
+ </option>
+ <option>
+ <name>IjetHWResetDelay</name>
+ <state>200</state>
+ </option>
+ <option>
+ <name>IjetPowerFromProbe</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetPowerRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>IjetInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiTargetEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetScanChainNonARMDevices</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetIRLength</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetJtagSpeedList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetProtocolRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetSwoPin</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>IjetSwoPrescalerList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetRestoreBreakpointsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetUpdateBreakpointsEdit</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>RDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchMMERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchNOCPERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCHKERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchSTATERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchBUSERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchINTERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchHARDERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeCfgOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeConfig</name>
+ <state/>
+ </option>
+ <option>
+ <name>IjetProbeConfigRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiCPUEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiCPUNumber</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetSelectedCPUBehaviour</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ICpuName</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCJetEmuParams</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>JLINK_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>15</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>JLinkSpeed</name>
+ <state>100</state>
+ </option>
+ <option>
+ <name>CCJLinkDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCJLinkHWResetDelay</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>JLinkInitialSpeed</name>
+ <state>32</state>
+ </option>
+ <option>
+ <name>CCDoJlinkMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCScanChainNonARMDevices</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkIRLength</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkCommRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkTCPIP</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCJLinkSpeedRadioV2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCUSBDevice</name>
+ <version>1</version>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCRDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>CCJLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCJLinkResetList</name>
+ <version>6</version>
+ <state>7</state>
+ </option>
+ <option>
+ <name>CCJLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchMMERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchNOCPERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchCHRERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchSTATERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchBUSERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchINTERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchHARDERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCJLinkUsbSerialNo</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCTcpIpAlt</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkTcpIpSerialNo</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>CCSwoClockAuto</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSwoClockEdit</name>
+ <state>2000</state>
+ </option>
+ <option>
+ <name>OCJLinkTraceSource</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkTraceSourceDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkDeviceName</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>LMIFTDI_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>LmiftdiSpeed</name>
+ <state>500</state>
+ </option>
+ <option>
+ <name>CCLmiftdiDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCLmiftdiLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCLmiFtdiInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCLmiFtdiInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>MACRAIGOR_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>3</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>jtag</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>EmuSpeed</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>DoEmuMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>EmuMultiTarget</name>
+ <state>0@ARM7TDMI</state>
+ </option>
+ <option>
+ <name>EmuHWReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CEmuCommBaud</name>
+ <version>0</version>
+ <state>4</state>
+ </option>
+ <option>
+ <name>CEmuCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>jtago</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>UnusedAddr</name>
+ <state>0x00800000</state>
+ </option>
+ <option>
+ <name>CCMacraigorHWResetDelay</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCJTagBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>CCMacraigorInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCMacraigorInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>PEMICRO_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCPEMicroAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCPEMicroInterfaceList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPEMicroResetDelay</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCPEMicroJtagSpeed</name>
+ <state>#UNINITIALIZED#</state>
+ </option>
+ <option>
+ <name>CCJPEMicroShowSettings</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCPEMicroUSBDevice</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPEMicroSerialPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJPEMicroTCPIPAutoScanNetwork</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCPEMicroTCPIP</name>
+ <state>10.0.0.1</state>
+ </option>
+ <option>
+ <name>CCPEMicroCommCmdLineProducer</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>RDI_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CRDIDriverDll</name>
+ <state>###Uninitialized###</state>
+ </option>
+ <option>
+ <name>CRDILogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRDILogFileEdit</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCRDIHWReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>STLINK_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkResetList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>CCSwoClockAuto</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSwoClockEdit</name>
+ <state>2000</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>THIRDPARTY_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CThirdPartyDriverDll</name>
+ <state>###Uninitialized###</state>
+ </option>
+ <option>
+ <name>CThirdPartyLogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CThirdPartyLogFileEditB</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>XDS100_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCXDS100AttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TIPackageOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>TIPackage</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCXds100InterfaceList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>BoardFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ </data>
+ </settings>
+ <debuggerPlugins>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\middleware\HCCWare\HCCWare.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\AVIX\AVIX.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\CMX\CmxArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\CMX\CmxTinyArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\embOS\embOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\MQX\MQXRtosPlugin.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\OpenRTOS\OpenRTOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\SafeRTOS\SafeRTOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\ThreadX\ThreadXArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\TI-RTOS\tirtosplugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-286-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-III\uCOS-III-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\CodeCoverage\CodeCoverage.ENU.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\Orti\Orti.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\SymList\SymList.ENU.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\uCProbe\uCProbePlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ </debuggerPlugins>
+ </configuration>
+ <configuration>
+ <name>Int Flash SramData Release</name>
+ <toolchain>
+ <name>ARM</name>
+ </toolchain>
+ <debug>0</debug>
+ <settings>
+ <name>C-SPY</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>26</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>CInput</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CEndian</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCVariant</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>MemOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MemFile</name>
+ <state>$TOOLKIT_DIR$\CONFIG\debugger\Freescale\MK70FN1M0xxx12.ddf</state>
+ </option>
+ <option>
+ <name>RunToEnable</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RunToName</name>
+ <state>main</state>
+ </option>
+ <option>
+ <name>CExtraOptionsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CExtraOptions</name>
+ <state/>
+ </option>
+ <option>
+ <name>CFpuProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCDDFArgumentProducer</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCDownloadSuppressDownload</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDownloadVerifyAll</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProductVersion</name>
+ <state>5.50.0.51907</state>
+ </option>
+ <option>
+ <name>OCDynDriverList</name>
+ <state>JLINK_ID</state>
+ </option>
+ <option>
+ <name>OCLastSavedByProductVersion</name>
+ <state>6.40.2.53991</state>
+ </option>
+ <option>
+ <name>OCDownloadAttachToProgram</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>UseFlashLoader</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CLowLevel</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCBE8Slave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>MacFile2</name>
+ <state/>
+ </option>
+ <option>
+ <name>CDevice</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>FlashLoadersV3</name>
+ <state>$TOOLKIT_DIR$\config\flashloader\Freescale\FlashK70Fxxx128K.board</state>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck1</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath1</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath2</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck3</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath3</name>
+ <state/>
+ </option>
+ <option>
+ <name>OverrideDefFlashBoard</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesOffset1</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesOffset2</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesOffset3</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesUse1</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesUse2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesUse3</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDeviceConfigMacroFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCDebuggerExtraOption</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCAllMTBOptions</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCMulticoreNrOfCores</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCMulticoreMaster</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCMulticorePort</name>
+ <state>53461</state>
+ </option>
+ <option>
+ <name>OCMulticoreWorkspace</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCMulticoreSlaveProject</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCMulticoreSlaveConfiguration</name>
+ <state/>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>ARMSIM_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCSimDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCSimEnablePSP</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCSimPspOverrideConfig</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCSimPspConfigFile</name>
+ <state/>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>ANGEL_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>CCAngelHeartbeat</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CAngelCommunication</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CAngelCommBaud</name>
+ <version>0</version>
+ <state>3</state>
+ </option>
+ <option>
+ <name>CAngelCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ANGELTCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoAngelLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AngelLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>CMSISDAP_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CMSISDAPAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCIarProbeScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CMSISDAPResetList</name>
+ <version>1</version>
+ <state>10</state>
+ </option>
+ <option>
+ <name>CMSISDAPHWResetDuration</name>
+ <state>300</state>
+ </option>
+ <option>
+ <name>CMSISDAPHWResetDelay</name>
+ <state>200</state>
+ </option>
+ <option>
+ <name>CMSISDAPDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CMSISDAPInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiTargetEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPJtagSpeedList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPRestoreBreakpointsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPUpdateBreakpointsEdit</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>RDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchUndef</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchData</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchPrefetch</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchMMERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchNOCPERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchCHKERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchSTATERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchBUSERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchINTERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchHARDERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiCPUEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiCPUNumber</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeCfgOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeConfig</name>
+ <state/>
+ </option>
+ <option>
+ <name>CMSISDAPProbeConfigRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPSelectedCPUBehaviour</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ICpuName</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCJetEmuParams</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>GDBSERVER_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCJTagBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>IARROM_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>CRomLogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRomLogFileEditB</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CRomCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRomCommBaud</name>
+ <version>0</version>
+ <state>7</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>IJET_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>3</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCIarProbeScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetResetList</name>
+ <version>1</version>
+ <state>10</state>
+ </option>
+ <option>
+ <name>IjetHWResetDuration</name>
+ <state>300</state>
+ </option>
+ <option>
+ <name>IjetHWResetDelay</name>
+ <state>200</state>
+ </option>
+ <option>
+ <name>IjetPowerFromProbe</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetPowerRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>IjetInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiTargetEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetScanChainNonARMDevices</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetIRLength</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetJtagSpeedList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetProtocolRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetSwoPin</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>IjetSwoPrescalerList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetRestoreBreakpointsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetUpdateBreakpointsEdit</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>RDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchMMERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchNOCPERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCHKERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchSTATERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchBUSERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchINTERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchHARDERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeCfgOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeConfig</name>
+ <state/>
+ </option>
+ <option>
+ <name>IjetProbeConfigRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiCPUEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiCPUNumber</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetSelectedCPUBehaviour</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ICpuName</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCJetEmuParams</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>JLINK_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>15</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>JLinkSpeed</name>
+ <state>100</state>
+ </option>
+ <option>
+ <name>CCJLinkDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCJLinkHWResetDelay</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>JLinkInitialSpeed</name>
+ <state>32</state>
+ </option>
+ <option>
+ <name>CCDoJlinkMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCScanChainNonARMDevices</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkIRLength</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkCommRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkTCPIP</name>
+ <state>10.171.88.231</state>
+ </option>
+ <option>
+ <name>CCJLinkSpeedRadioV2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCUSBDevice</name>
+ <version>1</version>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCRDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>CCJLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCJLinkResetList</name>
+ <version>6</version>
+ <state>7</state>
+ </option>
+ <option>
+ <name>CCJLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchMMERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchNOCPERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchCHRERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchSTATERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchBUSERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchINTERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchHARDERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCJLinkUsbSerialNo</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCTcpIpAlt</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkTcpIpSerialNo</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>CCSwoClockAuto</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSwoClockEdit</name>
+ <state>2000</state>
+ </option>
+ <option>
+ <name>OCJLinkTraceSource</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkTraceSourceDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkDeviceName</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>LMIFTDI_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>LmiftdiSpeed</name>
+ <state>500</state>
+ </option>
+ <option>
+ <name>CCLmiftdiDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCLmiftdiLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCLmiFtdiInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCLmiFtdiInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>MACRAIGOR_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>3</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>jtag</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>EmuSpeed</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>DoEmuMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>EmuMultiTarget</name>
+ <state>0@ARM7TDMI</state>
+ </option>
+ <option>
+ <name>EmuHWReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CEmuCommBaud</name>
+ <version>0</version>
+ <state>4</state>
+ </option>
+ <option>
+ <name>CEmuCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>jtago</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>UnusedAddr</name>
+ <state>0x00800000</state>
+ </option>
+ <option>
+ <name>CCMacraigorHWResetDelay</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCJTagBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>CCMacraigorInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCMacraigorInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>PEMICRO_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCPEMicroAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCPEMicroInterfaceList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPEMicroResetDelay</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCPEMicroJtagSpeed</name>
+ <state>#UNINITIALIZED#</state>
+ </option>
+ <option>
+ <name>CCJPEMicroShowSettings</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCPEMicroUSBDevice</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPEMicroSerialPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJPEMicroTCPIPAutoScanNetwork</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCPEMicroTCPIP</name>
+ <state>10.0.0.1</state>
+ </option>
+ <option>
+ <name>CCPEMicroCommCmdLineProducer</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>RDI_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>CRDIDriverDll</name>
+ <state>###Uninitialized###</state>
+ </option>
+ <option>
+ <name>CRDILogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRDILogFileEdit</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCRDIHWReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>STLINK_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkResetList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>CCSwoClockAuto</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSwoClockEdit</name>
+ <state>2000</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>THIRDPARTY_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>CThirdPartyDriverDll</name>
+ <state>###Uninitialized###</state>
+ </option>
+ <option>
+ <name>CThirdPartyLogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CThirdPartyLogFileEditB</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>XDS100_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCXDS100AttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TIPackageOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>TIPackage</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCXds100InterfaceList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>BoardFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ </data>
+ </settings>
+ <debuggerPlugins>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\middleware\HCCWare\HCCWare.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\AVIX\AVIX.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\CMX\CmxArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\CMX\CmxTinyArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\embOS\embOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\MQX\MQXRtosPlugin.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\OpenRTOS\OpenRTOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\SafeRTOS\SafeRTOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\ThreadX\ThreadXArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\TI-RTOS\tirtosplugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-286-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-III\uCOS-III-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\CodeCoverage\CodeCoverage.ENU.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\Orti\Orti.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\SymList\SymList.ENU.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\uCProbe\uCProbePlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ </debuggerPlugins>
+ </configuration>
+ <configuration>
+ <name>Int Flash DDRData Debug</name>
+ <toolchain>
+ <name>ARM</name>
+ </toolchain>
+ <debug>1</debug>
+ <settings>
+ <name>C-SPY</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>26</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CInput</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CEndian</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCVariant</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>MemOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MemFile</name>
+ <state>$TOOLKIT_DIR$\CONFIG\debugger\Freescale\MK70FN1M0xxx12.ddf</state>
+ </option>
+ <option>
+ <name>RunToEnable</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RunToName</name>
+ <state>main</state>
+ </option>
+ <option>
+ <name>CExtraOptionsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CExtraOptions</name>
+ <state/>
+ </option>
+ <option>
+ <name>CFpuProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCDDFArgumentProducer</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCDownloadSuppressDownload</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDownloadVerifyAll</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProductVersion</name>
+ <state>5.50.0.51907</state>
+ </option>
+ <option>
+ <name>OCDynDriverList</name>
+ <state>JLINK_ID</state>
+ </option>
+ <option>
+ <name>OCLastSavedByProductVersion</name>
+ <state>6.40.2.53991</state>
+ </option>
+ <option>
+ <name>OCDownloadAttachToProgram</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>UseFlashLoader</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CLowLevel</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCBE8Slave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>MacFile2</name>
+ <state/>
+ </option>
+ <option>
+ <name>CDevice</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>FlashLoadersV3</name>
+ <state>$TOOLKIT_DIR$\config\flashloader\Freescale\FlashK70Fxxx128K.board</state>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck1</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath1</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath2</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck3</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath3</name>
+ <state/>
+ </option>
+ <option>
+ <name>OverrideDefFlashBoard</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesOffset1</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesOffset2</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesOffset3</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesUse1</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesUse2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesUse3</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDeviceConfigMacroFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCDebuggerExtraOption</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCAllMTBOptions</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCMulticoreNrOfCores</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCMulticoreMaster</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCMulticorePort</name>
+ <state>53461</state>
+ </option>
+ <option>
+ <name>OCMulticoreWorkspace</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCMulticoreSlaveProject</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCMulticoreSlaveConfiguration</name>
+ <state/>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>ARMSIM_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCSimDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCSimEnablePSP</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCSimPspOverrideConfig</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCSimPspConfigFile</name>
+ <state/>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>ANGEL_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CCAngelHeartbeat</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CAngelCommunication</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CAngelCommBaud</name>
+ <version>0</version>
+ <state>3</state>
+ </option>
+ <option>
+ <name>CAngelCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ANGELTCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoAngelLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AngelLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>CMSISDAP_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CMSISDAPAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCIarProbeScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CMSISDAPResetList</name>
+ <version>1</version>
+ <state>10</state>
+ </option>
+ <option>
+ <name>CMSISDAPHWResetDuration</name>
+ <state>300</state>
+ </option>
+ <option>
+ <name>CMSISDAPHWResetDelay</name>
+ <state>200</state>
+ </option>
+ <option>
+ <name>CMSISDAPDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CMSISDAPInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiTargetEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPJtagSpeedList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPRestoreBreakpointsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPUpdateBreakpointsEdit</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>RDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchUndef</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchData</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchPrefetch</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchMMERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchNOCPERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchCHKERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchSTATERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchBUSERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchINTERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchHARDERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiCPUEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiCPUNumber</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeCfgOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeConfig</name>
+ <state/>
+ </option>
+ <option>
+ <name>CMSISDAPProbeConfigRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPSelectedCPUBehaviour</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ICpuName</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCJetEmuParams</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>GDBSERVER_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCJTagBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>IARROM_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CRomLogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRomLogFileEditB</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CRomCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRomCommBaud</name>
+ <version>0</version>
+ <state>7</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>IJET_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>3</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCIarProbeScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetResetList</name>
+ <version>1</version>
+ <state>10</state>
+ </option>
+ <option>
+ <name>IjetHWResetDuration</name>
+ <state>300</state>
+ </option>
+ <option>
+ <name>IjetHWResetDelay</name>
+ <state>200</state>
+ </option>
+ <option>
+ <name>IjetPowerFromProbe</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetPowerRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>IjetInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiTargetEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetScanChainNonARMDevices</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetIRLength</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetJtagSpeedList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetProtocolRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetSwoPin</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>IjetSwoPrescalerList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetRestoreBreakpointsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetUpdateBreakpointsEdit</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>RDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchMMERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchNOCPERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCHKERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchSTATERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchBUSERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchINTERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchHARDERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeCfgOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeConfig</name>
+ <state/>
+ </option>
+ <option>
+ <name>IjetProbeConfigRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiCPUEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiCPUNumber</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetSelectedCPUBehaviour</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ICpuName</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCJetEmuParams</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>JLINK_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>15</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>JLinkSpeed</name>
+ <state>100</state>
+ </option>
+ <option>
+ <name>CCJLinkDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCJLinkHWResetDelay</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>JLinkInitialSpeed</name>
+ <state>32</state>
+ </option>
+ <option>
+ <name>CCDoJlinkMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCScanChainNonARMDevices</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkIRLength</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkCommRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkTCPIP</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCJLinkSpeedRadioV2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCUSBDevice</name>
+ <version>1</version>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCRDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>CCJLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCJLinkResetList</name>
+ <version>6</version>
+ <state>7</state>
+ </option>
+ <option>
+ <name>CCJLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchMMERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchNOCPERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchCHRERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchSTATERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchBUSERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchINTERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchHARDERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCJLinkUsbSerialNo</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCTcpIpAlt</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkTcpIpSerialNo</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>CCSwoClockAuto</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSwoClockEdit</name>
+ <state>2000</state>
+ </option>
+ <option>
+ <name>OCJLinkTraceSource</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkTraceSourceDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkDeviceName</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>LMIFTDI_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>LmiftdiSpeed</name>
+ <state>500</state>
+ </option>
+ <option>
+ <name>CCLmiftdiDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCLmiftdiLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCLmiFtdiInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCLmiFtdiInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>MACRAIGOR_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>3</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>jtag</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>EmuSpeed</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>DoEmuMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>EmuMultiTarget</name>
+ <state>0@ARM7TDMI</state>
+ </option>
+ <option>
+ <name>EmuHWReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CEmuCommBaud</name>
+ <version>0</version>
+ <state>4</state>
+ </option>
+ <option>
+ <name>CEmuCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>jtago</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>UnusedAddr</name>
+ <state>0x00800000</state>
+ </option>
+ <option>
+ <name>CCMacraigorHWResetDelay</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCJTagBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>CCMacraigorInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCMacraigorInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>PEMICRO_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCPEMicroAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCPEMicroInterfaceList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPEMicroResetDelay</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCPEMicroJtagSpeed</name>
+ <state>#UNINITIALIZED#</state>
+ </option>
+ <option>
+ <name>CCJPEMicroShowSettings</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCPEMicroUSBDevice</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPEMicroSerialPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJPEMicroTCPIPAutoScanNetwork</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCPEMicroTCPIP</name>
+ <state>10.0.0.1</state>
+ </option>
+ <option>
+ <name>CCPEMicroCommCmdLineProducer</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>RDI_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CRDIDriverDll</name>
+ <state>###Uninitialized###</state>
+ </option>
+ <option>
+ <name>CRDILogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRDILogFileEdit</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCRDIHWReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>STLINK_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkResetList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>CCSwoClockAuto</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSwoClockEdit</name>
+ <state>2000</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>THIRDPARTY_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CThirdPartyDriverDll</name>
+ <state>###Uninitialized###</state>
+ </option>
+ <option>
+ <name>CThirdPartyLogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CThirdPartyLogFileEditB</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>XDS100_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCXDS100AttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TIPackageOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>TIPackage</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCXds100InterfaceList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>BoardFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ </data>
+ </settings>
+ <debuggerPlugins>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\middleware\HCCWare\HCCWare.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\AVIX\AVIX.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\CMX\CmxArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\CMX\CmxTinyArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\embOS\embOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\MQX\MQXRtosPlugin.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\OpenRTOS\OpenRTOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\SafeRTOS\SafeRTOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\ThreadX\ThreadXArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\TI-RTOS\tirtosplugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-286-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-III\uCOS-III-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\CodeCoverage\CodeCoverage.ENU.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\Orti\Orti.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\SymList\SymList.ENU.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\uCProbe\uCProbePlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ </debuggerPlugins>
+ </configuration>
+ <configuration>
+ <name>Int Flash DDRData Release</name>
+ <toolchain>
+ <name>ARM</name>
+ </toolchain>
+ <debug>0</debug>
+ <settings>
+ <name>C-SPY</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>26</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>CInput</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CEndian</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCVariant</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>MemOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MemFile</name>
+ <state>$TOOLKIT_DIR$\CONFIG\debugger\Freescale\MK70FN1M0xxx12.ddf</state>
+ </option>
+ <option>
+ <name>RunToEnable</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RunToName</name>
+ <state>main</state>
+ </option>
+ <option>
+ <name>CExtraOptionsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CExtraOptions</name>
+ <state/>
+ </option>
+ <option>
+ <name>CFpuProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCDDFArgumentProducer</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCDownloadSuppressDownload</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDownloadVerifyAll</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProductVersion</name>
+ <state>5.50.0.51907</state>
+ </option>
+ <option>
+ <name>OCDynDriverList</name>
+ <state>JLINK_ID</state>
+ </option>
+ <option>
+ <name>OCLastSavedByProductVersion</name>
+ <state>6.40.2.53991</state>
+ </option>
+ <option>
+ <name>OCDownloadAttachToProgram</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>UseFlashLoader</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CLowLevel</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCBE8Slave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>MacFile2</name>
+ <state/>
+ </option>
+ <option>
+ <name>CDevice</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>FlashLoadersV3</name>
+ <state>$TOOLKIT_DIR$\config\flashloader\Freescale\FlashK70Fxxx128K.board</state>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck1</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath1</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath2</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck3</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath3</name>
+ <state/>
+ </option>
+ <option>
+ <name>OverrideDefFlashBoard</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesOffset1</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesOffset2</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesOffset3</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesUse1</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesUse2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesUse3</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDeviceConfigMacroFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCDebuggerExtraOption</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCAllMTBOptions</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCMulticoreNrOfCores</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCMulticoreMaster</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCMulticorePort</name>
+ <state>53461</state>
+ </option>
+ <option>
+ <name>OCMulticoreWorkspace</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCMulticoreSlaveProject</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCMulticoreSlaveConfiguration</name>
+ <state/>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>ARMSIM_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCSimDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCSimEnablePSP</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCSimPspOverrideConfig</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCSimPspConfigFile</name>
+ <state/>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>ANGEL_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>CCAngelHeartbeat</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CAngelCommunication</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CAngelCommBaud</name>
+ <version>0</version>
+ <state>3</state>
+ </option>
+ <option>
+ <name>CAngelCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ANGELTCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoAngelLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AngelLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>CMSISDAP_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CMSISDAPAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCIarProbeScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CMSISDAPResetList</name>
+ <version>1</version>
+ <state>10</state>
+ </option>
+ <option>
+ <name>CMSISDAPHWResetDuration</name>
+ <state>300</state>
+ </option>
+ <option>
+ <name>CMSISDAPHWResetDelay</name>
+ <state>200</state>
+ </option>
+ <option>
+ <name>CMSISDAPDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CMSISDAPInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiTargetEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPJtagSpeedList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPRestoreBreakpointsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPUpdateBreakpointsEdit</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>RDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchUndef</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchData</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchPrefetch</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchMMERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchNOCPERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchCHKERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchSTATERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchBUSERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchINTERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchHARDERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiCPUEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiCPUNumber</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeCfgOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeConfig</name>
+ <state/>
+ </option>
+ <option>
+ <name>CMSISDAPProbeConfigRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPSelectedCPUBehaviour</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ICpuName</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCJetEmuParams</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>GDBSERVER_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCJTagBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>IARROM_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>CRomLogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRomLogFileEditB</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CRomCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRomCommBaud</name>
+ <version>0</version>
+ <state>7</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>IJET_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>3</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCIarProbeScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetResetList</name>
+ <version>1</version>
+ <state>10</state>
+ </option>
+ <option>
+ <name>IjetHWResetDuration</name>
+ <state>300</state>
+ </option>
+ <option>
+ <name>IjetHWResetDelay</name>
+ <state>200</state>
+ </option>
+ <option>
+ <name>IjetPowerFromProbe</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetPowerRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>IjetInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiTargetEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetScanChainNonARMDevices</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetIRLength</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetJtagSpeedList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetProtocolRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetSwoPin</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>IjetSwoPrescalerList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetRestoreBreakpointsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetUpdateBreakpointsEdit</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>RDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchMMERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchNOCPERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCHKERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchSTATERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchBUSERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchINTERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchHARDERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeCfgOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeConfig</name>
+ <state/>
+ </option>
+ <option>
+ <name>IjetProbeConfigRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiCPUEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiCPUNumber</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetSelectedCPUBehaviour</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ICpuName</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCJetEmuParams</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>JLINK_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>15</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>JLinkSpeed</name>
+ <state>100</state>
+ </option>
+ <option>
+ <name>CCJLinkDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCJLinkHWResetDelay</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>JLinkInitialSpeed</name>
+ <state>32</state>
+ </option>
+ <option>
+ <name>CCDoJlinkMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCScanChainNonARMDevices</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkIRLength</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkCommRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkTCPIP</name>
+ <state>10.171.88.231</state>
+ </option>
+ <option>
+ <name>CCJLinkSpeedRadioV2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCUSBDevice</name>
+ <version>1</version>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCRDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>CCJLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCJLinkResetList</name>
+ <version>6</version>
+ <state>7</state>
+ </option>
+ <option>
+ <name>CCJLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchMMERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchNOCPERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchCHRERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchSTATERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchBUSERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchINTERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchHARDERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCJLinkUsbSerialNo</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCTcpIpAlt</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkTcpIpSerialNo</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>CCSwoClockAuto</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSwoClockEdit</name>
+ <state>2000</state>
+ </option>
+ <option>
+ <name>OCJLinkTraceSource</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkTraceSourceDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkDeviceName</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>LMIFTDI_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>LmiftdiSpeed</name>
+ <state>500</state>
+ </option>
+ <option>
+ <name>CCLmiftdiDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCLmiftdiLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCLmiFtdiInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCLmiFtdiInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>MACRAIGOR_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>3</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>jtag</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>EmuSpeed</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>DoEmuMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>EmuMultiTarget</name>
+ <state>0@ARM7TDMI</state>
+ </option>
+ <option>
+ <name>EmuHWReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CEmuCommBaud</name>
+ <version>0</version>
+ <state>4</state>
+ </option>
+ <option>
+ <name>CEmuCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>jtago</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>UnusedAddr</name>
+ <state>0x00800000</state>
+ </option>
+ <option>
+ <name>CCMacraigorHWResetDelay</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCJTagBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>CCMacraigorInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCMacraigorInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>PEMICRO_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCPEMicroAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCPEMicroInterfaceList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPEMicroResetDelay</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCPEMicroJtagSpeed</name>
+ <state>#UNINITIALIZED#</state>
+ </option>
+ <option>
+ <name>CCJPEMicroShowSettings</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCPEMicroUSBDevice</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPEMicroSerialPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJPEMicroTCPIPAutoScanNetwork</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCPEMicroTCPIP</name>
+ <state>10.0.0.1</state>
+ </option>
+ <option>
+ <name>CCPEMicroCommCmdLineProducer</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>RDI_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>CRDIDriverDll</name>
+ <state>###Uninitialized###</state>
+ </option>
+ <option>
+ <name>CRDILogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRDILogFileEdit</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCRDIHWReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>STLINK_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkResetList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>CCSwoClockAuto</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSwoClockEdit</name>
+ <state>2000</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>THIRDPARTY_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>CThirdPartyDriverDll</name>
+ <state>###Uninitialized###</state>
+ </option>
+ <option>
+ <name>CThirdPartyLogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CThirdPartyLogFileEditB</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>XDS100_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCXDS100AttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TIPackageOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>TIPackage</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCXds100InterfaceList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>BoardFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ </data>
+ </settings>
+ <debuggerPlugins>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\middleware\HCCWare\HCCWare.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\AVIX\AVIX.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\CMX\CmxArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\CMX\CmxTinyArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\embOS\embOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\MQX\MQXRtosPlugin.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\OpenRTOS\OpenRTOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\SafeRTOS\SafeRTOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\ThreadX\ThreadXArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\TI-RTOS\tirtosplugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-286-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-III\uCOS-III-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\CodeCoverage\CodeCoverage.ENU.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\Orti\Orti.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\SymList\SymList.ENU.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\uCProbe\uCProbePlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ </debuggerPlugins>
+ </configuration>
+ <configuration>
+ <name>Int Ram Debug</name>
+ <toolchain>
+ <name>ARM</name>
+ </toolchain>
+ <debug>1</debug>
+ <settings>
+ <name>C-SPY</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>26</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CInput</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CEndian</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCVariant</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>MemOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MemFile</name>
+ <state>$TOOLKIT_DIR$\CONFIG\debugger\Freescale\MK70FN1M0xxx12.ddf</state>
+ </option>
+ <option>
+ <name>RunToEnable</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RunToName</name>
+ <state>main</state>
+ </option>
+ <option>
+ <name>CExtraOptionsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CExtraOptions</name>
+ <state/>
+ </option>
+ <option>
+ <name>CFpuProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCDDFArgumentProducer</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCDownloadSuppressDownload</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDownloadVerifyAll</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProductVersion</name>
+ <state>5.50.0.51907</state>
+ </option>
+ <option>
+ <name>OCDynDriverList</name>
+ <state>JLINK_ID</state>
+ </option>
+ <option>
+ <name>OCLastSavedByProductVersion</name>
+ <state>6.40.2.53991</state>
+ </option>
+ <option>
+ <name>OCDownloadAttachToProgram</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>UseFlashLoader</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CLowLevel</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCBE8Slave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>MacFile2</name>
+ <state/>
+ </option>
+ <option>
+ <name>CDevice</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>FlashLoadersV3</name>
+ <state>$TOOLKIT_DIR$\config\flashloader\Freescale\FlashK70Fxxx128K.board</state>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck1</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath1</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath2</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesSuppressCheck3</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesPath3</name>
+ <state/>
+ </option>
+ <option>
+ <name>OverrideDefFlashBoard</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesOffset1</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesOffset2</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesOffset3</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCImagesUse1</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesUse2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCImagesUse3</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDeviceConfigMacroFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCDebuggerExtraOption</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCAllMTBOptions</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCMulticoreNrOfCores</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCMulticoreMaster</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCMulticorePort</name>
+ <state>53461</state>
+ </option>
+ <option>
+ <name>OCMulticoreWorkspace</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCMulticoreSlaveProject</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCMulticoreSlaveConfiguration</name>
+ <state/>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>ARMSIM_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCSimDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCSimEnablePSP</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCSimPspOverrideConfig</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCSimPspConfigFile</name>
+ <state/>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>ANGEL_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CCAngelHeartbeat</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CAngelCommunication</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CAngelCommBaud</name>
+ <version>0</version>
+ <state>3</state>
+ </option>
+ <option>
+ <name>CAngelCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ANGELTCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoAngelLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AngelLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>CMSISDAP_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CMSISDAPAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCIarProbeScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CMSISDAPResetList</name>
+ <version>1</version>
+ <state>10</state>
+ </option>
+ <option>
+ <name>CMSISDAPHWResetDuration</name>
+ <state>300</state>
+ </option>
+ <option>
+ <name>CMSISDAPHWResetDelay</name>
+ <state>200</state>
+ </option>
+ <option>
+ <name>CMSISDAPDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CMSISDAPInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiTargetEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPJtagSpeedList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPRestoreBreakpointsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPUpdateBreakpointsEdit</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>RDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchUndef</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchData</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchPrefetch</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchMMERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchNOCPERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchCHKERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchSTATERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchBUSERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchINTERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchHARDERR</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiCPUEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPMultiCPUNumber</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeCfgOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeConfig</name>
+ <state/>
+ </option>
+ <option>
+ <name>CMSISDAPProbeConfigRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CMSISDAPSelectedCPUBehaviour</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ICpuName</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCJetEmuParams</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>GDBSERVER_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCJTagBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>IARROM_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CRomLogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRomLogFileEditB</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CRomCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRomCommBaud</name>
+ <version>0</version>
+ <state>7</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>IJET_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>3</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCIarProbeScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetResetList</name>
+ <version>1</version>
+ <state>10</state>
+ </option>
+ <option>
+ <name>IjetHWResetDuration</name>
+ <state>300</state>
+ </option>
+ <option>
+ <name>IjetHWResetDelay</name>
+ <state>200</state>
+ </option>
+ <option>
+ <name>IjetPowerFromProbe</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IjetPowerRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>IjetInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiTargetEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetScanChainNonARMDevices</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetIRLength</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetJtagSpeedList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetProtocolRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetSwoPin</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>IjetSwoPrescalerList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetRestoreBreakpointsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetUpdateBreakpointsEdit</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>RDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>RDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchMMERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchNOCPERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchCHKERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchSTATERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchBUSERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchINTERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchHARDERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeCfgOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCProbeConfig</name>
+ <state/>
+ </option>
+ <option>
+ <name>IjetProbeConfigRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiCPUEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetMultiCPUNumber</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IjetSelectedCPUBehaviour</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ICpuName</name>
+ <state/>
+ </option>
+ <option>
+ <name>OCJetEmuParams</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>JLINK_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>15</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>JLinkSpeed</name>
+ <state>100</state>
+ </option>
+ <option>
+ <name>CCJLinkDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCJLinkHWResetDelay</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>JLinkInitialSpeed</name>
+ <state>32</state>
+ </option>
+ <option>
+ <name>CCDoJlinkMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCScanChainNonARMDevices</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkIRLength</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkCommRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkTCPIP</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCJLinkSpeedRadioV2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCUSBDevice</name>
+ <version>1</version>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCRDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>CCJLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCJLinkResetList</name>
+ <version>6</version>
+ <state>7</state>
+ </option>
+ <option>
+ <name>CCJLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchCORERESET</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchMMERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchNOCPERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchCHRERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchSTATERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchBUSERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchINTERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchHARDERR</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCatchDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkScriptFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCJLinkUsbSerialNo</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCTcpIpAlt</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJLinkTcpIpSerialNo</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>CCSwoClockAuto</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSwoClockEdit</name>
+ <state>2000</state>
+ </option>
+ <option>
+ <name>OCJLinkTraceSource</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkTraceSourceDummy</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCJLinkDeviceName</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>LMIFTDI_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>LmiftdiSpeed</name>
+ <state>500</state>
+ </option>
+ <option>
+ <name>CCLmiftdiDoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCLmiftdiLogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCLmiFtdiInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCLmiFtdiInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>MACRAIGOR_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>3</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>jtag</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>EmuSpeed</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TCPIP</name>
+ <state>aaa.bbb.ccc.ddd</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>DoEmuMultiTarget</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>EmuMultiTarget</name>
+ <state>0@ARM7TDMI</state>
+ </option>
+ <option>
+ <name>EmuHWReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CEmuCommBaud</name>
+ <version>0</version>
+ <state>4</state>
+ </option>
+ <option>
+ <name>CEmuCommPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>jtago</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>UnusedAddr</name>
+ <state>0x00800000</state>
+ </option>
+ <option>
+ <name>CCMacraigorHWResetDelay</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCJTagBreakpointRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagDoUpdateBreakpoints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJTagUpdateBreakpoints</name>
+ <state>_call_main</state>
+ </option>
+ <option>
+ <name>CCMacraigorInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCMacraigorInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>PEMICRO_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCPEMicroAttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCPEMicroInterfaceList</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPEMicroResetDelay</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCPEMicroJtagSpeed</name>
+ <state>#UNINITIALIZED#</state>
+ </option>
+ <option>
+ <name>CCJPEMicroShowSettings</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCPEMicroUSBDevice</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPEMicroSerialPort</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCJPEMicroTCPIPAutoScanNetwork</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCPEMicroTCPIP</name>
+ <state>10.0.0.1</state>
+ </option>
+ <option>
+ <name>CCPEMicroCommCmdLineProducer</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>RDI_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CRDIDriverDll</name>
+ <state>###Uninitialized###</state>
+ </option>
+ <option>
+ <name>CRDILogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CRDILogFileEdit</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>CCRDIHWReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchReset</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchUndef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchSWI</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchData</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchPrefetch</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchIRQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCRDICatchFIQ</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>STLINK_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceRadio</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkInterfaceCmdLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSTLinkResetList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCpuClockEdit</name>
+ <state>72.0</state>
+ </option>
+ <option>
+ <name>CCSwoClockAuto</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSwoClockEdit</name>
+ <state>2000</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>THIRDPARTY_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CThirdPartyDriverDll</name>
+ <state>###Uninitialized###</state>
+ </option>
+ <option>
+ <name>CThirdPartyLogFileCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CThirdPartyLogFileEditB</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>XDS100_ID</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>2</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OCDriverInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OCXDS100AttachSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>TIPackageOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>TIPackage</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCXds100InterfaceList</name>
+ <version>1</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>BoardFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>DoLogfile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>LogFile</name>
+ <state>$PROJ_DIR$\cspycomm.log</state>
+ </option>
+ </data>
+ </settings>
+ <debuggerPlugins>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\middleware\HCCWare\HCCWare.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\AVIX\AVIX.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\CMX\CmxArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\CMX\CmxTinyArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\embOS\embOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\MQX\MQXRtosPlugin.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\OpenRTOS\OpenRTOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\SafeRTOS\SafeRTOSPlugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\ThreadX\ThreadXArmPlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\TI-RTOS\tirtosplugin.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-286-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$TOOLKIT_DIR$\plugins\rtos\uCOS-III\uCOS-III-KA-CSpy.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\CodeCoverage\CodeCoverage.ENU.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\Orti\Orti.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\SymList\SymList.ENU.ewplugin</file>
+ <loadFlag>1</loadFlag>
+ </plugin>
+ <plugin>
+ <file>$EW_DIR$\common\plugins\uCProbe\uCProbePlugin.ENU.ewplugin</file>
+ <loadFlag>0</loadFlag>
+ </plugin>
+ </debuggerPlugins>
+ </configuration>
+</project>
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/iar/sensor_demo.ewp b/examples/imx7_colibri_m4/demo_apps/sensor_demo/iar/sensor_demo.ewp
new file mode 100644
index 0000000..8ef8f27
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/iar/sensor_demo.ewp
@@ -0,0 +1,1891 @@
+<?xml version="1.0" encoding="iso-8859-1"?>
+<project>
+ <fileVersion>2</fileVersion>
+ <configuration>
+ <name>Debug</name>
+ <toolchain>
+ <name>ARM</name>
+ </toolchain>
+ <debug>1</debug>
+ <settings>
+ <name>General</name>
+ <archiveVersion>3</archiveVersion>
+ <data>
+ <version>22</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>ExePath</name>
+ <state>$PROJ_DIR$/debug</state>
+ </option>
+ <option>
+ <name>ObjPath</name>
+ <state>$PROJ_DIR$/debug/obj</state>
+ </option>
+ <option>
+ <name>ListPath</name>
+ <state>$PROJ_DIR$/debug/list</state>
+ </option>
+ <option>
+ <name>Variant</name>
+ <version>20</version>
+ <state>39</state>
+ </option>
+ <option>
+ <name>GEndianMode</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>Input variant</name>
+ <version>3</version>
+ <state>6</state>
+ </option>
+ <option>
+ <name>Input description</name>
+ <state>Automatic choice of formatter.</state>
+ </option>
+ <option>
+ <name>Output variant</name>
+ <version>2</version>
+ <state>5</state>
+ </option>
+ <option>
+ <name>Output description</name>
+ <state>Automatic choice of formatter.</state>
+ </option>
+ <option>
+ <name>GOutputBinary</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>FPU</name>
+ <version>2</version>
+ <state>5</state>
+ </option>
+ <option>
+ <name>OGCoreOrChip</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>GRuntimeLibSelect</name>
+ <version>0</version>
+ <state>1</state>
+ </option>
+ <option>
+ <name>GRuntimeLibSelectSlave</name>
+ <version>0</version>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RTDescription</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OGProductVersion</name>
+ <state>6.50.6.4952</state>
+ </option>
+ <option>
+ <name>OGLastSavedByProductVersion</name>
+ <state>7.20.1.7306</state>
+ </option>
+ <option>
+ <name>GeneralEnableMisra</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>GeneralMisraVerbose</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OGChipSelectEditMenu</name>
+ <state/>
+ </option>
+ <option>
+ <name>GenLowLevelInterface</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>GEndianModeBE</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OGBufferedTerminalOutput</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>GenStdoutInterface</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>GeneralMisraRules98</name>
+ <version>0</version>
+ <state>1000111110110101101110011100111111101110011011000101110111101101100111111111111100110011111001110111001111111111111111111111111</state>
+ </option>
+ <option>
+ <name>GeneralMisraVer</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>GeneralMisraRules04</name>
+ <version>0</version>
+ <state>111101110010111111111000110111111111111111111111111110010111101111010101111111111111111111111111101111111011111001111011111011111111111111111</state>
+ </option>
+ <option>
+ <name>RTConfigPath2</name>
+ <state>$TOOLKIT_DIR$\INC\c\DLib_Config_Normal.h</state>
+ </option>
+ <option>
+ <name>GFPUCoreSlave</name>
+ <version>20</version>
+ <state>39</state>
+ </option>
+ <option>
+ <name>GBECoreSlave</name>
+ <version>20</version>
+ <state>39</state>
+ </option>
+ <option>
+ <name>OGUseCmsis</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OGUseCmsisDspLib</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>GRuntimeLibThreads</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>ICCARM</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>31</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>CCDefines</name>
+
+ <state>__DEBUG</state><state>CPU_IMX7D_M4</state><state>PRINTF_FLOAT_ENABLE</state></option>
+ <option>
+ <name>CCPreprocFile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPreprocComments</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPreprocLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCListCFile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCListCMnemonics</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCListCMessages</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCListAssFile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCListAssSource</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCEnableRemarks</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCDiagSuppress</name>
+ <state>Pa039,Pe068,Pe069,Pa082,Pe177,Pe186,Pe550,Pa050</state>
+ </option>
+ <option>
+ <name>CCDiagRemark</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCDiagWarning</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCDiagError</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCObjPrefix</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCAllowList</name>
+ <version>1</version>
+ <state>00000000</state>
+ </option>
+ <option>
+ <name>CCDebugInfo</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IEndianMode</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IExtraOptionsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IExtraOptions</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCLangConformance</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSignedPlainChar</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCRequirePrototypes</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCMultibyteSupport</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCDiagWarnAreErr</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCompilerRuntimeInfo</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IFpuProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OutputFile</name>
+ <state>$FILE_BNAME$.o</state>
+ </option>
+ <option>
+ <name>CCLibConfigHeader</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>PreInclude</name>
+ <state/>
+ </option>
+ <option>
+ <name>CompilerMisraOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCIncludePath2</name>
+
+ <state>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/portable/IAR/ARM_CM4F</state><state>$PROJ_DIR$/../../../../../platform/CMSIS/Include</state><state>$PROJ_DIR$/../../../../../platform/devices</state><state>$PROJ_DIR$/../../../../../platform/devices/MCIMX7D/include</state><state>$PROJ_DIR$/../../../../../platform/devices/MCIMX7D/startup</state><state>$PROJ_DIR$/../../../../../platform/drivers/inc</state><state>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/include</state><state>$PROJ_DIR$/../../../../../platform/utilities/inc</state><state>$PROJ_DIR$/../../..</state><state>$PROJ_DIR$/../common</state></option>
+ <option>
+ <name>CCStdIncCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCodeSection</name>
+ <state>.text</state>
+ </option>
+ <option>
+ <name>IInterwork2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IProcessorMode2</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCOptLevel</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCOptStrategy</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCOptLevelSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CompilerMisraRules98</name>
+ <version>0</version>
+ <state>1000111110110101101110011100111111101110011011000101110111101101100111111111111100110011111001110111001111111111111111111111111</state>
+ </option>
+ <option>
+ <name>CompilerMisraRules04</name>
+ <version>0</version>
+ <state>111101110010111111111000110111111111111111111111111110010111101111010101111111111111111111111111101111111011111001111011111011111111111111111</state>
+ </option>
+ <option>
+ <name>CCPosIndRopi</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPosIndRwpi</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPosIndNoDynInit</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IccLang</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IccCDialect</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IccAllowVLA</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IccCppDialect</name>
+ <state>2</state>
+ </option>
+ <option>
+ <name>IccExceptions</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IccRTTI</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IccStaticDestr</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IccCppInlineSemantics</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IccCmsis</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IccFloatSemantics</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCOptimizationNoSizeConstraints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCNoLiteralPool</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCOptStrategySlave</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCGuardCalls</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>AARM</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>9</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>AObjPrefix</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>AEndian</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>ACaseSensitivity</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>MacroChars</name>
+ <version>0</version>
+ <state>3</state>
+ </option>
+ <option>
+ <name>AWarnEnable</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>AWarnWhat</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AWarnOne</name>
+ <state/>
+ </option>
+ <option>
+ <name>AWarnRange1</name>
+ <state/>
+ </option>
+ <option>
+ <name>AWarnRange2</name>
+ <state/>
+ </option>
+ <option>
+ <name>ADebug</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>AltRegisterNames</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>ADefines</name>
+
+ <state>__DEBUG</state></option>
+ <option>
+ <name>AList</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AListHeader</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>AListing</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>Includes</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacDefs</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacExps</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>MacExec</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OnlyAssed</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MultiLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>PageLengthCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>PageLength</name>
+ <state>80</state>
+ </option>
+ <option>
+ <name>TabSpacing</name>
+ <state>8</state>
+ </option>
+ <option>
+ <name>AXRef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AXRefDefines</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AXRefInternal</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AXRefDual</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>AFpuProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>AOutputFile</name>
+ <state>$FILE_BNAME$.o</state>
+ </option>
+ <option>
+ <name>AMultibyteSupport</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ALimitErrorsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ALimitErrorsEdit</name>
+ <state>100</state>
+ </option>
+ <option>
+ <name>AIgnoreStdInclude</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AUserIncludes</name>
+
+ <state>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/portable/IAR/ARM_CM4F</state><state>$PROJ_DIR$/../../..</state></option>
+ <option>
+ <name>AExtraOptionsCheckV2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AExtraOptionsV2</name>
+ <state/>
+ </option>
+ <option>
+ <name>AsmNoLiteralPool</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>OBJCOPY</name>
+ <archiveVersion>0</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>OOCOutputFormat</name>
+ <version>2</version>
+ <state>2</state>
+ </option>
+ <option>
+ <name>OCOutputOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OOCOutputFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OOCCommandLineProducer</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OOCObjCopyEnable</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>CUSTOM</name>
+ <archiveVersion>3</archiveVersion>
+ <data>
+ <extensions/>
+ <cmdline/>
+ </data>
+ </settings>
+ <settings>
+ <name>BICOMP</name>
+ <archiveVersion>0</archiveVersion>
+ <data/>
+ </settings>
+ <settings>
+ <name>BUILDACTION</name>
+ <archiveVersion>1</archiveVersion>
+ <data>
+ <prebuild/>
+ <postbuild/>
+ </data>
+ </settings>
+ <settings>
+ <name>ILINK</name>
+ <archiveVersion>0</archiveVersion>
+ <data>
+ <version>16</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>IlinkLibIOConfig</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>XLinkMisraHandler</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkInputFileSlave</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkOutputFile</name>
+ <state>sensor_demo.out</state>
+ </option>
+ <option>
+ <name>IlinkDebugInfoEnable</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkKeepSymbols</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkRawBinaryFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkRawBinarySymbol</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkRawBinarySegment</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkRawBinaryAlign</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkDefines</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkConfigDefines</name>
+
+ <state>__stack_size__=0x400</state><state>__heap_size__=0x200</state></option>
+ <option>
+ <name>IlinkMapFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkLogFile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkLogInitialization</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkLogModule</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkLogSection</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkLogVeneer</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkIcfOverride</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkIcfFile</name>
+ <state>$PROJ_DIR$/../../../../../platform/devices/MCIMX7D/linker/iar/MCIMX7D_M4_tcm.icf</state>
+ </option>
+ <option>
+ <name>IlinkIcfFileSlave</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkEnableRemarks</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkSuppressDiags</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkTreatAsRem</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkTreatAsWarn</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkTreatAsErr</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkWarningsAreErrors</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkUseExtraOptions</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkExtraOptions</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkLowLevelInterfaceSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkAutoLibEnable</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkAdditionalLibs</name>
+
+ </option>
+ <option>
+ <name>IlinkOverrideProgramEntryLabel</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkProgramEntryLabelSelect</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkProgramEntryLabel</name>
+ <state>Reset_Handler</state>
+ </option>
+ <option>
+ <name>DoFill</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>FillerByte</name>
+ <state>0xFF</state>
+ </option>
+ <option>
+ <name>FillerStart</name>
+ <state>0x0</state>
+ </option>
+ <option>
+ <name>FillerEnd</name>
+ <state>0x0</state>
+ </option>
+ <option>
+ <name>CrcSize</name>
+ <version>0</version>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CrcAlign</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CrcPoly</name>
+ <state>0x11021</state>
+ </option>
+ <option>
+ <name>CrcCompl</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CrcBitOrder</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CrcInitialValue</name>
+ <state>0x0</state>
+ </option>
+ <option>
+ <name>DoCrc</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkBE8Slave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkBufferedTerminalOutput</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkStdoutInterfaceSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CrcFullSize</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkIElfToolPostProcess</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkLogAutoLibSelect</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkLogRedirSymbols</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkLogUnusedFragments</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkCrcReverseByteOrder</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkCrcUseAsInput</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkOptInline</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkOptExceptionsAllow</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkOptExceptionsForce</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkCmsis</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkOptMergeDuplSections</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkOptUseVfe</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkOptForceVfe</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkStackAnalysisEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkStackControlFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkStackCallGraphFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>CrcAlgorithm</name>
+ <version>0</version>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CrcUnitSize</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkThreadsSlave</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>IARCHIVE</name>
+ <archiveVersion>0</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>1</debug>
+ <option>
+ <name>IarchiveInputs</name>
+ <state/>
+ </option>
+ <option>
+ <name>IarchiveOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IarchiveOutput</name>
+ <state>###Unitialized###</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>BILINK</name>
+ <archiveVersion>0</archiveVersion>
+ <data/>
+ </settings>
+ </configuration>
+ <configuration>
+ <name>Release</name>
+ <toolchain>
+ <name>ARM</name>
+ </toolchain>
+ <debug>0</debug>
+ <settings>
+ <name>General</name>
+ <archiveVersion>3</archiveVersion>
+ <data>
+ <version>22</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>ExePath</name>
+ <state>$PROJ_DIR$/release</state>
+ </option>
+ <option>
+ <name>ObjPath</name>
+ <state>$PROJ_DIR$/release/obj</state>
+ </option>
+ <option>
+ <name>ListPath</name>
+ <state>$PROJ_DIR$/release/list</state>
+ </option>
+ <option>
+ <name>Variant</name>
+ <version>20</version>
+ <state>39</state>
+ </option>
+ <option>
+ <name>GEndianMode</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>Input variant</name>
+ <version>3</version>
+ <state>6</state>
+ </option>
+ <option>
+ <name>Input description</name>
+ <state>Automatic choice of formatter.</state>
+ </option>
+ <option>
+ <name>Output variant</name>
+ <version>2</version>
+ <state>5</state>
+ </option>
+ <option>
+ <name>Output description</name>
+ <state>Automatic choice of formatter.</state>
+ </option>
+ <option>
+ <name>GOutputBinary</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>FPU</name>
+ <version>2</version>
+ <state>5</state>
+ </option>
+ <option>
+ <name>OGCoreOrChip</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>GRuntimeLibSelect</name>
+ <version>0</version>
+ <state>1</state>
+ </option>
+ <option>
+ <name>GRuntimeLibSelectSlave</name>
+ <version>0</version>
+ <state>1</state>
+ </option>
+ <option>
+ <name>RTDescription</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OGProductVersion</name>
+ <state>6.50.6.4952</state>
+ </option>
+ <option>
+ <name>OGLastSavedByProductVersion</name>
+ <state>7.20.1.7306</state>
+ </option>
+ <option>
+ <name>GeneralEnableMisra</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>GeneralMisraVerbose</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OGChipSelectEditMenu</name>
+ <state/>
+ </option>
+ <option>
+ <name>GenLowLevelInterface</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>GEndianModeBE</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OGBufferedTerminalOutput</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>GenStdoutInterface</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>GeneralMisraRules98</name>
+ <version>0</version>
+ <state>1000111110110101101110011100111111101110011011000101110111101101100111111111111100110011111001110111001111111111111111111111111</state>
+ </option>
+ <option>
+ <name>GeneralMisraVer</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>GeneralMisraRules04</name>
+ <version>0</version>
+ <state>111101110010111111111000110111111111111111111111111110010111101111010101111111111111111111111111101111111011111001111011111011111111111111111</state>
+ </option>
+ <option>
+ <name>RTConfigPath2</name>
+ <state>$TOOLKIT_DIR$\INC\c\DLib_Config_Normal.h</state>
+ </option>
+ <option>
+ <name>GFPUCoreSlave</name>
+ <version>20</version>
+ <state>39</state>
+ </option>
+ <option>
+ <name>GBECoreSlave</name>
+ <version>20</version>
+ <state>39</state>
+ </option>
+ <option>
+ <name>OGUseCmsis</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OGUseCmsisDspLib</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>GRuntimeLibThreads</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>ICCARM</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>31</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>CCDefines</name>
+
+ <state>__NDEBUG</state><state>CPU_IMX7D_M4</state><state>PRINTF_FLOAT_ENABLE</state></option>
+ <option>
+ <name>CCPreprocFile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPreprocComments</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPreprocLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCListCFile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCListCMnemonics</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCListCMessages</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCListAssFile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCListAssSource</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCEnableRemarks</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCDiagSuppress</name>
+ <state>Pa039,Pe068,Pe069,Pa082,Pe177,Pe186,Pe550,Pa050</state>
+ </option>
+ <option>
+ <name>CCDiagRemark</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCDiagWarning</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCDiagError</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCObjPrefix</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCAllowList</name>
+ <version>1</version>
+ <state>00010000</state>
+ </option>
+ <option>
+ <name>CCDebugInfo</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IEndianMode</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IExtraOptionsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IExtraOptions</name>
+ <state/>
+ </option>
+ <option>
+ <name>CCLangConformance</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCSignedPlainChar</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCRequirePrototypes</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCMultibyteSupport</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCDiagWarnAreErr</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCompilerRuntimeInfo</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IFpuProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OutputFile</name>
+ <state>$FILE_BNAME$.o</state>
+ </option>
+ <option>
+ <name>CCLibConfigHeader</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>PreInclude</name>
+ <state/>
+ </option>
+ <option>
+ <name>CompilerMisraOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCIncludePath2</name>
+
+ <state>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/portable/IAR/ARM_CM4F</state><state>$PROJ_DIR$/../../../../../platform/CMSIS/Include</state><state>$PROJ_DIR$/../../../../../platform/devices</state><state>$PROJ_DIR$/../../../../../platform/devices/MCIMX7D/include</state><state>$PROJ_DIR$/../../../../../platform/devices/MCIMX7D/startup</state><state>$PROJ_DIR$/../../../../../platform/drivers/inc</state><state>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/include</state><state>$PROJ_DIR$/../../../../../platform/utilities/inc</state><state>$PROJ_DIR$/../../..</state><state>$PROJ_DIR$/../common</state></option>
+ <option>
+ <name>CCStdIncCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCCodeSection</name>
+ <state>.text</state>
+ </option>
+ <option>
+ <name>IInterwork2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IProcessorMode2</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CCOptLevel</name>
+ <state>3</state>
+ </option>
+ <option>
+ <name>CCOptStrategy</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCOptLevelSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CompilerMisraRules98</name>
+ <version>0</version>
+ <state>1000111110110101101110011100111111101110011011000101110111101101100111111111111100110011111001110111001111111111111111111111111</state>
+ </option>
+ <option>
+ <name>CompilerMisraRules04</name>
+ <version>0</version>
+ <state>111101110010111111111000110111111111111111111111111110010111101111010101111111111111111111111111101111111011111001111011111011111111111111111</state>
+ </option>
+ <option>
+ <name>CCPosIndRopi</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPosIndRwpi</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCPosIndNoDynInit</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IccLang</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IccCDialect</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IccAllowVLA</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IccCppDialect</name>
+ <state>2</state>
+ </option>
+ <option>
+ <name>IccExceptions</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IccRTTI</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IccStaticDestr</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IccCppInlineSemantics</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IccCmsis</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IccFloatSemantics</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCOptimizationNoSizeConstraints</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCNoLiteralPool</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCOptStrategySlave</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CCGuardCalls</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>AARM</name>
+ <archiveVersion>2</archiveVersion>
+ <data>
+ <version>9</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>AObjPrefix</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>AEndian</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>ACaseSensitivity</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>MacroChars</name>
+ <version>0</version>
+ <state>3</state>
+ </option>
+ <option>
+ <name>AWarnEnable</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>AWarnWhat</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AWarnOne</name>
+ <state/>
+ </option>
+ <option>
+ <name>AWarnRange1</name>
+ <state/>
+ </option>
+ <option>
+ <name>AWarnRange2</name>
+ <state/>
+ </option>
+ <option>
+ <name>ADebug</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AltRegisterNames</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>ADefines</name>
+
+ </option>
+ <option>
+ <name>AList</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AListHeader</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>AListing</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>Includes</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacDefs</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MacExps</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>MacExec</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OnlyAssed</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>MultiLine</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>PageLengthCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>PageLength</name>
+ <state>80</state>
+ </option>
+ <option>
+ <name>TabSpacing</name>
+ <state>8</state>
+ </option>
+ <option>
+ <name>AXRef</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AXRefDefines</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AXRefInternal</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AXRefDual</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>AFpuProcessor</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>AOutputFile</name>
+ <state>$FILE_BNAME$.o</state>
+ </option>
+ <option>
+ <name>AMultibyteSupport</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ALimitErrorsCheck</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>ALimitErrorsEdit</name>
+ <state>100</state>
+ </option>
+ <option>
+ <name>AIgnoreStdInclude</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AUserIncludes</name>
+
+ <state>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/portable/IAR/ARM_CM4F</state><state>$PROJ_DIR$/../../..</state></option>
+ <option>
+ <name>AExtraOptionsCheckV2</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>AExtraOptionsV2</name>
+ <state/>
+ </option>
+ <option>
+ <name>AsmNoLiteralPool</name>
+ <state>0</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>OBJCOPY</name>
+ <archiveVersion>0</archiveVersion>
+ <data>
+ <version>1</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>OOCOutputFormat</name>
+ <version>2</version>
+ <state>2</state>
+ </option>
+ <option>
+ <name>OCOutputOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>OOCOutputFile</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OOCCommandLineProducer</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>OOCObjCopyEnable</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>CUSTOM</name>
+ <archiveVersion>3</archiveVersion>
+ <data>
+ <extensions/>
+ <cmdline/>
+ </data>
+ </settings>
+ <settings>
+ <name>BICOMP</name>
+ <archiveVersion>0</archiveVersion>
+ <data/>
+ </settings>
+ <settings>
+ <name>BUILDACTION</name>
+ <archiveVersion>1</archiveVersion>
+ <data>
+ <prebuild/>
+ <postbuild/>
+ </data>
+ </settings>
+ <settings>
+ <name>ILINK</name>
+ <archiveVersion>0</archiveVersion>
+ <data>
+ <version>16</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>IlinkLibIOConfig</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>XLinkMisraHandler</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkInputFileSlave</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkOutputFile</name>
+ <state>sensor_demo.out</state>
+ </option>
+ <option>
+ <name>IlinkDebugInfoEnable</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkKeepSymbols</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkRawBinaryFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkRawBinarySymbol</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkRawBinarySegment</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkRawBinaryAlign</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkDefines</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkConfigDefines</name>
+
+ <state>__stack_size__=0x400</state><state>__heap_size__=0x200</state></option>
+ <option>
+ <name>IlinkMapFile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkLogFile</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkLogInitialization</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkLogModule</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkLogSection</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkLogVeneer</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkIcfOverride</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkIcfFile</name>
+ <state>$PROJ_DIR$/../../../../../platform/devices/MCIMX7D/linker/iar/MCIMX7D_M4_tcm.icf</state>
+ </option>
+ <option>
+ <name>IlinkIcfFileSlave</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkEnableRemarks</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkSuppressDiags</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkTreatAsRem</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkTreatAsWarn</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkTreatAsErr</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkWarningsAreErrors</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkUseExtraOptions</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkExtraOptions</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkLowLevelInterfaceSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkAutoLibEnable</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkAdditionalLibs</name>
+
+ </option>
+ <option>
+ <name>IlinkOverrideProgramEntryLabel</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkProgramEntryLabelSelect</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkProgramEntryLabel</name>
+ <state>Reset_Handler</state>
+ </option>
+ <option>
+ <name>DoFill</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>FillerByte</name>
+ <state>0xFF</state>
+ </option>
+ <option>
+ <name>FillerStart</name>
+ <state>0x0</state>
+ </option>
+ <option>
+ <name>FillerEnd</name>
+ <state>0x0</state>
+ </option>
+ <option>
+ <name>CrcSize</name>
+ <version>0</version>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CrcAlign</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CrcPoly</name>
+ <state>0x11021</state>
+ </option>
+ <option>
+ <name>CrcCompl</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CrcBitOrder</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>CrcInitialValue</name>
+ <state>0x0</state>
+ </option>
+ <option>
+ <name>DoCrc</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkBE8Slave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkBufferedTerminalOutput</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkStdoutInterfaceSlave</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CrcFullSize</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkIElfToolPostProcess</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkLogAutoLibSelect</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkLogRedirSymbols</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkLogUnusedFragments</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkCrcReverseByteOrder</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkCrcUseAsInput</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkOptInline</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkOptExceptionsAllow</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkOptExceptionsForce</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkCmsis</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkOptMergeDuplSections</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkOptUseVfe</name>
+ <state>1</state>
+ </option>
+ <option>
+ <name>IlinkOptForceVfe</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkStackAnalysisEnable</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkStackControlFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>IlinkStackCallGraphFile</name>
+ <state/>
+ </option>
+ <option>
+ <name>CrcAlgorithm</name>
+ <version>0</version>
+ <state>1</state>
+ </option>
+ <option>
+ <name>CrcUnitSize</name>
+ <version>0</version>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IlinkThreadsSlave</name>
+ <state>1</state>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>IARCHIVE</name>
+ <archiveVersion>0</archiveVersion>
+ <data>
+ <version>0</version>
+ <wantNonLocal>1</wantNonLocal>
+ <debug>0</debug>
+ <option>
+ <name>IarchiveInputs</name>
+ <state/>
+ </option>
+ <option>
+ <name>IarchiveOverride</name>
+ <state>0</state>
+ </option>
+ <option>
+ <name>IarchiveOutput</name>
+ <state/>
+ </option>
+ </data>
+ </settings>
+ <settings>
+ <name>BILINK</name>
+ <archiveVersion>0</archiveVersion>
+ <data/>
+ </settings>
+ </configuration>
+
+
+
+
+
+<group><name>freertos</name><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/portable/IAR/ARM_CM4F/port.c</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/portable/IAR/ARM_CM4F/portasm.s</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/portable/IAR/ARM_CM4F/portmacro.h</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/portable/MemMang/heap_2.c</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/include/croutine.h</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/include/event_groups.h</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/include/FreeRTOS.h</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/include/list.h</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/include/mpu_wrappers.h</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/include/portable.h</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/include/projdefs.h</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/include/queue.h</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/include/semphr.h</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/include/StackMacros.h</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/include/task.h</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/include/timers.h</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/croutine.c</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/event_groups.c</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/list.c</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/queue.c</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/tasks.c</name></file><file><name>$PROJ_DIR$/../../../../../rtos/FreeRTOS/Source/timers.c</name></file></group><group><name>startup</name><file><name>$PROJ_DIR$/../../../../../platform/devices/MCIMX7D/startup/iar/startup_MCIMX7D_M4.s</name></file><file><name>$PROJ_DIR$/../../../../../platform/devices/MCIMX7D/startup/system_MCIMX7D_M4.c</name></file><file><name>$PROJ_DIR$/../../../../../platform/devices/MCIMX7D/startup/system_MCIMX7D_M4.h</name></file></group><group><name>board</name><file><name>$PROJ_DIR$/../../../FreeRTOSConfig.h</name></file><file><name>$PROJ_DIR$/../../../pin_mux.c</name></file><file><name>$PROJ_DIR$/../../../pin_mux.h</name></file><file><name>$PROJ_DIR$/../../../board.c</name></file><file><name>$PROJ_DIR$/../../../board.h</name></file><file><name>$PROJ_DIR$/../../../clock_freq.c</name></file><file><name>$PROJ_DIR$/../../../clock_freq.h</name></file><file><name>$PROJ_DIR$/../hardware_init.c</name></file></group><group><name>source</name><file><name>$PROJ_DIR$/../sensor_demo_imx7d/main.c</name></file><file><name>$PROJ_DIR$/../common/i2c_xfer.c</name></file><file><name>$PROJ_DIR$/../common/i2c_xfer.h</name></file><file><name>$PROJ_DIR$/../common/mpl3115.c</name></file><file><name>$PROJ_DIR$/../common/mpl3115.h</name></file><file><name>$PROJ_DIR$/../common/fxos8700.c</name></file><file><name>$PROJ_DIR$/../common/fxos8700.h</name></file><file><name>$PROJ_DIR$/../common/fxas21002.c</name></file><file><name>$PROJ_DIR$/../common/fxas21002.h</name></file></group><group><name>driver</name><file><name>$PROJ_DIR$/../../../../../platform/drivers/src/i2c_imx.c</name></file><file><name>$PROJ_DIR$/../../../../../platform/drivers/inc/i2c_imx.h</name></file><file><name>$PROJ_DIR$/../../../../../platform/drivers/src/uart_imx.c</name></file><file><name>$PROJ_DIR$/../../../../../platform/drivers/inc/uart_imx.h</name></file></group><group><name>system</name><file><name>$PROJ_DIR$/../../../../../platform/drivers/inc/ccm_analog_imx7d.h</name></file><file><name>$PROJ_DIR$/../../../../../platform/drivers/inc/ccm_imx7d.h</name></file><file><name>$PROJ_DIR$/../../../../../platform/drivers/inc/rdc.h</name></file><file><name>$PROJ_DIR$/../../../../../platform/drivers/inc/rdc_defs_imx7d.h</name></file><file><name>$PROJ_DIR$/../../../../../platform/drivers/inc/wdog_imx.h</name></file><file><name>$PROJ_DIR$/../../../../../platform/drivers/src/ccm_analog_imx7d.c</name></file><file><name>$PROJ_DIR$/../../../../../platform/drivers/src/ccm_imx7d.c</name></file><file><name>$PROJ_DIR$/../../../../../platform/drivers/src/rdc.c</name></file><file><name>$PROJ_DIR$/../../../../../platform/drivers/src/wdog_imx.c</name></file></group><group><name>utilities</name><file><name>$PROJ_DIR$/../../../../../platform/utilities/src/debug_console_imx.c</name></file><file><name>$PROJ_DIR$/../../../../../platform/utilities/inc/debug_console_imx.h</name></file><file><name>$PROJ_DIR$/../../../../../platform/utilities/src/print_scan.c</name></file><file><name>$PROJ_DIR$/../../../../../platform/utilities/src/print_scan.h</name></file></group></project>
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/iar/sensor_demo.eww b/examples/imx7_colibri_m4/demo_apps/sensor_demo/iar/sensor_demo.eww
new file mode 100644
index 0000000..f300b1c
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/iar/sensor_demo.eww
@@ -0,0 +1,4 @@
+<?xml version="1.0" encoding="iso-8859-1"?>
+<workspace>
+<batchBuild><batchDefinition><name>all</name><member><project>sensor_demo</project><configuration>Release</configuration></member><member><project>sensor_demo</project><configuration>Debug</configuration></member></batchDefinition><batchDefinition><name>Release</name><member><project>sensor_demo</project><configuration>Release</configuration></member></batchDefinition><batchDefinition><name>Debug</name><member><project>sensor_demo</project><configuration>Debug</configuration></member></batchDefinition></batchBuild>
+<project><path>$WS_DIR$/sensor_demo.ewp</path></project></workspace>
diff --git a/examples/imx7_colibri_m4/demo_apps/sensor_demo/sensor_demo_imx7d/main.c b/examples/imx7_colibri_m4/demo_apps/sensor_demo/sensor_demo_imx7d/main.c
new file mode 100644
index 0000000..6f87be1
--- /dev/null
+++ b/examples/imx7_colibri_m4/demo_apps/sensor_demo/sensor_demo_imx7d/main.c
@@ -0,0 +1,237 @@
+/*
+ * Copyright (c) 2015, 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
+///////////////////////////////////////////////////////////////////////////////
+#include <stdint.h>
+#include <stdbool.h>
+#include "FreeRTOS.h"
+#include "task.h"
+#include "board.h"
+#include "debug_console_imx.h"
+#include "i2c_xfer.h"
+#include "fxas21002.h"
+#include "fxos8700.h"
+#include "mpl3115.h"
+
+////////////////////////////////////////////////////////////////////////////////
+// Definition
+////////////////////////////////////////////////////////////////////////////////
+#define HEIGHT_UPDATE_THRESHOLD (0.5f)
+#define TEMP_UPDATE_THRESHOLD (0.3f)
+#define GYRO_UPDATE_THRESHOLD (5.0f)
+
+////////////////////////////////////////////////////////////////////////////////
+// Code
+////////////////////////////////////////////////////////////////////////////////
+void fxas21002Demo(void)
+{
+ gyro_sensor_t thisGyroSensor;
+ uint32_t count = 0, printCount = 0;
+
+ PRINTF("\n\r-------------- FXAS21002 Gyro data acquisition --------------\n\r\n\r");
+
+ PRINTF("FXAS21002 initialization ... ");
+ if (fxas21002_init(&thisGyroSensor))
+ PRINTF("OK\n\r");
+ else
+ PRINTF("ERROR\n\r");
+
+ /* delay 10ms to wait sensor init finish */
+ vTaskDelay(10);
+
+ while(1)
+ {
+ fxas21002_read_data(&thisGyroSensor);
+ thisGyroSensor.iSumYpFast[0] += thisGyroSensor.iYpFast[0];
+ thisGyroSensor.iSumYpFast[1] += thisGyroSensor.iYpFast[1];
+ thisGyroSensor.iSumYpFast[2] += thisGyroSensor.iYpFast[2];
+
+ count++;
+ if (count == OVERSAMPLE_RATIO)
+ {
+ count = 0;
+ thisGyroSensor.iYp[0] = thisGyroSensor.iSumYpFast[0] / OVERSAMPLE_RATIO;
+ thisGyroSensor.iYp[1] = thisGyroSensor.iSumYpFast[1] / OVERSAMPLE_RATIO;
+ thisGyroSensor.iYp[2] = thisGyroSensor.iSumYpFast[2] / OVERSAMPLE_RATIO;
+ thisGyroSensor.fYp[0] = thisGyroSensor.iYp[0] * thisGyroSensor.fDegPerSecPerCount;
+ thisGyroSensor.fYp[1] = thisGyroSensor.iYp[1] * thisGyroSensor.fDegPerSecPerCount;
+ thisGyroSensor.fYp[2] = thisGyroSensor.iYp[2] * thisGyroSensor.fDegPerSecPerCount;
+ thisGyroSensor.iSumYpFast[0] = 0;
+ thisGyroSensor.iSumYpFast[1] = 0;
+ thisGyroSensor.iSumYpFast[2] = 0;
+ }
+
+ if ((thisGyroSensor.fYp[0] > GYRO_UPDATE_THRESHOLD) ||
+ (thisGyroSensor.fYp[0] < -GYRO_UPDATE_THRESHOLD) ||
+ (thisGyroSensor.fYp[1] > GYRO_UPDATE_THRESHOLD) ||
+ (thisGyroSensor.fYp[1] < -GYRO_UPDATE_THRESHOLD) ||
+ (thisGyroSensor.fYp[2] > GYRO_UPDATE_THRESHOLD) ||
+ (thisGyroSensor.fYp[2] < -GYRO_UPDATE_THRESHOLD))
+ {
+ printCount++;
+ if (40 == printCount)
+ {
+ printCount = 0;
+ PRINTF("[FXAS21002] Rotate detected: X:%5.1fdps, Y:%5.1fdps, Z:%5.1fdps\n\r",\
+ thisGyroSensor.fYp[0], thisGyroSensor.fYp[1], thisGyroSensor.fYp[2]);
+ }
+ }
+ }
+}
+
+void fxos8700Demo(void)
+{
+ int16_t Ax, Ay, Az, Mx, My, Mz;
+ float Axf, Ayf, Azf, Mxf, Myf, Mzf;
+
+ PRINTF("\n\r-------------- FXOS8700 Acc+Mag data acquisition --------------\n\r\n\r");
+
+ PRINTF("FXOS8700 initialization ... ");
+ if (fxos8700_init())
+ PRINTF("OK\n\r");
+ else
+ PRINTF("ERROR\n\r");
+
+ while(1)
+ {
+ vTaskDelay(500);
+ fxos8700_read_data(&Ax, &Ay, &Az, &Mx, &My, &Mz);
+ Axf = Ax / 8192.0;
+ Ayf = Ay / 8192.0;
+ Azf = Az / 8192.0;
+ Mxf = Mx * 0.1;
+ Myf = My * 0.1;
+ Mzf = Mz * 0.1;
+ PRINTF("[FXOS8700]Current Acc:X=%7.1fg Y=%7.1fg Z=%7.1fg\n\r",Axf, Ayf, Azf);
+ PRINTF("[FXOS8700]Current Mag:X=%6.1fuT Y=%6.1fuT Z=%6.1fuT\n\r",Mxf, Myf, Mzf);
+ }
+}
+
+void mpl3115Demo(void)
+{
+ pressure_sensor_t thisPressureSensor;
+ float lastHight = 0, lastTemp = 0;
+
+ PRINTF("\n\r-------------- MPL3115 Pressure data acquisition --------------\n\r\n\r");
+
+ PRINTF("MPL3115 initialization ... ");
+ if (mpl3115_init(&thisPressureSensor))
+ PRINTF("OK\n\r");
+ else
+ PRINTF("ERROR\n\r");
+
+ while(1)
+ {
+ vTaskDelay(100);
+ mpl3115_read_data(&thisPressureSensor);
+ thisPressureSensor.iHp = thisPressureSensor.iHpFast;;
+ thisPressureSensor.iTp = thisPressureSensor.iTpFast;
+ thisPressureSensor.fHp = (float) thisPressureSensor.iHp *\
+ thisPressureSensor.fmPerCount;
+ thisPressureSensor.fTp = (float) thisPressureSensor.iTp *\
+ thisPressureSensor.fCPerCount;
+ if (((thisPressureSensor.fHp - lastHight) > HEIGHT_UPDATE_THRESHOLD) ||
+ ((thisPressureSensor.fHp - lastHight) < -HEIGHT_UPDATE_THRESHOLD) ||
+ ((thisPressureSensor.fTp - lastTemp) > TEMP_UPDATE_THRESHOLD) ||
+ ((thisPressureSensor.fTp - lastTemp) < -TEMP_UPDATE_THRESHOLD))
+ {
+ lastHight = thisPressureSensor.fHp;
+ lastTemp = thisPressureSensor.fTp;
+ PRINTF("[MPL3115]Current Height = %6.1fMeter, Current Temp = %5.1fCelsius\n\r",
+ thisPressureSensor.fHp,
+ thisPressureSensor.fTp);
+ }
+ }
+}
+
+void MainTask(void *pvParameters)
+{
+ uint8_t demoSel;
+
+ PRINTF("\n\r-------------- iMX7D SDB on board sensor example --------------\n\r\n\r");
+
+ /* Setup I2C init structure. */
+ i2c_init_config_t i2cInitConfig = {
+ .clockRate = get_i2c_clock_freq(BOARD_I2C_BASEADDR),
+ .baudRate = 400000u,
+ .slaveAddress = 0x00
+ };
+
+ /* Initialize I2C module with I2C init structure. */
+ I2C_XFER_Config(&i2cInitConfig);
+
+ /* Print the initial banner. */
+ PRINTF("\n\rPlease select the sensor demo you want to run:\n\r");
+ PRINTF("[1].FXAS21002 3-axes Gyro sensor\n\r");
+ PRINTF("[2].FXOS8700 6-axes Acc+Mag sensor\n\r");
+ PRINTF("[3].MPL3115 Pressure sensor\n\r");
+
+ while(1)
+ {
+ demoSel = GETCHAR();
+ if (('1' == demoSel) || ('2' == demoSel) || ('3' == demoSel))
+ break;
+ }
+
+ switch(demoSel)
+ {
+ case '1':
+ fxas21002Demo();
+ break;
+ case '2':
+ fxos8700Demo();
+ break;
+ case '3':
+ mpl3115Demo();
+ break;
+ }
+}
+
+int main(void)
+{
+ /* Initialize board specified hardware. */
+ hardware_init();
+
+ /* Create a the APP main task. */
+ xTaskCreate(MainTask, "Main Task", configMINIMAL_STACK_SIZE + 100,
+ NULL, tskIDLE_PRIORITY+1, NULL);
+
+ /* Start FreeRTOS scheduler. */
+ vTaskStartScheduler();
+
+ /* should never reach this point. */
+ while (true);
+}
+
+/*******************************************************************************
+ * EOF
+ ******************************************************************************/