1
0
mirror of https://github.com/RIOT-OS/RIOT.git synced 2024-12-29 04:50:03 +01:00

Merge pull request #6153 from haukepetersen/opt_driver_mma8x5x

drivers/mma8x5x: remodeled driver
This commit is contained in:
Peter Kietzmann 2017-01-19 09:56:31 +01:00 committed by GitHub
commit 616d35e96f
24 changed files with 941 additions and 976 deletions

View File

@ -3,6 +3,6 @@ ifneq (,$(filter netdev_default gnrc_netdev_default,$(USEMODULE)))
endif
ifneq (,$(filter saul_default,$(USEMODULE)))
USEMODULE += mma8652
USEMODULE += mma8x5x
USEMODULE += hdc1000
endif

View File

@ -79,7 +79,7 @@ extern "C"
* @name Define the interface for the HDC1000 humidity sensor
* @{
*/
#define HDC1000_I2C (I2C_0)
#define HDC1000_I2C (I2C_DEV(0))
#define HDC1000_ADDR (0x43)
/** @} */
@ -87,7 +87,7 @@ extern "C"
* @name Define the interface for the MAG3110 magnetometer sensor
* @{
*/
#define MAG3110_I2C (I2C_0)
#define MAG3110_I2C (I2C_DEV(0))
#define MAG3110_ADDR (0x0E)
/** @} */
@ -95,7 +95,7 @@ extern "C"
* @name Define the interface for the MMA8652 tri-axis accelerometer sensor
* @{
*/
#define MMA8652_I2C (I2C_0)
#define MMA8652_I2C (I2C_DEV(0))
#define MMA8652_ADDR (0x1D)
/** @} */
@ -103,7 +103,7 @@ extern "C"
* @name Define the interface for the MPL3115A2 pressure sensor
* @{
*/
#define MPL3115A2_I2C (I2C_0)
#define MPL3115A2_I2C (I2C_DEV(0))
#define MPL3115A2_ADDR (0x60)
/** @} */
@ -111,7 +111,7 @@ extern "C"
* @name Define the interface for the TCS3772 light sensor
* @{
*/
#define TCS37727_I2C (I2C_0)
#define TCS37727_I2C (I2C_DEV(0))
#define TCS37727_ADDR (0x29)
/** @} */
@ -119,7 +119,7 @@ extern "C"
* @name Define the interface for the TMP006 IR-Termopile sensor
* @{
*/
#define TMP006_I2C (I2C_0)
#define TMP006_I2C (I2C_DEV(0))
#define TMP006_ADDR (0x41)
/** @} */

View File

@ -1,58 +0,0 @@
/*
* Copyright (C) 2016 Freie Universität Berlin
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup boards_pba-d-01-kw2x
* @{
*
* @file
* @brief MMA8652 board specific configuration
*
* @author Cenk Gündoğan <mail@cgundogan.de>
*/
#ifndef MMA8652_PARAMS_H
#define MMA8652_PARAMS_H
#include "board.h"
#include "saul_reg.h"
#include "mma8652.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief MMA852 configuration
*/
static const mma8652_params_t mma8652_params[] =
{
{
.i2c = MMA8652_I2C,
.addr = MMA8652_ADDR,
.rate = MMA8652_DATARATE_DEFAULT,
.scale = MMA8652_FS_RANGE_DEFAULT,
},
};
/**
* @brief Additional meta information to keep in the SAUL registry
*/
static const saul_reg_info_t mma8652_saul_info[] =
{
{
.name = "mma8652",
},
};
#ifdef __cplusplus
}
#endif
#endif /* MMA8652_PARAMS_H */
/** @} */

View File

@ -0,0 +1,61 @@
/*
* Copyright (C) 2016 Freie Universität Berlin
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup boards_pba-d-01-kw2x
* @{
*
* @file
* @brief MMA8x5x board specific configuration
*
* @author Cenk Gündoğan <mail@cgundogan.de>
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*/
#ifndef MMA8X5X_PARAMS_H
#define MMA8X5X_PARAMS_H
#include "board.h"
#include "saul_reg.h"
#include "mma8x5x.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief MMA852 configuration
*/
static const mma8x5x_params_t mma8x5x_params[] =
{
{
.i2c = MMA8652_I2C,
.addr = MMA8652_ADDR,
.type = MMA8X5X_TYPE_MMA8652,
.rate = MMA8X5X_RATE_200HZ,
.range = MMA8X5X_RANGE_2G,
.offset = { 0, 0, 0 }
}
};
/**
* @brief Additional meta information to keep in the SAUL registry
*/
static const saul_reg_info_t mma8x5x_saul_info[] =
{
{
.name = "mma8652"
}
};
#ifdef __cplusplus
}
#endif
#endif /* MMA8X5X_PARAMS_H */
/** @} */

View File

@ -34,8 +34,8 @@ endif
ifneq (,$(filter mpl3115a2,$(USEMODULE)))
USEMODULE_INCLUDES += $(RIOTBASE)/drivers/mpl3115a2/include
endif
ifneq (,$(filter mma8652,$(USEMODULE)))
USEMODULE_INCLUDES += $(RIOTBASE)/drivers/mma8652/include
ifneq (,$(filter mma8x5x,$(USEMODULE)))
USEMODULE_INCLUDES += $(RIOTBASE)/drivers/mma8x5x/include
endif
ifneq (,$(filter mag3110,$(USEMODULE)))
USEMODULE_INCLUDES += $(RIOTBASE)/drivers/mag3110/include

View File

@ -1,199 +0,0 @@
/*
* Copyright (C) 2014 PHYTEC Messtechnik GmbH
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @defgroup drivers_mma8652 MMA8652 Accelerometer
* @ingroup drivers_sensors
* @brief Driver for the Freescale MMA8652 3-Axis accelerometer.
* The driver will initialize the accelerometer for
* best resolution (12 bit).
* After initialization and set activ the accelerometer
* will make measurements at periodic times.
* The measurements period and scale range can be determined by
* accelerometer initialization.
* This driver only implements basic functionality.
*
* @{
*
* @file
* @brief Interface definition for the MMA8652 accelerometer driver.
*
* @author Johann Fischer <j.fischer@phytec.de>
*/
#ifndef MMA8652_H
#define MMA8652_H
#include <stdint.h>
#include <stdbool.h>
#include "periph/i2c.h"
#ifdef __cplusplus
extern "C"
{
#endif
#ifndef MMA8652_I2C_ADDRESS
#define MMA8652_I2C_ADDRESS 0x1D /**< Accelerometer Default Address */
#endif
#define MMA8652_DATARATE_800HZ 0 /**< 800 Hz Ouput Data Rate in WAKE mode */
#define MMA8652_DATARATE_400HZ 1 /**< 400 Hz Ouput Data Rate in WAKE mode */
#define MMA8652_DATARATE_200HZ 2 /**< 200 Hz Ouput Data Rate in WAKE mode */
#define MMA8652_DATARATE_100HZ 3 /**< 100 Hz Ouput Data Rate in WAKE mode */
#define MMA8652_DATARATE_50HZ 4 /**< 50 Hz Ouput Data Rate in WAKE mode */
#define MMA8652_DATARATE_1HZ25 5 /**< 12.5 Hz Ouput Data Rate in WAKE mode */
#define MMA8652_DATARATE_6HZ25 6 /**< 6.25 Hz Ouput Data Rate in WAKE mode */
#define MMA8652_DATARATE_1HZ56 7 /**< 1.56 Hz Ouput Data Rate in WAKE mode */
#define MMA8652_DATARATE_DEFAULT MMA8652_DATARATE_6HZ25 /**< Data Rate for testing */
#define MMA8652_FS_RANGE_2G 0 /**< +/- 2 g Full Scale Range */
#define MMA8652_FS_RANGE_4G 1 /**< +/- 4 g Full Scale Range */
#define MMA8652_FS_RANGE_8G 2 /**< +/- 8 g Full Scale Range */
#define MMA8652_FS_RANGE_DEFAULT MMA8652_FS_RANGE_2G /**< Full-Scale Range for testing */
enum {
MMA8x5x_TYPE_MMA8652 = 0,
MMA8x5x_TYPE_MMA8653,
MMA8x5x_TYPE_MMA8451,
MMA8x5x_TYPE_MMA8452,
MMA8x5x_TYPE_MMA8453,
MMA8x5x_TYPE_MAX,
};
/**
* @brief Device descriptor for MMA8652 accelerometer.
*/
typedef struct {
i2c_t i2c; /**< I2C device, the accelerometer is connected to */
uint8_t addr; /**< the accelerometer's slave address on the I2C bus */
bool initialized; /**< accelerometer status, true if accelerometer is initialized */
int16_t scale; /**< each count corresponds to (1/scale) g */
uint8_t type; /**< mma8x5x type */
} mma8652_t;
/**
* @brief Data structure holding all the information needed for initialization
*/
typedef struct {
i2c_t i2c; /**< I2C bus used */
uint8_t addr; /**< accelerometer's I2C address */
uint8_t rate; /**< accelerometer's sampling rate */
uint8_t scale; /**< accelerometer's scale factor */
uint8_t type; /**< mma8x5x type */
} mma8652_params_t;
/**
* @brief MMA8652 accelerometer test.
* This function looks for Device ID of the MMA8652 accelerometer.
*
* @param[in] dev device descriptor of accelerometer
*
* @return 0 on success
* @return -1 on error
*/
int mma8652_test(mma8652_t *dev);
/**
* @brief Initialize the MMA8652 accelerometer driver.
*
* @param[out] dev device descriptor of accelerometer to initialize
* @param[in] i2c I2C bus the accelerometer is connected to
* @param[in] address accelerometer's I2C slave address
* @param[in] dr output data rate selection in WAKE mode
* @param[in] range full scale range
* @param[in] type mma8x5x type
*
* @return 0 on success
* @return -1 if parameters are wrong
* @return -2 if initialization of I2C bus failed
* @return -3 if accelerometer test failed
* @return -4 if setting to STANDBY mode failed
* @return -5 if accelerometer configuration failed
*/
int mma8652_init(mma8652_t *dev, i2c_t i2c, uint8_t address, uint8_t dr, uint8_t range, uint8_t type);
/**
* @brief Set user offset correction.
* Offset correction registers will be erased after accelerometer reset.
*
* @param[out] dev device descriptor of accelerometer to initialize
* @param[in] x offset correction value for x-axis
* @param[in] y offset correction value for y-axis
* @param[in] z offset correction value for z-axis
*
* @return 0 on success
* @return -1 on error
*/
int mma8652_set_user_offset(mma8652_t *dev, int8_t x, int8_t y, int8_t z);
/**
* @brief Reset the MMA8652 accelerometer. After that accelerometer should be reinitialized.
*
* @param[out] dev device descriptor of accelerometer to reset
*
* @return 0 on success
* @return -1 on error
*/
int mma8652_reset(mma8652_t *dev);
/**
* @brief Set active mode, this enables periodic measurements.
*
* @param[out] dev device descriptor of accelerometer to reset
*
* @return 0 on success
* @return -1 on error
*/
int mma8652_set_active(mma8652_t *dev);
/**
* @brief Set standby mode.
*
* @param[in] dev device descriptor of accelerometer
*
* @return 0 on success
* @return -1 on error
*/
int mma8652_set_standby(mma8652_t *dev);
/**
* @brief Check for new set of measurement data.
*
* @param[in] dev device descriptor of accelerometer
*
* @return >0 if x- ,y- ,z-axis new sample is ready
* @return 0 measurement in progress
* @return -1 on error
*/
int mma8652_is_ready(mma8652_t *dev);
/**
* @brief Read accelerometer's data.
* Acceleration will be calculated as:<br>
* \f$ a = \frac{value \cdot 1000}{1024} \cdot mg \f$ if full scale is set to 2g<br>
* \f$ a = \frac{value \cdot 1000}{512} \cdot mg \f$ if full scale is set to 4g<br>
* \f$ a = \frac{value \cdot 1000}{256} \cdot mg \f$ if full scale is set to 8g<br>
*
* @param[in] dev device descriptor of accelerometer
* @param[out] x x-axis value in mg
* @param[out] y y-axis value in mg
* @param[out] z z-axis value in mg
* @param[out] status accelerometer status register
*
* @return 0 on success
* @return -1 on error
*/
int mma8652_read(mma8652_t *dev, int16_t *x, int16_t *y, int16_t *z, uint8_t *status);
#ifdef __cplusplus
}
#endif
#endif
/** @} */

186
drivers/include/mma8x5x.h Normal file
View File

@ -0,0 +1,186 @@
/*
* Copyright (C) 2014 PHYTEC Messtechnik GmbH
* 2016 Freie Universität Berlin
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @defgroup drivers_mma8x5x MMA8x5x Accelerometer
* @ingroup drivers_sensors
* @brief Driver for the Freescale MMA8x5x 3-Axis accelerometer.
* The driver will initialize the accelerometer for best
* resolution. After the initialization the accelerometer will make
* measurements at periodic times. The measurements period and
* scale range can be determined by accelerometer initialization.
* This driver only implements basic functionality (i.e. no support
* for external interrupt pins).
*
* @{
*
* @file
* @brief Interface definition for the MMA8x5x accelerometer driver.
*
* @author Johann Fischer <j.fischer@phytec.de>
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*/
#ifndef MMA8X5X_H
#define MMA8X5X_H
#include <stdint.h>
#include "periph/i2c.h"
#ifdef __cplusplus
extern "C" {
#endif
#ifndef MMA8X5X_I2C_ADDRESS
#define MMA8X5X_I2C_ADDRESS 0x1D /**< Accelerometer Default Address */
#endif
/**
* @brief Devices supported by this driver
*/
enum {
MMA8X5X_TYPE_MMA8652 = 0x4a, /**< MMA8652 */
MMA8X5X_TYPE_MMA8653 = 0x5a, /**< MMA8653 */
MMA8X5X_TYPE_MMA8451 = 0x1a, /**< MMA8451 */
MMA8X5X_TYPE_MMA8452 = 0x2a, /**< MMA8452 */
MMA8X5X_TYPE_MMA8453 = 0x3a /**< MMA8453 */
};
/**
* @brief Available sampling rates
*/
enum {
MMA8X5X_RATE_800HZ = (0 << 3), /**< 800 Hz Ouput Data Rate in WAKE mode */
MMA8X5X_RATE_400HZ = (1 << 3), /**< 400 Hz Ouput Data Rate in WAKE mode */
MMA8X5X_RATE_200HZ = (2 << 3), /**< 200 Hz Ouput Data Rate in WAKE mode */
MMA8X5X_RATE_100HZ = (3 << 3), /**< 100 Hz Ouput Data Rate in WAKE mode */
MMA8X5X_RATE_50HZ = (4 << 3), /**< 50 Hz Ouput Data Rate in WAKE mode */
MMA8X5X_RATE_1HZ25 = (5 << 3), /**< 12.5 Hz Ouput Data Rate in WAKE mode */
MMA8X5X_RATE_6HZ25 = (6 << 3), /**< 6.25 Hz Ouput Data Rate in WAKE mode */
MMA8X5X_RATE_1HZ56 = (7 << 3) /**< 1.56 Hz Ouput Data Rate in WAKE mode */
};
/**
* @brief Available range options
*/
enum {
MMA8X5X_RANGE_2G = 0, /**< +/- 2 g Full Scale Range */
MMA8X5X_RANGE_4G = 1, /**< +/- 4 g Full Scale Range */
MMA8X5X_RANGE_8G = 2 /**< +/- 8 g Full Scale Range */
};
/**
* @brief Named return values
*/
enum {
MMA8X5X_OK = 0, /**< everything was fine */
MMA8X5X_DATA_READY = 1, /**< new data ready to be read */
MMA8X5X_NOI2C = -1, /**< I2C communication failed */
MMA8X5X_NODEV = -2, /**< no MMA8X5X device found on the bus */
MMA8X5X_NODATA = -3 /**< no data available */
};
/**
* @brief Configuration parameters
*/
typedef struct {
i2c_t i2c; /**< I2C bus the device is connected to */
uint8_t addr; /**< I2C bus address of the device */
uint8_t type; /**< device type */
uint8_t rate; /**< sampling rate to use */
uint8_t range; /**< scale range to use */
uint8_t offset[3]; /**< data offset in X, Y, and Z direction */
} mma8x5x_params_t;
/**
* @brief Device descriptor for MMA8x5x accelerometers
*/
typedef struct {
mma8x5x_params_t params; /**< device configuration parameters */
} mma8x5x_t;
/**
* @brief Data type for the result data
*/
typedef struct {
int16_t x; /**< acceleration in X direction */
int16_t y; /**< acceleration in Y direction */
int16_t z; /**< acceleration in Z direction */
} mma8x5x_data_t;
/**
* @brief Initialize the MMA8x5x accelerometer driver.
*
* @param[out] dev device descriptor of accelerometer to initialize
* @param[in] params configuration parameters
*
* @return MMA8X5X_OK on success
* @return MMA8X5X_NOI2C if initialization of I2C bus failed
* @return MMA8X5X_NODEV if accelerometer test failed
*/
int mma8x5x_init(mma8x5x_t *dev, const mma8x5x_params_t *params);
/**
* @brief Set user offset correction
*
* Offset correction registers will be erased after accelerometer reset.
*
* @param[out] dev device descriptor of accelerometer to initialize
* @param[in] x offset correction value for x-axis
* @param[in] y offset correction value for y-axis
* @param[in] z offset correction value for z-axis
*/
void mma8x5x_set_user_offset(mma8x5x_t *dev, int8_t x, int8_t y, int8_t z);
/**
* @brief Set active mode, this enables periodic measurements
*
* @param[out] dev device descriptor of accelerometer to reset
*/
void mma8x5x_set_active(mma8x5x_t *dev);
/**
* @brief Set standby mode.
*
* @param[in] dev device descriptor of accelerometer
*/
void mma8x5x_set_standby(mma8x5x_t *dev);
/**
* @brief Check for new set of measurement data
*
* @param[in] dev device descriptor of accelerometer
*
* @return MMA8X5X_DATA_READY if new sample is ready
* @return MMA8X5X_NODATA if nothing is available
*/
int mma8x5x_is_ready(mma8x5x_t *dev);
/**
* @brief Read accelerometer's data
*
* Acceleration will be calculated as:<br>
* \f$ a = \frac{value \cdot 1000}{1024} \cdot mg \f$ if full scale is set
* to 2g<br>
* \f$ a = \frac{value \cdot 1000}{512} \cdot mg \f$ if full scale is set to
* 4g<br>
* \f$ a = \frac{value \cdot 1000}{256} \cdot mg \f$ if full scale is set to
* 8g<br>
*
* @param[in] dev device descriptor of accelerometer
* @param[out] data the current acceleration data [in mg]
*/
void mma8x5x_read(mma8x5x_t *dev, mma8x5x_data_t *data);
#ifdef __cplusplus
}
#endif
#endif /* MMA8X5X_H */
/** @} */

View File

@ -1,265 +0,0 @@
/*
* Copyright (C) 2014 PHYTEC Messtechnik GmbH
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*
*/
/**
* @ingroup drivers_mma8652
* @{
*
* @file
* @brief Register definition for the MMA8652 accelerometer driver.
*
* @author Johann Fischer <j.fischer@phytec.de>
*
*/
#ifndef MMA8652_REG_H
#define MMA8652_REG_H
#ifdef __cplusplus
extern "C"
{
#endif
#include "mma8652.h"
#define MMA8652_STATUS 0x00 /**< Data or FIFO Status */
#define MMA8652_OUT_X_MSB 0x01 /**< [7:0] are 8 MSBs of X data */
#define MMA8652_OUT_X_LSB 0x02 /**< [7:4] are 4 LSBs of X data */
#define MMA8652_OUT_Y_MSB 0x03 /**< [7:0] are 8 MSBs of Y data */
#define MMA8652_OUT_Y_LSB 0x04 /**< [7:4] are 4 LSBs of Y data */
#define MMA8652_OUT_Z_MSB 0x05 /**< [7:0] are 8 MSBs of Z data */
#define MMA8652_OUT_Z_LSB 0x06 /**< [7:4] are 8 LSBs of Z data */
#define MMA8652_F_SETUP 0x09 /**< FIFO setup */
#define MMA8652_TRIG_CFG 0x0A /**< Map of FIFO data capture events */
#define MMA8652_SYSMOD 0x0B /**< Current System mode */
#define MMA8652_INT_SOURCE 0x0C /**< Interrupt status */
#define MMA8652_WHO_AM_I 0x0D /**< Device ID */
#define MMA8652_XYZ_DATA_CFG 0x0E /**< Dynamic Range Settings */
#define MMA8652_HP_FILTER_CUTOFF 0x0F /**< High-Pass Filter Selection */
#define MMA8652_PL_STATUS 0x10 /**< Landscape/Portrait orientation status */
#define MMA8652_PL_CFG 0x11 /**< Landscape/Portrait configuration */
#define MMA8652_PL_COUNT 0x12 /**< Landscape/Portrait debounce counter */
#define MMA8652_PL_BF_ZCOMP 0x13 /**< Back/Front, Z-Lock Trip threshold */
#define MMA8652_P_L_THS_REG 0x14 /**< Portrait/Landscape Threshold and Hysteresis */
#define MMA8652_FF_MT_CFG 0x15 /**< Freefall/Motion functional block configuration */
#define MMA8652_FF_MT_SRC 0x16 /**< Freefall/Motion event source register */
#define MMA8652_FF_MT_THS 0x17 /**< Freefall/Motion threshold register */
#define MMA8652_FF_MT_COUNT 0x18 /**< Freefall/Motion debounce counter */
#define MMA8652_TRANSIENT_CFG 0x1D /**< Transient functional block configuration */
#define MMA8652_TRANSIENT_SRC 0x1E /**< Transient event status register */
#define MMA8652_TRANSIENT_THS 0x1F /**< Transient event threshold */
#define MMA8652_TRANSIENT_COUNT 0x20 /**< Transient debounce counter */
#define MMA8652_PULSE_CFG 0x21 /**< Pulse enable configuration */
#define MMA8652_PULSE_SRC 0x22 /**< Pulse detection source */
#define MMA8652_PULSE_THSX 0x23 /**< X pulse threshold */
#define MMA8652_PULSE_THSY 0x24 /**< Y pulse threshold */
#define MMA8652_PULSE_THSZ 0x25 /**< Z pulse threshold */
#define MMA8652_PULSE_TMLT 0x26 /**< Time limit for pulse */
#define MMA8652_PULSE_LTCY 0x27 /**< Latency time for 2nd pulse */
#define MMA8652_PULSE_WIND 0x28 /**< Window time for 2nd pulse */
#define MMA8652_ASLP_COUNT 0x29 /**< Counter setting for Auto-SLEEP */
#define MMA8652_CTRL_REG1 0x2A /**< Data rates and modes setting */
#define MMA8652_CTRL_REG2 0x2B /**< Sleep Enable, OS modes, RST, ST */
#define MMA8652_CTRL_REG3 0x2C /**< Wake from Sleep, IPOL, PP_OD */
#define MMA8652_CTRL_REG4 0x2D /**< Interrupt enable register */
#define MMA8652_CTRL_REG5 0x2E /**< Interrupt pin (INT1/INT2) map */
#define MMA8652_OFF_X 0x2F /**< X-axis offset adjust */
#define MMA8652_OFF_Y 0x30 /**< Y-axis offset adjust */
#define MMA8652_OFF_Z 0x31 /**< Z-axis offset adjust */
#define MMA8652_STATUS_XDR (1 << 0)
#define MMA8652_STATUS_YDR (1 << 1)
#define MMA8652_STATUS_ZDR (1 << 2)
#define MMA8652_STATUS_ZYXDR (1 << 3)
#define MMA8652_STATUS_XOW (1 << 4)
#define MMA8652_STATUS_YOW (1 << 5)
#define MMA8652_STATUS_ZOW (1 << 6)
#define MMA8652_STATUS_ZYXOW (1 << 7)
#define MMA8652_F_STATUS_F_CNT_MASK 0x3F
#define MMA8652_F_STATUS_F_WMRK_FLAG (1 << 6)
#define MMA8652_F_STATUS_F_OVF (1 << 7)
#define MMA8652_F_SETUP_MODE_MASK 0xC0
#define MMA8652_F_SETUP_MODE_DISABLED 0
#define MMA8652_F_SETUP_MODE_CIRCULAR 1
#define MMA8652_F_SETUP_MODE_STOP 2
#define MMA8652_F_SETUP_MODE_TRIGGER 3
#define MMA8652_F_SETUP_F_WMRK_MASK 0x3F
#define MMA8652_TRIG_CFG_FF_MT (1 << 2)
#define MMA8652_TRIG_CFG_PULSE (1 << 3)
#define MMA8652_TRIG_CFG_LNDPRT (1 << 4)
#define MMA8652_TRIG_CFG_TRANS (1 << 5)
#define MMA8652_SYSMOD_MASK 0x3
#define MMA8652_SYSMOD_STANDBY 0
#define MMA8652_SYSMOD_WAKE 1
#define MMA8652_SYSMOD_SLEEP 2
#define MMA8652_SYSMOD_FGT_MASK 0x7C
#define MMA8652_SYSMOD_FGERR (1 << 7)
#define MMA8652_INT_SOURCE_DRDY (1 << 0)
#define MMA8652_INT_SOURCE_FF_MT (1 << 2)
#define MMA8652_INT_SOURCE_PULSE (1 << 3)
#define MMA8652_INT_SOURCE_LNDPRT (1 << 4)
#define MMA8652_INT_SOURCE_TRANS (1 << 5)
#define MMA8652_INT_SOURCE_FIFO (1 << 6)
#define MMA8652_INT_SOURCE_ASLP (1 << 7)
#define MMA8652_XYZ_DATA_CFG_FS_MASK 0x3
#define MMA8652_XYZ_DATA_CFG_FS(x) ((uint8_t)(x)&MMA8652_XYZ_DATA_CFG_FS_MASK)
#define MMA8652_XYZ_DATA_CFG_HPF_OUT (1 << 4)
#define MMA8652_HP_FILTER_SEL_MASK 0x03
#define MMA8652_HP_FILTER_LPF_EN (1 << 4)
#define MMA8652_HP_FILTER_HPF_BYP (1 << 5)
#define MMA8652_PL_STATUS_BAFRO (1 << 0)
#define MMA8652_PL_STATUS_LAPO_MASK 0x6
#define MMA8652_PL_STATUS_LAPO_P_UP 0
#define MMA8652_PL_STATUS_LAPO_P_DOWN 1
#define MMA8652_PL_STATUS_LAPO_L_RIGHT 2
#define MMA8652_PL_STATUS_LAPO_L_LEFT 3
#define MMA8652_PL_STATUS_LO (1 << 6)
#define MMA8652_PL_STATUS_NEWLP (1 << 7)
#define MMA8652_PL_CFG_PL_EN (1 << 6)
#define MMA8652_PL_CFG_DBCNTM (1 << 7)
#define MMA8652_PL_BF_ZCOMP_ZLOCK_MASK 0x07
#define MMA8652_PL_BF_ZCOMP_BKFR_MASK 0xC0
#define MMA8652_P_L_HYS_MASK 0x07
#define MMA8652_P_L_THS_MASK 0xF8
#define MMA8652_FF_MT_CFG_XEFE (1 << 3)
#define MMA8652_FF_MT_CFG_YEFE (1 << 4)
#define MMA8652_FF_MT_CFG_ZEFE (1 << 5)
#define MMA8652_FF_MT_CFG_OAE (1 << 6)
#define MMA8652_FF_MT_CFG_ELE (1 << 7)
#define MMA8652_FF_MT_SRC_XHP (1 << 0)
#define MMA8652_FF_MT_SRC_XHE (1 << 1)
#define MMA8652_FF_MT_SRC_YHP (1 << 2)
#define MMA8652_FF_MT_SRC_YHE (1 << 3)
#define MMA8652_FF_MT_SRC_ZHP (1 << 4)
#define MMA8652_FF_MT_SRC_ZHE (1 << 5)
#define MMA8652_FF_MT_SRC_EA (1 << 7)
#define MMA8652_FF_MT_THS_MASK 0x7F
#define MMA8652_FF_MT_THS_DBCNTM (1 << 7)
#define MMA8652_TRANSIENT_CFG_HPF_BYP (1 << 0)
#define MMA8652_TRANSIENT_CFG_XTEFE (1 << 1)
#define MMA8652_TRANSIENT_CFG_YTEFE (1 << 2)
#define MMA8652_TRANSIENT_CFG_ZTEFE (1 << 3)
#define MMA8652_TRANSIENT_CFG_ELE (1 << 4)
#define MMA8652_TRANSIENT_SRC_XTPOL (1 << 0)
#define MMA8652_TRANSIENT_SRC_XTEVENT (1 << 1)
#define MMA8652_TRANSIENT_SRC_YTPOL (1 << 2)
#define MMA8652_TRANSIENT_SRC_YTEVENT (1 << 3)
#define MMA8652_TRANSIENT_SRC_ZTPOL (1 << 4)
#define MMA8652_TRANSIENT_SRC_ZTEVENT (1 << 5)
#define MMA8652_TRANSIENT_SRC_EA (1 << 6)
#define MMA8652_TRANSIENT_THS_MASK 0x7F
#define MMA8652_TRANSIENT_THS_DBCNTM (1<< 7)
#define MMA8652_PULSE_CFG_XSPEFE (1 << 0)
#define MMA8652_PULSE_CFG_XDPEFE (1 << 1)
#define MMA8652_PULSE_CFG_YSPEFE (1 << 2)
#define MMA8652_PULSE_CFG_YDPEFE (1 << 3)
#define MMA8652_PULSE_CFG_ZSPEFE (1 << 4)
#define MMA8652_PULSE_CFG_ZDPEFE (1 << 5)
#define MMA8652_PULSE_CFG_ELE (1 << 6)
#define MMA8652_PULSE_CFG_DPA (1 << 7)
#define MMA8652_PULSE_SRC_POLX (1 << 0)
#define MMA8652_PULSE_SRC_POLY (1 << 1)
#define MMA8652_PULSE_SRC_POLZ (1 << 2)
#define MMA8652_PULSE_SRC_DPE (1 << 3)
#define MMA8652_PULSE_SRC_AXX (1 << 4)
#define MMA8652_PULSE_SRC_AXY (1 << 5)
#define MMA8652_PULSE_SRC_AXZ (1 << 6)
#define MMA8652_PULSE_SRC_EA (1 << 7)
#define MMA8652_PULSE_THSX_MASK 0x7F
#define MMA8652_PULSE_THSY_MASK 0x7F
#define MMA8652_PULSE_THSZ_MASK 0x7F
#define MMA8652_CTRL_REG1_ACTIVE (1 << 0)
#define MMA8652_CTRL_REG1_F_READ (1 << 1)
#define MMA8652_CTRL_REG1_DR_MASK 0x38
#define MMA8652_CTRL_REG1_DR_SHIFT 3
#define MMA8652_CTRL_REG1_DR(x) (((uint8_t)(((uint8_t)(x))<<MMA8652_CTRL_REG1_DR_SHIFT))\
&MMA8652_CTRL_REG1_DR_MASK)
#define MMA8652_CTRL_REG1_ASR_MASK 0xC0
#define MMA8652_CTRL_REG1_ASR_50HZ 0
#define MMA8652_CTRL_REG1_ASR_12HZ5 1
#define MMA8652_CTRL_REG1_ASR_6HZ25 2
#define MMA8652_CTRL_REG1_ASR_1HZ56 3
#define MMA8652_CTRL_REG2_MODS_MASK 0x3
#define MMA8652_CTRL_REG2_MODS_NORMAL 0
#define MMA8652_CTRL_REG2_MODS_LNLP 1
#define MMA8652_CTRL_REG2_MODS_HR 2
#define MMA8652_CTRL_REG2_MODS_LP 3
#define MMA8652_CTRL_REG2_SLPE (1 << 2)
#define MMA8652_CTRL_REG2_SMODS_MASK 0x18
#define MMA8652_CTRL_REG2_SMODS_NORMAL 0
#define MMA8652_CTRL_REG2_SMODS_LNLP 1
#define MMA8652_CTRL_REG2_SMODS_HR 2
#define MMA8652_CTRL_REG2_SMODS_LP 3
#define MMA8652_CTRL_REG2_RST (1 << 6)
#define MMA8652_CTRL_REG2_ST (1 << 7)
#define MMA8652_CTRL_REG3_PP_OD (1 << 0)
#define MMA8652_CTRL_REG3_IPOL (1 << 1)
#define MMA8652_CTRL_REG3_WAKE_FF_MT (1 << 3)
#define MMA8652_CTRL_REG3_WAKE_PULSE (1 << 4)
#define MMA8652_CTRL_REG3_WAKE_LNDPRT (1 << 5)
#define MMA8652_CTRL_REG3_WAKE_TRANS (1 << 6)
#define MMA8652_CTRL_REG3_FIFO_GATE (1 << 7)
#define MMA8652_CTRL_REG4_INT_EN_DRDY (1 << 0)
#define MMA8652_CTRL_REG4_INT_EN_FF_MT (1 << 2)
#define MMA8652_CTRL_REG4_INT_EN_PULSE (1 << 3)
#define MMA8652_CTRL_REG4_INT_EN_LNDPRT (1 << 4)
#define MMA8652_CTRL_REG4_INT_EN_TRANS (1 << 5)
#define MMA8652_CTRL_REG4_INT_EN_FIFO (1 << 6)
#define MMA8652_CTRL_REG4_INT_EN_ASLP (1 << 7)
#define MMA8652_CTRL_REG5_INT_CFG_DRDY (1 << 0)
#define MMA8652_CTRL_REG5_INT_CFG_FF_MT (1 << 2)
#define MMA8652_CTRL_REG5_INT_CFG_PULSE (1 << 3)
#define MMA8652_CTRL_REG5_INT_CFG_LNDPRT (1 << 4)
#define MMA8652_CTRL_REG5_INT_CFG_TRANS (1 << 5)
#define MMA8652_CTRL_REG5_INT_CFG_FIFO (1 << 6)
#define MMA8652_CTRL_REG5_INT_CFG_ASLP (1 << 7)
/**
* @brief Device ID
*/
static const uint8_t mma8x5x_device_id[MMA8x5x_TYPE_MAX] =
{
0x4A, /* MMA8652_ID */
0x5A, /* MMA8653_ID */
0x1A, /* MMA8451_ID */
0x2A, /* MMA8452_ID */
0x3A, /* MMA8453_ID */
};
#ifdef __cplusplus
}
#endif
#endif
/** @} */

View File

@ -1,227 +0,0 @@
/*
* Copyright (C) 2014 PHYTEC Messtechnik GmbH
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*
*/
/**
* @ingroup drivers_mma8652
* @{
*
* @file
* @brief Driver for the Freescale MMA8652 accelerometer.
*
* @author Johann Fischer <j.fischer@phytec.de>
* @author Peter Kietzmann <peter.kietzmann@haw-hamburg.de>
*
* @}
*/
#include <stdint.h>
#include <stdbool.h>
#include "periph/i2c.h"
#include "mma8652.h"
#include "mma8652_reg.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
#define I2C_SPEED I2C_SPEED_FAST
int mma8652_test(mma8652_t *dev)
{
uint8_t reg;
/* Acquire exclusive access to the bus. */
i2c_acquire(dev->i2c);
if (i2c_read_regs(dev->i2c, dev->addr, MMA8652_WHO_AM_I, &reg, 1) != 1) {
/* Release the bus for other threads. */
i2c_release(dev->i2c);
return -1;
}
i2c_release(dev->i2c);
if (reg != mma8x5x_device_id[dev->type]) {
return -1;
}
return 0;
}
int mma8652_init(mma8652_t *dev, i2c_t i2c, uint8_t address, uint8_t dr, uint8_t range, uint8_t type)
{
uint8_t reg;
/* write device descriptor */
dev->i2c = i2c;
dev->addr = address;
dev->initialized = false;
if (dr > MMA8652_DATARATE_1HZ56 || range > MMA8652_FS_RANGE_8G || type >= MMA8x5x_TYPE_MAX) {
return -1;
}
dev->type = type;
i2c_acquire(dev->i2c);
/* initialize the I2C bus */
if (i2c_init_master(i2c, I2C_SPEED) < 0) {
i2c_release(dev->i2c);
return -2;
}
i2c_release(dev->i2c);
if (mma8652_test(dev)) {
return -3;
}
if (mma8652_set_standby(dev) < 0) {
return -4;
}
reg = MMA8652_XYZ_DATA_CFG_FS(range);
i2c_acquire(dev->i2c);
if (i2c_write_regs(dev->i2c, dev->addr, MMA8652_XYZ_DATA_CFG, &reg, 1) != 1) {
i2c_release(dev->i2c);
return -5;
}
reg = MMA8652_CTRL_REG1_DR(dr);
if (i2c_write_regs(dev->i2c, dev->addr, MMA8652_CTRL_REG1, &reg, 1) != 1) {
i2c_release(dev->i2c);
return -5;
}
i2c_release(dev->i2c);
dev->initialized = true;
dev->scale = 1024 >> range;
return 0;
}
int mma8652_set_user_offset(mma8652_t *dev, int8_t x, int8_t y, int8_t z)
{
uint8_t buf[3];
buf[0] = (uint8_t)x;
buf[1] = (uint8_t)y;
buf[2] = (uint8_t)z;
i2c_acquire(dev->i2c);
if (i2c_write_regs(dev->i2c, dev->addr, MMA8652_OFF_X, buf, 3) != 3) {
i2c_release(dev->i2c);
return -1;
}
i2c_release(dev->i2c);
return 0;
}
int mma8652_reset(mma8652_t *dev)
{
uint8_t reg;
dev->initialized = false;
reg = MMA8652_CTRL_REG2_RST;
i2c_acquire(dev->i2c);
if (i2c_write_regs(dev->i2c, dev->addr, MMA8652_CTRL_REG2, &reg, 1) != 1) {
i2c_release(dev->i2c);
return -1;
}
i2c_release(dev->i2c);
return 0;
}
int mma8652_set_active(mma8652_t *dev)
{
uint8_t reg;
if (dev->initialized == false) {
return -1;
}
i2c_acquire(dev->i2c);
if (i2c_read_regs(dev->i2c, dev->addr, MMA8652_CTRL_REG1, &reg, 1) != 1) {
i2c_release(dev->i2c);
return -1;
}
reg |= MMA8652_CTRL_REG1_ACTIVE;
if (i2c_write_regs(dev->i2c, dev->addr, MMA8652_CTRL_REG1, &reg, 1) != 1) {
i2c_release(dev->i2c);
return -1;
}
i2c_release(dev->i2c);
return 0;
}
int mma8652_set_standby(mma8652_t *dev)
{
uint8_t reg;
i2c_acquire(dev->i2c);
if (i2c_read_regs(dev->i2c, dev->addr, MMA8652_CTRL_REG1, &reg, 1) != 1) {
i2c_release(dev->i2c);
return -1;
}
reg &= ~MMA8652_CTRL_REG1_ACTIVE;
if (i2c_write_regs(dev->i2c, dev->addr, MMA8652_CTRL_REG1, &reg, 1) != 1) {
i2c_release(dev->i2c);
return -1;
}
i2c_release(dev->i2c);
return 0;
}
int mma8652_is_ready(mma8652_t *dev)
{
uint8_t reg;
if (dev->initialized == false) {
return -1;
}
i2c_acquire(dev->i2c);
if (i2c_read_regs(dev->i2c, dev->addr, MMA8652_STATUS, &reg, 1) != 1) {
i2c_release(dev->i2c);
return -1;
}
i2c_release(dev->i2c);
return reg & MMA8652_STATUS_ZYXDR;
}
int mma8652_read(mma8652_t *dev, int16_t *x, int16_t *y, int16_t *z, uint8_t *status)
{
uint8_t buf[7];
if (dev->initialized == false) {
return -1;
}
i2c_acquire(dev->i2c);
if (i2c_read_regs(dev->i2c, dev->addr, MMA8652_STATUS, buf, 7) != 7) {
i2c_release(dev->i2c);
return -1;
}
i2c_release(dev->i2c);
*status = buf[0];
*x = (int32_t)((int16_t)(((int16_t)buf[1] << 8) | buf[2]) >> 4) * 1000 / dev->scale;
*y = (int32_t)((int16_t)(((int16_t)buf[3] << 8) | buf[4]) >> 4) * 1000 / dev->scale;
*z = (int32_t)((int16_t)(((int16_t)buf[5] << 8) | buf[6]) >> 4) * 1000 / dev->scale;
return 0;
}

View File

@ -1,3 +1 @@
MODULE = mma8652
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1,86 @@
/*
* Copyright (C) 2015 Freie Universität Berlin
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup drivers_mma8x5x
* @{
*
* @file
* @brief Default configuration for MMA8x5x devices
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*/
#ifndef MMA8X5X_PARAMS_H
#define MMA8X5X_PARAMS_H
#include "board.h"
#include "saul_reg.h"
#include "mma8x5x.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Set default configuration parameters for the MMA8x5x driver
* @{
*/
#ifndef MMA8X5X_PARAM_I2C
#define MMA8X5X_PARAM_I2C (I2C_DEV(0))
#endif
#ifndef MMA8X5X_PARAM_ADDR
#define MMA8X5X_PARAM_ADDR (MMA8X5X_I2C_ADDRESS)
#endif
#ifndef MMA8X5X_PARAM_TYPE
#define MMA8X5X_PARAM_TYPE (MMA8X5X_TYPE_MMA8652)
#endif
#ifndef MMA8X5X_PARAM_RATE
#define MMA8X5X_PARAM_RATE (MMA8X5X_RATE_200HZ)
#endif
#ifndef MMA8X5X_PARAM_RANGE
#define MMA8X5X_PARAM_RANGE (MMA8X5X_RANGE_2G)
#endif
#ifndef MMA8X5X_PARAM_OFFSET
#define MMA8X5X_PARAM_OFFSET { 0, 0, 0 }
#endif
#ifndef MMA8X5X_PARAMS
#define MMA8X5X_PARAMS { .i2c = MMA8X5X_PARAM_I2C, \
.addr = MMA8X5X_PARAM_ADDR, \
.type = MMA8X5X_PARAM_TYPE, \
.rate = MMA8X5X_PARAM_RATE, \
.range = MMA8X5X_PARAM_RANGE, \
.offset = MMA8X5X_PARAM_OFFSET }
#endif
/**@}*/
/**
* @brief MMA8x5x configuration
*/
static const mma8x5x_params_t mma8x5x_params[] =
{
MMA8X5X_PARAMS
};
/**
* @brief Additional meta information to keep in the SAUL registry
*/
static const saul_reg_info_t mma8x5x_saul_info[] =
{
{
.name = "mma8652"
}
};
#ifdef __cplusplus
}
#endif
#endif /* MMA8X5X_PARAMS_H */
/** @} */

View File

@ -0,0 +1,262 @@
/*
* Copyright (C) 2014 PHYTEC Messtechnik GmbH
* 2016 Freie Universität Berlin
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*
*/
/**
* @ingroup drivers_mma8652
* @{
*
* @file
* @brief Register definition for the MMA8x5x accelerometer driver
*
* @author Johann Fischer <j.fischer@phytec.de>
* @author Hauke Petersen
*
*/
#ifndef MMA8X5X_REG_H
#define MMA8X5X_REG_H
#ifdef __cplusplus
extern "C"
{
#endif
/**
* @brief Register addresses
* @{
*/
#define MMA8X5X_STATUS 0x00 /**< Data or FIFO Status */
#define MMA8X5X_OUT_X_MSB 0x01 /**< [7:0] are 8 MSBs of X data */
#define MMA8X5X_OUT_X_LSB 0x02 /**< [7:4] are 4 LSBs of X data */
#define MMA8X5X_OUT_Y_MSB 0x03 /**< [7:0] are 8 MSBs of Y data */
#define MMA8X5X_OUT_Y_LSB 0x04 /**< [7:4] are 4 LSBs of Y data */
#define MMA8X5X_OUT_Z_MSB 0x05 /**< [7:0] are 8 MSBs of Z data */
#define MMA8X5X_OUT_Z_LSB 0x06 /**< [7:4] are 8 LSBs of Z data */
#define MMA8X5X_F_SETUP 0x09 /**< FIFO setup */
#define MMA8X5X_TRIG_CFG 0x0A /**< Map of FIFO data capture events */
#define MMA8X5X_SYSMOD 0x0B /**< Current System mode */
#define MMA8X5X_INT_SOURCE 0x0C /**< Interrupt status */
#define MMA8X5X_WHO_AM_I 0x0D /**< Device ID */
#define MMA8X5X_XYZ_DATA_CFG 0x0E /**< Dynamic Range Settings */
#define MMA8X5X_HP_FILTER_CUTOFF 0x0F /**< High-Pass Filter Selection */
#define MMA8X5X_PL_STATUS 0x10 /**< Landscape/Portrait orientation status */
#define MMA8X5X_PL_CFG 0x11 /**< Landscape/Portrait configuration */
#define MMA8X5X_PL_COUNT 0x12 /**< Landscape/Portrait debounce counter */
#define MMA8X5X_PL_BF_ZCOMP 0x13 /**< Back/Front, Z-Lock Trip threshold */
#define MMA8X5X_P_L_THS_REG 0x14 /**< Portrait/Landscape Threshold and Hysteresis */
#define MMA8X5X_FF_MT_CFG 0x15 /**< Freefall/Motion functional block configuration */
#define MMA8X5X_FF_MT_SRC 0x16 /**< Freefall/Motion event source register */
#define MMA8X5X_FF_MT_THS 0x17 /**< Freefall/Motion threshold register */
#define MMA8X5X_FF_MT_COUNT 0x18 /**< Freefall/Motion debounce counter */
#define MMA8X5X_TRANSIENT_CFG 0x1D /**< Transient functional block configuration */
#define MMA8X5X_TRANSIENT_SRC 0x1E /**< Transient event status register */
#define MMA8X5X_TRANSIENT_THS 0x1F /**< Transient event threshold */
#define MMA8X5X_TRANSIENT_COUNT 0x20 /**< Transient debounce counter */
#define MMA8X5X_PULSE_CFG 0x21 /**< Pulse enable configuration */
#define MMA8X5X_PULSE_SRC 0x22 /**< Pulse detection source */
#define MMA8X5X_PULSE_THSX 0x23 /**< X pulse threshold */
#define MMA8X5X_PULSE_THSY 0x24 /**< Y pulse threshold */
#define MMA8X5X_PULSE_THSZ 0x25 /**< Z pulse threshold */
#define MMA8X5X_PULSE_TMLT 0x26 /**< Time limit for pulse */
#define MMA8X5X_PULSE_LTCY 0x27 /**< Latency time for 2nd pulse */
#define MMA8X5X_PULSE_WIND 0x28 /**< Window time for 2nd pulse */
#define MMA8X5X_ASLP_COUNT 0x29 /**< Counter setting for Auto-SLEEP */
#define MMA8X5X_CTRL_REG1 0x2A /**< Data rates and modes setting */
#define MMA8X5X_CTRL_REG2 0x2B /**< Sleep Enable, OS modes, RST, ST */
#define MMA8X5X_CTRL_REG3 0x2C /**< Wake from Sleep, IPOL, PP_OD */
#define MMA8X5X_CTRL_REG4 0x2D /**< Interrupt enable register */
#define MMA8X5X_CTRL_REG5 0x2E /**< Interrupt pin (INT1/INT2) map */
#define MMA8X5X_OFF_X 0x2F /**< X-axis offset adjust */
#define MMA8X5X_OFF_Y 0x30 /**< Y-axis offset adjust */
#define MMA8X5X_OFF_Z 0x31 /**< Z-axis offset adjust */
/** @} */
/**
* @brief MMA8x5x register bitfields
* @{
*/
#define MMA8X5X_STATUS_XDR (1 << 0)
#define MMA8X5X_STATUS_YDR (1 << 1)
#define MMA8X5X_STATUS_ZDR (1 << 2)
#define MMA8X5X_STATUS_ZYXDR (1 << 3)
#define MMA8X5X_STATUS_XOW (1 << 4)
#define MMA8X5X_STATUS_YOW (1 << 5)
#define MMA8X5X_STATUS_ZOW (1 << 6)
#define MMA8X5X_STATUS_ZYXOW (1 << 7)
#define MMA8X5X_F_STATUS_F_CNT_MASK 0x3F
#define MMA8X5X_F_STATUS_F_WMRK_FLAG (1 << 6)
#define MMA8X5X_F_STATUS_F_OVF (1 << 7)
#define MMA8X5X_F_SETUP_MODE_MASK 0xC0
#define MMA8X5X_F_SETUP_MODE_DISABLED 0
#define MMA8X5X_F_SETUP_MODE_CIRCULAR 1
#define MMA8X5X_F_SETUP_MODE_STOP 2
#define MMA8X5X_F_SETUP_MODE_TRIGGER 3
#define MMA8X5X_F_SETUP_F_WMRK_MASK 0x3F
#define MMA8X5X_TRIG_CFG_FF_MT (1 << 2)
#define MMA8X5X_TRIG_CFG_PULSE (1 << 3)
#define MMA8X5X_TRIG_CFG_LNDPRT (1 << 4)
#define MMA8X5X_TRIG_CFG_TRANS (1 << 5)
#define MMA8X5X_SYSMOD_MASK 0x3
#define MMA8X5X_SYSMOD_STANDBY 0
#define MMA8X5X_SYSMOD_WAKE 1
#define MMA8X5X_SYSMOD_SLEEP 2
#define MMA8X5X_SYSMOD_FGT_MASK 0x7C
#define MMA8X5X_SYSMOD_FGERR (1 << 7)
#define MMA8X5X_INT_SOURCE_DRDY (1 << 0)
#define MMA8X5X_INT_SOURCE_FF_MT (1 << 2)
#define MMA8X5X_INT_SOURCE_PULSE (1 << 3)
#define MMA8X5X_INT_SOURCE_LNDPRT (1 << 4)
#define MMA8X5X_INT_SOURCE_TRANS (1 << 5)
#define MMA8X5X_INT_SOURCE_FIFO (1 << 6)
#define MMA8X5X_INT_SOURCE_ASLP (1 << 7)
#define MMA8X5X_XYZ_DATA_CFG_FS_MASK 0x3
#define MMA8X5X_XYZ_DATA_CFG_HPF_OUT (1 << 4)
#define MMA8X5X_HP_FILTER_SEL_MASK 0x03
#define MMA8X5X_HP_FILTER_LPF_EN (1 << 4)
#define MMA8X5X_HP_FILTER_HPF_BYP (1 << 5)
#define MMA8X5X_PL_STATUS_BAFRO (1 << 0)
#define MMA8X5X_PL_STATUS_LAPO_MASK 0x6
#define MMA8X5X_PL_STATUS_LAPO_P_UP 0
#define MMA8X5X_PL_STATUS_LAPO_P_DOWN 1
#define MMA8X5X_PL_STATUS_LAPO_L_RIGHT 2
#define MMA8X5X_PL_STATUS_LAPO_L_LEFT 3
#define MMA8X5X_PL_STATUS_LO (1 << 6)
#define MMA8X5X_PL_STATUS_NEWLP (1 << 7)
#define MMA8X5X_PL_CFG_PL_EN (1 << 6)
#define MMA8X5X_PL_CFG_DBCNTM (1 << 7)
#define MMA8X5X_PL_BF_ZCOMP_ZLOCK_MASK 0x07
#define MMA8X5X_PL_BF_ZCOMP_BKFR_MASK 0xC0
#define MMA8X5X_P_L_HYS_MASK 0x07
#define MMA8X5X_P_L_THS_MASK 0xF8
#define MMA8X5X_FF_MT_CFG_XEFE (1 << 3)
#define MMA8X5X_FF_MT_CFG_YEFE (1 << 4)
#define MMA8X5X_FF_MT_CFG_ZEFE (1 << 5)
#define MMA8X5X_FF_MT_CFG_OAE (1 << 6)
#define MMA8X5X_FF_MT_CFG_ELE (1 << 7)
#define MMA8X5X_FF_MT_SRC_XHP (1 << 0)
#define MMA8X5X_FF_MT_SRC_XHE (1 << 1)
#define MMA8X5X_FF_MT_SRC_YHP (1 << 2)
#define MMA8X5X_FF_MT_SRC_YHE (1 << 3)
#define MMA8X5X_FF_MT_SRC_ZHP (1 << 4)
#define MMA8X5X_FF_MT_SRC_ZHE (1 << 5)
#define MMA8X5X_FF_MT_SRC_EA (1 << 7)
#define MMA8X5X_FF_MT_THS_MASK 0x7F
#define MMA8X5X_FF_MT_THS_DBCNTM (1 << 7)
#define MMA8X5X_TRANSIENT_CFG_HPF_BYP (1 << 0)
#define MMA8X5X_TRANSIENT_CFG_XTEFE (1 << 1)
#define MMA8X5X_TRANSIENT_CFG_YTEFE (1 << 2)
#define MMA8X5X_TRANSIENT_CFG_ZTEFE (1 << 3)
#define MMA8X5X_TRANSIENT_CFG_ELE (1 << 4)
#define MMA8X5X_TRANSIENT_SRC_XTPOL (1 << 0)
#define MMA8X5X_TRANSIENT_SRC_XTEVENT (1 << 1)
#define MMA8X5X_TRANSIENT_SRC_YTPOL (1 << 2)
#define MMA8X5X_TRANSIENT_SRC_YTEVENT (1 << 3)
#define MMA8X5X_TRANSIENT_SRC_ZTPOL (1 << 4)
#define MMA8X5X_TRANSIENT_SRC_ZTEVENT (1 << 5)
#define MMA8X5X_TRANSIENT_SRC_EA (1 << 6)
#define MMA8X5X_TRANSIENT_THS_MASK 0x7F
#define MMA8X5X_TRANSIENT_THS_DBCNTM (1<< 7)
#define MMA8X5X_PULSE_CFG_XSPEFE (1 << 0)
#define MMA8X5X_PULSE_CFG_XDPEFE (1 << 1)
#define MMA8X5X_PULSE_CFG_YSPEFE (1 << 2)
#define MMA8X5X_PULSE_CFG_YDPEFE (1 << 3)
#define MMA8X5X_PULSE_CFG_ZSPEFE (1 << 4)
#define MMA8X5X_PULSE_CFG_ZDPEFE (1 << 5)
#define MMA8X5X_PULSE_CFG_ELE (1 << 6)
#define MMA8X5X_PULSE_CFG_DPA (1 << 7)
#define MMA8X5X_PULSE_SRC_POLX (1 << 0)
#define MMA8X5X_PULSE_SRC_POLY (1 << 1)
#define MMA8X5X_PULSE_SRC_POLZ (1 << 2)
#define MMA8X5X_PULSE_SRC_DPE (1 << 3)
#define MMA8X5X_PULSE_SRC_AXX (1 << 4)
#define MMA8X5X_PULSE_SRC_AXY (1 << 5)
#define MMA8X5X_PULSE_SRC_AXZ (1 << 6)
#define MMA8X5X_PULSE_SRC_EA (1 << 7)
#define MMA8X5X_PULSE_THSX_MASK 0x7F
#define MMA8X5X_PULSE_THSY_MASK 0x7F
#define MMA8X5X_PULSE_THSZ_MASK 0x7F
#define MMA8X5X_CTRL_REG1_ACTIVE (1 << 0)
#define MMA8X5X_CTRL_REG1_F_READ (1 << 1)
#define MMA8X5X_CTRL_REG1_DR_MASK 0x38
#define MMA8X5X_CTRL_REG1_DR_SHIFT 3
#define MMA8X5X_CTRL_REG1_DR(x) (((uint8_t)(((uint8_t)(x))<<MMA8X5X_CTRL_REG1_DR_SHIFT))\
&MMA8X5X_CTRL_REG1_DR_MASK)
#define MMA8X5X_CTRL_REG1_ASR_MASK 0xC0
#define MMA8X5X_CTRL_REG1_ASR_50HZ 0
#define MMA8X5X_CTRL_REG1_ASR_12HZ5 1
#define MMA8X5X_CTRL_REG1_ASR_6HZ25 2
#define MMA8X5X_CTRL_REG1_ASR_1HZ56 3
#define MMA8X5X_CTRL_REG2_MODS_MASK 0x3
#define MMA8X5X_CTRL_REG2_MODS_NORMAL 0
#define MMA8X5X_CTRL_REG2_MODS_LNLP 1
#define MMA8X5X_CTRL_REG2_MODS_HR 2
#define MMA8X5X_CTRL_REG2_MODS_LP 3
#define MMA8X5X_CTRL_REG2_SLPE (1 << 2)
#define MMA8X5X_CTRL_REG2_SMODS_MASK 0x18
#define MMA8X5X_CTRL_REG2_SMODS_NORMAL 0
#define MMA8X5X_CTRL_REG2_SMODS_LNLP 1
#define MMA8X5X_CTRL_REG2_SMODS_HR 2
#define MMA8X5X_CTRL_REG2_SMODS_LP 3
#define MMA8X5X_CTRL_REG2_RST (1 << 6)
#define MMA8X5X_CTRL_REG2_ST (1 << 7)
#define MMA8X5X_CTRL_REG3_PP_OD (1 << 0)
#define MMA8X5X_CTRL_REG3_IPOL (1 << 1)
#define MMA8X5X_CTRL_REG3_WAKE_FF_MT (1 << 3)
#define MMA8X5X_CTRL_REG3_WAKE_PULSE (1 << 4)
#define MMA8X5X_CTRL_REG3_WAKE_LNDPRT (1 << 5)
#define MMA8X5X_CTRL_REG3_WAKE_TRANS (1 << 6)
#define MMA8X5X_CTRL_REG3_FIFO_GATE (1 << 7)
#define MMA8X5X_CTRL_REG4_INT_EN_DRDY (1 << 0)
#define MMA8X5X_CTRL_REG4_INT_EN_FF_MT (1 << 2)
#define MMA8X5X_CTRL_REG4_INT_EN_PULSE (1 << 3)
#define MMA8X5X_CTRL_REG4_INT_EN_LNDPRT (1 << 4)
#define MMA8X5X_CTRL_REG4_INT_EN_TRANS (1 << 5)
#define MMA8X5X_CTRL_REG4_INT_EN_FIFO (1 << 6)
#define MMA8X5X_CTRL_REG4_INT_EN_ASLP (1 << 7)
#define MMA8X5X_CTRL_REG5_INT_CFG_DRDY (1 << 0)
#define MMA8X5X_CTRL_REG5_INT_CFG_FF_MT (1 << 2)
#define MMA8X5X_CTRL_REG5_INT_CFG_PULSE (1 << 3)
#define MMA8X5X_CTRL_REG5_INT_CFG_LNDPRT (1 << 4)
#define MMA8X5X_CTRL_REG5_INT_CFG_TRANS (1 << 5)
#define MMA8X5X_CTRL_REG5_INT_CFG_FIFO (1 << 6)
#define MMA8X5X_CTRL_REG5_INT_CFG_ASLP (1 << 7)
/** @} */
#ifdef __cplusplus
}
#endif
#endif
/** @} */

171
drivers/mma8x5x/mma8x5x.c Normal file
View File

@ -0,0 +1,171 @@
/*
* Copyright (C) 2014 PHYTEC Messtechnik GmbH
* 2016 Freie Universität Berlin
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*
*/
/**
* @ingroup drivers_mma8x5x
* @{
*
* @file
* @brief Driver for the Freescale MMA8x5x accelerometer family
*
* @author Johann Fischer <j.fischer@phytec.de>
* @author Peter Kietzmann <peter.kietzmann@haw-hamburg.de>
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
* @}
*/
#include <stdint.h>
#include <stdbool.h>
#include <string.h>
#include "assert.h"
#include "periph/i2c.h"
#include "mma8x5x.h"
#include "mma8x5x_regs.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
#define I2C_SPEED I2C_SPEED_FAST
#define BUS (dev->params.i2c)
#define ADDR (dev->params.addr)
int mma8x5x_init(mma8x5x_t *dev, const mma8x5x_params_t *params)
{
uint8_t reg;
assert(dev && params);
/* write device descriptor */
memcpy(dev, params, sizeof(mma8x5x_params_t));
/* initialize the I2C bus */
i2c_acquire(BUS);
if (i2c_init_master(BUS, I2C_SPEED) < 0) {
i2c_release(BUS);
DEBUG("[mma8x5x] init - error: unable to initialize I2C bus\n");
return MMA8X5X_NOI2C;
}
/* test if the target device responds */
i2c_read_reg(BUS, ADDR, MMA8X5X_WHO_AM_I, &reg);
if (reg != dev->params.type) {
i2c_release(BUS);
DEBUG("[mma8x5x] init - error: invalid WHO_AM_I value [0x%02x]\n",
(int)reg);
return MMA8X5X_NODEV;
}
/* reset the device */
i2c_write_reg(BUS, ADDR, MMA8X5X_CTRL_REG2, MMA8X5X_CTRL_REG2_RST);
do {
i2c_read_reg(BUS, ADDR, MMA8X5X_CTRL_REG2, &reg);
} while (reg & MMA8X5X_CTRL_REG2_RST);
/* configure the user offset */
i2c_write_regs(BUS, ADDR, MMA8X5X_OFF_X, dev->params.offset, 3);
/* configure range, rate, and activate the device */
reg = (dev->params.range & MMA8X5X_XYZ_DATA_CFG_FS_MASK);
i2c_write_reg(BUS, ADDR, MMA8X5X_XYZ_DATA_CFG, reg);
reg = ((dev->params.rate & MMA8X5X_CTRL_REG1_DR_MASK) |
MMA8X5X_CTRL_REG1_ACTIVE);
i2c_write_reg(BUS, ADDR, MMA8X5X_CTRL_REG1, reg);
/* finally release the bus */
i2c_release(BUS);
DEBUG("[mma8x5x] init: successful\n");
return MMA8X5X_OK;
}
void mma8x5x_set_user_offset(mma8x5x_t *dev, int8_t x, int8_t y, int8_t z)
{
uint8_t buf[3];
assert(dev);
buf[0] = (uint8_t)x;
buf[1] = (uint8_t)y;
buf[2] = (uint8_t)z;
DEBUG("[mma8x5x] setting user offset to X: %3i, Y: %3i, Z: %3i\n",
(int)x, (int)y, (int)z);
i2c_acquire(BUS);
i2c_write_regs(BUS, ADDR, MMA8X5X_OFF_X, buf, 3);
i2c_release(BUS);
}
void mma8x5x_set_active(mma8x5x_t *dev)
{
uint8_t reg;
assert(dev);
DEBUG("[mma8x5x] put device to active mode\n");
i2c_acquire(BUS);
i2c_read_reg(BUS, ADDR, MMA8X5X_CTRL_REG1, &reg);
reg |= MMA8X5X_CTRL_REG1_ACTIVE;
i2c_write_reg(BUS, ADDR, MMA8X5X_CTRL_REG1, reg);
i2c_release(BUS);
}
void mma8x5x_set_standby(mma8x5x_t *dev)
{
uint8_t reg;
assert(dev);
DEBUG("[mma8x5x] put device to standby mode\n");
i2c_acquire(BUS);
i2c_read_reg(BUS, ADDR, MMA8X5X_CTRL_REG1, &reg);
reg &= ~MMA8X5X_CTRL_REG1_ACTIVE;
i2c_write_reg(BUS, ADDR, MMA8X5X_CTRL_REG1, reg);
i2c_release(BUS);
}
int mma8x5x_is_ready(mma8x5x_t *dev)
{
uint8_t reg;
assert(dev);
DEBUG("[mma8x5x] checking for new available data\n");
i2c_acquire(BUS);
i2c_read_reg(BUS, ADDR, MMA8X5X_STATUS, &reg);
i2c_release(BUS);
if (reg & MMA8X5X_STATUS_ZYXDR) {
return MMA8X5X_DATA_READY;
}
else {
return MMA8X5X_NODATA;
}
}
void mma8x5x_read(mma8x5x_t *dev, mma8x5x_data_t *data)
{
uint8_t buf[7];
assert(dev);
i2c_acquire(BUS);
i2c_read_regs(BUS, ADDR, MMA8X5X_STATUS, buf, 7);
i2c_release(BUS);
data->x = ((int16_t)(buf[1] << 8 | buf[2])) / (16 >> dev->params.range);
data->y = ((int16_t)(buf[3] << 8 | buf[4])) / (16 >> dev->params.range);
data->z = ((int16_t)(buf[5] << 8 | buf[6])) / (16 >> dev->params.range);
}

View File

@ -7,13 +7,14 @@
*/
/**
* @ingroup driver_mma8652
* @ingroup driver_mma8x5x
* @{
*
* @file
* @brief MMA8652 adaption to the RIOT actuator/sensor interface
* @brief MMA8x5x adaption to the RIOT actuator/sensor interface
*
* @author Cenk Gündoğan <mail@cgundogan.de>
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
* @}
*/
@ -22,34 +23,20 @@
#include <stdio.h>
#include "saul.h"
#include "mma8652.h"
#include "mma8x5x.h"
static int read_acc(void *dev, phydat_t *res)
{
int16_t x, y, z;
uint8_t status;
mma8x5x_read((mma8x5x_t *)dev, (mma8x5x_data_t *)res);
mma8652_t *d = (mma8652_t *)dev;
mma8652_read(d, &x, &y, &z, &status);
res->val[0] = x;
res->val[1] = y;
res->val[2] = z;
res->unit = UNIT_G;
res->scale = -3;
return 3;
}
static int write(void *dev, phydat_t *state)
{
(void) dev;
(void) state;
return -ENOTSUP;
}
const saul_driver_t mma8652_saul_driver = {
const saul_driver_t mma8x5x_saul_driver = {
.read = read_acc,
.write = write,
.write = saul_notsup,
.type = SAUL_SENSE_ACCEL,
};

View File

@ -282,9 +282,9 @@ void auto_init(void)
extern void auto_init_lis3dh(void);
auto_init_lis3dh();
#endif
#ifdef MODULE_MMA8652
extern void auto_init_mma8652(void);
auto_init_mma8652();
#ifdef MODULE_MMA8X5X
extern void auto_init_mma8x5x(void);
auto_init_mma8x5x();
#endif
#ifdef MODULE_SI70XX
extern void auto_init_si70xx(void);

View File

@ -21,7 +21,9 @@
#ifdef MODULE_HDC1000
#include "log.h"
#include "saul_reg.h"
#include "hdc1000.h"
#include "hdc1000_params.h"

View File

@ -1,79 +0,0 @@
/*
* Copyright (C) 2016 Freie Universität Berlin
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*
*/
/**
* @ingroup auto_init_saul
* @{
*
* @file
* @brief Auto initialization of MMA8652 accelerometer
*
* @author Cenk Gündoğan <mail@cgundogan.de>
*
* @}
*/
#ifdef MODULE_MMA8652
#include "saul_reg.h"
#include "mma8652.h"
#include "mma8652_params.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
/**
* @brief Define the number of configured sensors
*/
#define MMA8652_NUM (sizeof(mma8652_params)/sizeof(mma8652_params[0]))
/**
* @brief Allocate memory for the device descriptors
*/
static mma8652_t mma8652_devs[MMA8652_NUM];
/**
* @brief Memory for the SAUL registry entries
*/
static saul_reg_t saul_entries[MMA8652_NUM];
/**
* @brief Reference the driver struct
* @{
*/
extern saul_driver_t mma8652_saul_driver;
/** @} */
void auto_init_mma8652(void)
{
for (unsigned int i = 0; i < MMA8652_NUM; i++) {
const mma8652_params_t *p = &mma8652_params[i];
DEBUG("[auto_init_saul] initializing mma8652 acc sensor\n");
if (mma8652_init(&mma8652_devs[i], p->i2c, p->addr, p->rate, p->scale, p->type) < 0) {
DEBUG("[auto_init_saul] error during initialization\n");
return;
}
if (mma8652_set_active(&mma8652_devs[i]) < 0) {
DEBUG("[auto_init_saul] error activating mma8652\n");
return;
}
saul_entries[i].dev = &(mma8652_devs[i]);
saul_entries[i].name = mma8652_saul_info[i].name;
saul_entries[i].driver = &mma8652_saul_driver;
saul_reg_add(&(saul_entries[i]));
}
}
#else
typedef int dont_be_pedantic;
#endif /* MODULE_MMA8652 */

View File

@ -0,0 +1,70 @@
/*
* Copyright (C) 2016 Freie Universität Berlin
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*
*/
/**
* @ingroup auto_init_saul
* @{
*
* @file
* @brief Auto initialization of MMA8x5x accelerometers
*
* @author Cenk Gündoğan <mail@cgundogan.de>
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
*
* @}
*/
#ifdef MODULE_MMA8X5X
#include "log.h"
#include "saul_reg.h"
#include "mma8x5x.h"
#include "mma8x5x_params.h"
/**
* @brief Define the number of configured sensors
*/
#define MMA8X5X_NUM (sizeof(mma8x5x_params) / sizeof(mma8x5x_params[0]))
/**
* @brief Allocate memory for the device descriptors
*/
static mma8x5x_t mma8x5x_devs[MMA8X5X_NUM];
/**
* @brief Memory for the SAUL registry entries
*/
static saul_reg_t saul_entries[MMA8X5X_NUM];
/**
* @brief Reference the driver struct
* @{
*/
extern saul_driver_t mma8x5x_saul_driver;
/** @} */
void auto_init_mma8x5x(void)
{
for (unsigned i = 0; i < MMA8X5X_NUM; i++) {
if (mma8x5x_init(&mma8x5x_devs[i], &mma8x5x_params[i]) != MMA8X5X_OK) {
LOG_ERROR("Unable to initialize MMA8x5x sensor #%i\n", i);
return;
}
saul_entries[i].dev = &(mma8x5x_devs[i]);
saul_entries[i].name = mma8x5x_saul_info[i].name;
saul_entries[i].driver = &mma8x5x_saul_driver;
saul_reg_add(&(saul_entries[i]));
}
}
#else
typedef int dont_be_pedantic;
#endif /* MODULE_MMA8X5X */

View File

@ -1,25 +0,0 @@
APPLICATION = driver_mma8652
include ../Makefile.tests_common
FEATURES_REQUIRED = periph_i2c
USEMODULE += mma8652
USEMODULE += xtimer
# set default device parameters in case they are undefined
TEST_MMA8652_I2C ?= I2C_DEV\(0\)
TEST_MMA8652_ADDR ?= 0x1D
TEST_MMA8652_USER_OFFSET_X ?= 0
TEST_MMA8652_USER_OFFSET_Y ?= 0
TEST_MMA8652_USER_OFFSET_Z ?= 0
TEST_MMA8x5x_TYPE ?= MMA8x5x_TYPE_MMA8652
# export parameters
CFLAGS += -DTEST_MMA8652_I2C=$(TEST_MMA8652_I2C)
CFLAGS += -DTEST_MMA8652_ADDR=$(TEST_MMA8652_ADDR)
CFLAGS += -DTEST_MMA8652_USER_OFFSET_X=$(TEST_MMA8652_USER_OFFSET_X)
CFLAGS += -DTEST_MMA8652_USER_OFFSET_Y=$(TEST_MMA8652_USER_OFFSET_Y)
CFLAGS += -DTEST_MMA8652_USER_OFFSET_Z=$(TEST_MMA8652_USER_OFFSET_Z)
CFLAGS += -DTEST_MMA8x5x_TYPE=$(TEST_MMA8x5x_TYPE)
include $(RIOTBASE)/Makefile.include

View File

@ -1,10 +0,0 @@
# About
This is a manual test application for the MMA8652 accelerometer driver.
# Usage
This test application will initialize the MMA8652 sensor with the following parameters:
- full scale parameter set to +/-2 g
- 6.25 Hz output data-rate
After initialization, the sensor reads the x-, y-, z-axis values every 1 s
and prints them to STDOUT.

View File

@ -1,79 +0,0 @@
/*
* Copyright (C) 2014 Freie Universität Berlin
* Copyright (C) 2014 PHYTEC Messtechnik GmbH
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup tests
* @{
*
* @file
* @brief Test application for the MMA8652 accelerometer driver.
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Johann Fischer <j.fischer@phytec.de>
*
* @}
*/
#ifndef TEST_MMA8652_I2C
#error "TEST_MMA8652_I2C not defined"
#endif
#ifndef TEST_MMA8652_ADDR
#error "TEST_MMA8652_ADDR not defined"
#endif
#ifndef TEST_MMA8x5x_TYPE
#error "TEST_MMA8x5x_TYPE not defined"
#endif
#include <stdio.h>
#include "xtimer.h"
#include "mma8652.h"
#define SLEEP (1000 * 1000U)
int main(void)
{
mma8652_t dev;
int16_t x, y, z;
uint8_t status;
puts("MMA8652 accelerometer driver test application\n");
printf("Initializing MMA8652 accelerometer at I2C_%i... ", TEST_MMA8652_I2C);
if (mma8652_init(&dev, TEST_MMA8652_I2C, TEST_MMA8652_ADDR,
MMA8652_DATARATE_DEFAULT,
MMA8652_FS_RANGE_DEFAULT,
TEST_MMA8x5x_TYPE) == 0) {
puts("[OK]\n");
}
else {
puts("[Failed]");
return -1;
}
if (mma8652_set_user_offset(&dev, TEST_MMA8652_USER_OFFSET_X,
TEST_MMA8652_USER_OFFSET_Y,
TEST_MMA8652_USER_OFFSET_Z)) {
puts("Set user offset correction failed.");
return -1;
}
if (mma8652_set_active(&dev)) {
puts("Measurement start failed.");
return -1;
}
while (1) {
mma8652_read(&dev, &x, &y, &z, &status);
printf("Acceleration, in mg: X: %d Y: %d Z: %d S: %2x\n", x, y, z, status);
xtimer_usleep(SLEEP);
}
return 0;
}

View File

@ -0,0 +1,9 @@
APPLICATION = driver_mma8x5x
include ../Makefile.tests_common
FEATURES_REQUIRED = periph_i2c
USEMODULE += mma8x5x
USEMODULE += xtimer
include $(RIOTBASE)/Makefile.include

View File

@ -0,0 +1,18 @@
# About
This is a manual test application for the MMA8x5x accelerometer driver.
# Usage
This test application will initialize the MMA8x5x sensor with the following parameters:
- default device type: MMA8652
- full scale parameter set to +/-2 g
- 200 Hz output data-rate
To change these parameters, you can override them by setting their corresponding
defines in your build environment, e.g.
```bash
CFLAGS=-DMMA8X5X_PARAM_TYPE=MMA8X5X_TYPE_MMA8451 make ...
```
See RIOT/drivers/mma8x5x_params.h for the default configuration.
After initialization, the sensor reads the x-, y-, z-axis values every 100ms
and prints them to STDOUT.

View File

@ -0,0 +1,57 @@
/*
* Copyright (C) 2014 Freie Universität Berlin
* Copyright (C) 2014 PHYTEC Messtechnik GmbH
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup tests
* @{
*
* @file
* @brief Test application for the MMA8652 accelerometer driver.
*
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
* @author Johann Fischer <j.fischer@phytec.de>
*
* @}
*/
#include <stdio.h>
#include "xtimer.h"
#include "mma8x5x.h"
#include "mma8x5x_params.h"
#define SLEEP (100 * 1000U)
static mma8x5x_t dev;
int main(void)
{
mma8x5x_data_t data;
puts("MMA8652 accelerometer driver test application\n");
printf("Initializing MMA8652 accelerometer at I2C_DEV(%i)... ",
mma8x5x_params->i2c);
if (mma8x5x_init(&dev, mma8x5x_params) == MMA8X5X_OK) {
puts("[OK]\n");
}
else {
puts("[Failed]");
return -1;
}
while (1) {
mma8x5x_read(&dev, &data);
printf("Acceleration [in mg]: X: %d Y: %d Z: %d\n",
data.x, data.y, data.z);
xtimer_usleep(SLEEP);
}
return 0;
}