summaryrefslogtreecommitdiff
path: root/examples/imx7_colibri_m4/demo_apps/sensor_demo/common
diff options
context:
space:
mode:
Diffstat (limited to 'examples/imx7_colibri_m4/demo_apps/sensor_demo/common')
-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
10 files changed, 1355 insertions, 0 deletions
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
+ ******************************************************************************/