kx122: Added driver files to src

Signed-off-by: Samuli Rissanen <samuli.rissanen@hotmail.com>
Signed-off-by: Noel Eck <noel.eck@intel.com>
This commit is contained in:
Samuli Rissanen 2018-02-22 13:04:21 +02:00
parent 829da899fc
commit 8f99289a48
7 changed files with 3137 additions and 0 deletions

8
src/kx122/CMakeLists.txt Normal file
View File

@ -0,0 +1,8 @@
upm_mixed_module_init (NAME kx122
DESCRIPTION "3-Axis Digital Accelerometer"
C_HDR kx122.h kx122_registers.h
C_SRC kx122.c
CPP_HDR kx122.hpp
CPP_SRC kx122.cxx
CPP_WRAPS_C
REQUIRES mraa m)

1033
src/kx122/kx122.c Normal file

File diff suppressed because it is too large Load Diff

321
src/kx122/kx122.cxx Normal file
View File

@ -0,0 +1,321 @@
/*
* The MIT License (MIT)
*
* Author: Samuli Rissanen <samuli.rissanen@hotmail.com>
* Copyright (c) 2018 Rohm Semiconductor.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*/
#include <iostream>
#include <stdexcept>
#include <string>
#include <unistd.h>
#include "kx122.hpp"
using namespace upm;
KX122::KX122(int bus, int addr, int chip_select) : m_kx122(kx122_init(bus,addr,chip_select))
{
if(!m_kx122){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_init() failed");
}
}
KX122::~KX122()
{
kx122_close(m_kx122);
}
void KX122::deviceInit(KX122_ODR_T odr, KX122_RES_T res, KX122_RANGE_T grange)
{
if(kx122_device_init(m_kx122,odr,res,grange)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_device_init() failed");
}
}
float KX122::getSamplePeriod()
{
return kx122_get_sample_period(m_kx122);
}
void KX122::getRawAccelerationData(float *x, float *y, float *z)
{
if(kx122_get_acceleration_data_raw(m_kx122,x,y,z)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_get_accleration_data_raw failed");
}
}
void KX122::getAccelerationData(float *x, float *y, float *z)
{
if(kx122_get_acceleration_data(m_kx122,x,y,z)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_get_acceleration_data failed");
}
}
void KX122::softwareReset()
{
if(kx122_sensor_software_reset(m_kx122)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_sensor_software_reset failed");
}
}
void KX122::enableIIR()
{
if(kx122_enable_iir(m_kx122)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_enable_iir failed");
}
}
void KX122::disableIIR()
{
if(kx122_disable_iir(m_kx122)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_disable_iir failed");
}
}
void KX122::selfTest()
{
if(kx122_self_test(m_kx122)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_self_test failed");
}
}
void KX122::setSensorStandby()
{
if(kx122_set_sensor_standby(m_kx122)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_set_sensor_standby failed");
}
}
void KX122::setSensorActive()
{
if(kx122_set_sensor_active(m_kx122)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_set_sensor_active failed");
}
}
void KX122::setODR(KX122_ODR_T odr)
{
if(kx122_set_odr(m_kx122,odr)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_set_odr failed");
}
}
void KX122::setGrange(KX122_RANGE_T grange)
{
if(kx122_set_grange(m_kx122,grange)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_set_grange failed");
}
}
void KX122::setResolution(KX122_RES_T res)
{
if(kx122_set_resolution(m_kx122,res)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_set_resolution failed");
}
}
void KX122::setBW(LPRO_STATE_T lpro)
{
if(kx122_set_bw(m_kx122,lpro)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_set_bw failed");
}
}
void KX122::setAverage(KX122_AVG_T avg)
{
if(kx122_set_average(m_kx122,avg)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_set_average failed");
}
}
void KX122::installISR(mraa::Edge edge, KX122_INTERRUPT_PIN_T intp, int pin, void(*isr)(void*),void *arg)
{
if(kx122_install_isr(m_kx122,(mraa_gpio_edge_t)edge,intp,pin,isr,arg)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_install_isr failed");
}
}
void KX122::uninstallISR(KX122_INTERRUPT_PIN_T intp)
{
kx122_uninstall_isr(m_kx122,intp);
}
void KX122::enableInterrupt1(KX122_INTERRUPT_POLARITY_T polarity)
{
if(kx122_enable_interrupt1(m_kx122,polarity)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_enable_interrupt1 failed");
}
}
void KX122::enableInterrupt2(KX122_INTERRUPT_POLARITY_T polarity)
{
if(kx122_enable_interrupt2(m_kx122,polarity)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_enable_interrupt2 failed");
}
}
void KX122::disableInterrupt1()
{
if(kx122_disable_interrupt1(m_kx122)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_disable_interrupt1 failed");
}
}
void KX122::disableInterrupt2()
{
if(kx122_disable_interrupt2(m_kx122)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_disable_interrupt2 failed");
}
}
void KX122::routeInterrupt1(uint8_t bits)
{
if(kx122_route_interrupt1(m_kx122,bits)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_route_interrupt1 failed");
}
}
void KX122::routeInterrupt2(uint8_t bits)
{
if(kx122_route_interrupt2(m_kx122,bits)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_route_interrupt2 failed");
}
}
void KX122::getInterruptStatus(uint8_t *data)
{
if(kx122_get_interrupt_status(m_kx122,data)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_get_interrupt_status failed");
}
}
void KX122::getInterruptSource(uint8_t *data)
{
if(kx122_get_interrupt_source(m_kx122,data)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_get_interrupt_source failed");
}
}
void KX122::clearInterrupt()
{
if(kx122_clear_interrupt(m_kx122)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_clear_interrupt failed");
}
}
void KX122::enableDataReadyInterrupt()
{
if(kx122_enable_data_ready_interrupt(m_kx122)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_enable_data_ready_interrupt failed");
}
}
void KX122::disableDataReadyInterrupt()
{
if(kx122_disable_data_ready_interrupt(m_kx122)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_disable_data_ready_interrupt failed");
}
}
void KX122::enableBufferFullInterrupt()
{
if(kx122_enable_buffer_full_interrupt(m_kx122)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_enable_buffer_full_interrupt failed");
}
}
void KX122::disableBufferFullInterrupt()
{
if(kx122_disable_buffer_full_interrupt(m_kx122)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_disable_buffer_full_interrupt failed");
}
}
void KX122::enableBuffer()
{
if(kx122_enable_buffer(m_kx122)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_enable_buffer failed");
}
}
void KX122::disableBuffer()
{
if(kx122_disable_buffer(m_kx122)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_disable_buffer failed");
}
}
void KX122::bufferInit(uint samples, KX122_RES_T res, KX122_BUFFER_MODE_T mode)
{
if(kx122_buffer_init(m_kx122,samples,res,mode)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_buffer_init failed");
}
}
void KX122::setBufferResolution(KX122_RES_T res)
{
if(kx122_set_buffer_resolution(m_kx122,res)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_set_buffer_resolution failed");
}
}
void KX122::setBufferThreshold(uint samples)
{
if(kx122_set_buffer_threshold(m_kx122,samples)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_set_buffer_threshold failed");
}
}
void KX122::setBufferMode(KX122_BUFFER_MODE_T mode)
{
if(kx122_set_buffer_mode(m_kx122,mode)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_set_buffer_mode failed");
}
}
void KX122::getBufferStatus(uint *samples)
{
if(kx122_get_buffer_status(m_kx122,samples)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_get_buffer_status failed");
}
}
void KX122::getRawBufferSamples(uint len, float *x_array, float *y_array, float *z_array)
{
if(kx122_read_buffer_samples_raw(m_kx122,len,x_array,y_array,z_array)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_read_buffer_samples_raw failed");
}
}
void KX122::getBufferSamples(uint len, float *x_array, float *y_array, float *z_array)
{
if(kx122_read_buffer_samples(m_kx122,len,x_array,y_array,z_array)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_read_buffer_samples failed");
}
}
void KX122::clearBuffer()
{
if(kx122_clear_buffer(m_kx122)){
throw std::runtime_error(std::string(__FUNCTION__) + "kx122_clear_buffer failed");
}
}

696
src/kx122/kx122.h Normal file
View File

@ -0,0 +1,696 @@
/*
* The MIT License (MIT)
*
* Author: Samuli Rissanen <samuli.rissanen@hotmail.com>
* Copyright (c) 2018 Rohm Semiconductor.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*/
#include <assert.h>
#include <unistd.h>
#include <math.h>
#include <mraa/i2c.h>
#include <mraa/spi.h>
#include <mraa/gpio.h>
#include <upm/upm_types.h>
#include "kx122_registers.h"
/**
* @file kx122.h
* @library kx122
* @brief C API for the kx122 driver
*
* @include kx122.c
*/
//Used to set the bit required for SPI reading
#define SPI_READ 0x80
//Used to mask the read bit required for SPI writing
#define SPI_WRITE 0x7F
//Frequency of the SPI connection
#define SPI_FREQUENCY 10000
//Default slave addresses for the sensor
#define KX122_DEFAULT_SLAVE_ADDR_1 0x1F
#define KX122_DEFAULT_SLAVE_ADDR_2 0x1E
//Masks
#define KX122_CNTL2_SRST_MASK 0x80
//Used to determine amount of samples in the buffer.
#define LOW_RES_SAMPLE_MODIFIER 3
#define HIGH_RES_SAMPLE_MODIFIER 6
//Masks for interrupt control registers
#define KX122_INC1_MASK 0xFB
#define KX122_INC4_MASK 0xF7
#define KX122_INC5_MASK 0xFB
#define KX122_INC6_MASK 0xF7
//Acceleration data buffer length
#define BUFFER_LEN 6
//Acceleration per decimal value for each acceleration ranges
#define RANGE_2G_G 0.00006f
#define RANGE_4G_G 0.00012f
#define RANGE_8G_G 0.00024f
//Acceleration scaling between high and low resolution modes
#define RANGE_RES_SCALE 260
//Maximum loop iterations
#define MAX_LOOP_COUNT 100
//Sensor self-test defines
#define SELF_TEST_LOOP_WAIT_TIME 10000
#define SELF_TEST_MAX_DIFFERENCE 0.75f
#define SELF_TEST_MIN_XY_DIFFERENCE 0.25f
#define SELF_TEST_MIN_Z_DIFFERENCE 0.20f
//Maximum amount of samples in the buffer for high and low resolutions
#define MAX_BUFFER_SAMPLES_LOW_RES 681
#define MAX_BUFFER_SAMPLES_HIGH_RES 340
//Earth gravity constant (m/s^2)
#define GRAVITY 9.81f
//Microseconds in a second
#define MICRO_S 1000000
//Sensor ODR values
typedef enum{
KX122_ODR_12P5 = KX122_ODCNTL_OSA_12P5,
KX122_ODR_25 = KX122_ODCNTL_OSA_25,
KX122_ODR_50 = KX122_ODCNTL_OSA_50,
KX122_ODR_100 = KX122_ODCNTL_OSA_100,
KX122_ODR_200 = KX122_ODCNTL_OSA_200,
KX122_ODR_400 = KX122_ODCNTL_OSA_400,
KX122_ODR_800 = KX122_ODCNTL_OSA_800,
KX122_ODR_1600 = KX122_ODCNTL_OSA_1600,
KX122_ODR_0P781 = KX122_ODCNTL_OSA_0P781,
KX122_ODR_1P563 = KX122_ODCNTL_OSA_1P563,
KX122_ODR_3P125 = KX122_ODCNTL_OSA_3P125,
KX122_ODR_6P25 = KX122_ODCNTL_OSA_6P25,
KX122_ODR_3200 = KX122_ODCNTL_OSA_3200,
KX122_ODR_6400 = KX122_ODCNTL_OSA_6400,
KX122_ODR_12800 = KX122_ODCNTL_OSA_12800,
KX122_ODR_25600 = KX122_ODCNTL_OSA_25600
} KX122_ODR_T;
//Sensor average values
typedef enum{
KX122_NO_AVG = KX122_LP_CNTL_AVC_NO_AVG,
KX122_2_SAMPLE_AVG = KX122_LP_CNTL_AVC_2_SAMPLE_AVG,
KX122_4_SAMPLE_AVG = KX122_LP_CNTL_AVC_4_SAMPLE_AVG,
KX122_8_SAMPLE_AVG = KX122_LP_CNTL_AVC_8_SAMPLE_AVG,
KX122_16_SAMPLE_AVG = KX122_LP_CNTL_AVC_16_SAMPLE_AVG,
KX122_32_SAMPLE_AVG = KX122_LP_CNTL_AVC_32_SAMPLE_AVG,
KX122_64_SAMPLE_AVG = KX122_LP_CNTL_AVC_64_SAMPLE_AVG,
KX122_128_SAMPLE_AVG = KX122_LP_CNTL_AVC_128_SAMPLE_AVG
} KX122_AVG_T;
//Sensor range values
typedef enum{
KX122_RANGE_2G = KX122_CNTL1_GSEL_2G,
KX122_RANGE_4G = KX122_CNTL1_GSEL_4G,
KX122_RANGE_8G = KX122_CNTL1_GSEL_8G
} KX122_RANGE_T;
//Sensor buffer modes
typedef enum{
KX122_FIFO_MODE = KX122_BUF_CNTL2_BUF_M_FIFO,
KX122_FILO_MODE = KX122_BUF_CNTL2_BUF_M_FILO,
KX122_STREAM_MODE = KX122_BUF_CNTL2_BUF_M_STREAM,
} KX122_BUFFER_MODE_T;
//Sensor interrupt types
typedef enum{
KX122_BUF_FULL_INT = KX122_INC4_BFI1,
KX122_WATERMARK_INT = KX122_INC4_WMI1,
KX122_DATA_READY_INT = KX122_INC4_DRDYI1
} KX122_INTERRUPT_T;
//High and low resolution modes
typedef enum{
HIGH_RES,
LOW_RES
} KX122_RES_T;
//Sensor low-pass filter roll of values
typedef enum{
ODR_9,
ODR_2
} LPRO_STATE_T;
//Interrupt pins
typedef enum{
INT1,
INT2
}KX122_INTERRUPT_PIN_T;
//Interrupt polarity
typedef enum{
ACTIVE_LOW,
ACTIVE_HIGH
} KX122_INTERRUPT_POLARITY_T;
//Device context
typedef struct _kx122_context {
mraa_i2c_context i2c;
mraa_spi_context spi;
mraa_gpio_context gpio1; //Interrupt pin 1
mraa_gpio_context gpio2; //Interrupt pin 2
mraa_gpio_context chip_select; //Chip select pin (SPI)
float accel_scale; //Acceleration scaling
KX122_RES_T res_mode; //Sensor resolution
KX122_RANGE_T grange_mode; //Sensor range
float buffer_accel_scale; //Buffer acceleration scaling
KX122_BUFFER_MODE_T buffer_mode; //Buffer mode
KX122_RES_T buffer_res; //Buffer resolution
bool using_spi;
} *kx122_context;
//Struct for ODR values and their decimal counterparts.
typedef struct _odr_item{
uint8_t odr_value;
float odr_decimal;
} odr_item;
/**
KX122 initialization
Set addr to -1 if using SPI.
When using I2C, set chip_select_pin to -1;
@param bus I2C or SPI bus to use.
@param addr I2C address of the sensor.
@param chip_select Chip select pin for SPI.
@return The device context, or NULL if an error occurs.
*/
kx122_context kx122_init(int bus, int addr, int chip_select_pin);
/**
KX122 destructor
Closes the I2C or SPI context, and removes interrupts.
Frees memory of the kx122_context.
@param dev The device context.
*/
void kx122_close(kx122_context dev);
/**
Intilializes the sensor with the given sampling rate, resolution and acceleration range.
This gets called during the kx122_init(), so it will not need to be called unless the device is reset.
Sensor is automatically set into standby mode during the initialization.
Sensor is set to active mode after initialization.
@param dev The device context.
@param odr One of the KX122_ODR_T values.
@param res One of the KX122_RES_T values.
@param grange One of the KX122_RANGE_T values.
@return UPM result.
*/
upm_result_t kx122_device_init(const kx122_context dev, KX122_ODR_T odr, KX122_RES_T res, KX122_RANGE_T grange);
/**
Gets the length of one sample period depending on the sampling rate of the sensor.
@param dev The device context.
@return Floating point value of the sampling period, or if an error occurs returns -1.
*/
float kx122_get_sample_period(const kx122_context dev);
/**
Gets who am i value of the sensor.
@param dev The device context.
@param data Pointer to a uint8_t variable to store the value.
@return UPM result.
*/
upm_result_t kx122_get_who_am_i(const kx122_context dev, uint8_t *data);
/**
Gets raw accelerometer data from the sensor.
@param dev The device context.
@param x Pointer to a floating point variable to store the x-axis value. Can be set to NULL if not wanted.
@param y Pointer to a floating point variable to store the y-axis value. Can be set to NULL if not wanted.
@param z Pointer to a floating point variable to store the z-axis value. Can be set to NULL if not wanted.
@return UPM result.
*/
upm_result_t kx122_get_acceleration_data_raw(const kx122_context dev, float *x, float *y, float *z);
/**
Gets converted (m/s^2) accelerometer data from the sensor.
@param dev The device context.
@param x Pointer to a floating point variable to store the x-axis value. Can be set to NULL if not wanted.
@param y Pointer to a floating point variable to store the y-axis value. Can be set to NULL if not wanted.
@param z Pointer to a floating point variable to store the z-axis value. Can be set to NULL if not wanted.
*/
upm_result_t kx122_get_acceleration_data(const kx122_context dev, float *x, float *y, float *z);
/**
Performs a sensor software reset. The software reset clears the RAM of the sensor and resets all registers
to pre-defined values.
You should call kx122_device_init() after the software reset.
See the datasheet for more details.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_sensor_software_reset(const kx122_context dev);
/**
Enables sensor filter bypass.
Sensor needs to be in standby mode when enabling the filter bypass.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_enable_iir(const kx122_context dev);
/**
Disables sensor filter bypass.
Sensor needs to be in standby mode when disabling the filter bypass.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_disable_iir(const kx122_context dev);
/**
Performs a self-test of the sensor. The test applies an electrostatic force to the sensor,
simulating input acceleration. The test compares samples from all axis before and after
applying the electrostatic force to the sensor. If the amount of acceleration increases according
to the values defined in TABLE 1 of the datasheet, the test passes.
See the datasheet for more information.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_self_test(const kx122_context dev);
/**
Sets the sensor to the standby mode.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_set_sensor_standby(const kx122_context dev);
/**
Sets the sensor to active mode.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_set_sensor_active(const kx122_context dev);
/**
Sets the data sampling rate of the sensor.
Sensor needs to be in standby mode when setting the data sampling rate.
@param dev The device context.
@param odr One of the KX122_ODR_T values.
@return UPM result.
*/
upm_result_t kx122_set_odr(const kx122_context dev, KX122_ODR_T odr);
/**
Sets the acceleration range of the sensor.
Sensor needs to be in standby mode when setting the acceleration range value.
@param dev The device context.
@param grange One of the KX122_RANGE_T values.
@return UPM result.
*/
upm_result_t kx122_set_grange(const kx122_context dev, KX122_RANGE_T grange);
/**
Sets the resolution of the sensor. High resolution (16 bits) or low resolution (8 bits).
Sensor needs to be in standby mode when setting the sensor resolution.
@param dev The device context.
@param res One of the KX122_RES_T values.
@return UPM result.
*/
upm_result_t kx122_set_resolution(const kx122_context dev, KX122_RES_T res);
/**
Sets the low pass filter roll off
Sensor needs to be in standby mode when setting the filter roll off value.
@param dev The device context.
@param lpro One of the LPRO_STATE_T values.
@return UPM result.
*/
upm_result_t kx122_set_bw(const kx122_context dev, LPRO_STATE_T lpro);
/**
Set the amount of samples to be averaged in low power mode.
Sensor needs to be in standby mode when setting the average value.
@param dev The device context.
@param avg One of the KX122_AVG_T values.
@return UPM result.
*/
upm_result_t kx122_set_average(const kx122_context dev, KX122_AVG_T avg);
/**
Installs an interrupt handler to be executed when an interrupt is detected on the interrupt pin.
@param dev The device context.
@param edge One of the mraa_gpio_edge_t values. Interrupt trigger edge.
@param intp One of the KX122_INTERRUPT_PIN_T values. Specifies which interrupt pin you are setting.
@param pin The GPIO pin to use as the interrupt pin.
@param isr Pointer to the function to be called, when the interrupt occurs.
@param arg The arguments to be passed to the function.
@return UPM result.
*/
upm_result_t kx122_install_isr(const kx122_context dev, mraa_gpio_edge_t edge,KX122_INTERRUPT_PIN_T intp, int pin,void (*isr)(void *), void *arg);
/**
Uninstalls a previously installed interrupt handler.
@param dev The device context.
@param intp One of the KX122_INTERRUPT_PIN_T values. Specifies which interrupt pin handler is uninstalled.
*/
void kx122_uninstall_isr(const kx122_context dev, KX122_INTERRUPT_PIN_T intp);
/**
Enables interrupts on the interrupt pin 1 of the sensor.
Pulse width = 50us (10us if data sampling rate > 1600Hz).
Using pulse mode.
Sensor needs to be in standby mode when enabling the interrupt.
See datasheet for more details.
@param dev The device context.
@param polarity One of the KX122_INTERRUPT_POLARITY_T values. Select the polarity of the interrupt.
@return UPM result.
*/
upm_result_t kx122_enable_interrupt1(const kx122_context dev, KX122_INTERRUPT_POLARITY_T polarity);
/**
Enables interrupts on the interrupt pin 2 of the sensor.
Pulse width = 50us (10us if data sampling rate > 1600Hz).
Using pulse mode.
Sensor needs to be in standby mode when enabling the interrupt.
See datasheet for more details.
@param dev The device context.
@param polarity One of the KX122_INTERRUPT_POLARITY_T values. Select the polarity of the interrupt.
@return UPM result.
*/
upm_result_t kx122_enable_interrupt2(const kx122_context dev, KX122_INTERRUPT_POLARITY_T polarity);
/**
Disables interrupts on the interrupt pin 1 of the sensor.
Sensor needs to be in standby mode when disabling the interrupt pin 1.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_disable_interrupt1(const kx122_context dev);
/**
Disables interrupts on the interrupt pin 2 of the sensor.
Sensor needs to be in standby mode when disabling the interrupt pin 2.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_disable_interrupt2(const kx122_context dev);
/**
Routes the interrupts to the interrupt pin 1 of the sensor.
Sensor needs to be in standby mode when routing the interrupts.
See datasheet for more details.
@param dev The device context.
@param bits One or more of the KX122_INTERRUPT_T values. Combine with bitwise OR (|)
@return UPM result.
*/
upm_result_t kx122_route_interrupt1(const kx122_context dev, uint8_t bits);
/**
Routes the interrupts to the interrupt pin 2 of the sensor.
Sensor needs to be in standby mode when routing the interrupts.
See datasheet for more details.
@param dev The device context.
@param bits One or more of the KX122_INTERRUPT_T values. Combine with bitwise OR (|)
@return UPM result.
*/
upm_result_t kx122_route_interrupt2(const kx122_context dev, uint8_t bits);
/**
Gets the status of the interrupts. (Has an interrupt occured)
See datasheet for more details.
@param dev The device context.
@param data Pointer to a uint8_t variable to store the value.
@return UPM result.
*/
upm_result_t kx122_get_interrupt_status(const kx122_context dev, uint8_t *data);
/**
Gets the source of the interrupt.
See datasheet for more details.
@param dev The device context.
@param data Pointer to a uint8_t variable to store the value.
@return UPM result.
*/
upm_result_t kx122_get_interrupt_source(const kx122_context dev, uint8_t *data);
/**
Clears latching interrupts (Wakeup, Data Ready).
See datasheet for more details.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_clear_interrupt(const kx122_context dev);
/**
Enables the data ready interrupt. Availability of new acceleration data is
reflected as an interrupt.
Sensor needs to be in standby mode when enabling the interrupt.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_enable_data_ready_interrupt(const kx122_context dev);
/**
Disables the data ready interrupt.
Sensor needs to be in standby mode when disabling the interrupt.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_disable_data_ready_interrupt(const kx122_context dev);
/**
Enables the buffer full interrupt.
Buffer can hold 681 sets of values (8 bit, low resolution mode) or
340 sets of values (16 bit, high resolution mode).
Sensor needs to be in standby mode when enabling the interrupt.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_enable_buffer_full_interrupt(const kx122_context dev);
/**
Disables the buffer full interrupt.
Sensor needs to be in standby mode when disabling the interrupt.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_disable_buffer_full_interrupt(const kx122_context dev);
/**
Enables the buffer.
Sensor needs to be in standby mode when enabling the buffer.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_enable_buffer(const kx122_context dev);
/**
Disables the buffer.
Sensor needs to be in standby mode when disabling the buffer.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_disable_buffer(const kx122_context dev);
/**
Initializes the buffer with the given sample watermark level, buffer resolution and buffer operating mode.
Buffer is enabled after the initialization.
Sensor is automatically set into standby mode during the buffer initialization.
Sensor is set to active mode after initialization.
See the other buffer functions for details about the different parameter values.
@param dev The device context.
@param samples Amount of samples to trigger the watermark interrupt.
@param res One of the KX122_RES_T values.
@param mode One of the KX122_BUFFER_MODE_T values.
@return UPM result.
*/
upm_result_t kx122_buffer_init(const kx122_context dev, uint samples, KX122_RES_T res, KX122_BUFFER_MODE_T mode);
/**
Sets the buffer resolution.
Buffer resolution is indepedent of the sensor resolution.
Sensor needs to be in standby mode when setting the buffer resolution.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_set_buffer_resolution(const kx122_context dev, KX122_RES_T res);
/**
Sets the buffer watermark interrupt threshold.
When the buffer sample count reaches the watermark, watermark interrupt will be given.
In low resolution mode, maxiumum number of samples is 681. In high resolution, the maximum
number is 340.
See datasheet for more details.
Sensor needs to be in standby mode when setting the buffer threshold.
@param dev The device context.
@param samples Amount of samples to trigger the watermark interrupt.
@return UPM result.
*/
upm_result_t kx122_set_buffer_threshold(const kx122_context dev, uint samples);
/**
Sets the buffer operating mode.
The buffer can operate in FIFO,FILO or Stream mode.
The buffer gathers data, reports data and interracts with the status indicators
in a slightly different way depending on the operating mode.
See datasheet for more details.
Sensor needs to be in standby mode when setting the buffer mode.
@param dev The device context.
@param mode One of the KX122_BUFFER_MODE_T values.
@return UPM result.
*/
upm_result_t kx122_set_buffer_mode(const kx122_context dev, KX122_BUFFER_MODE_T mode);
/**
Gets the current amount of samples in the buffer.
@param dev The device context.
@param samples Pointer to an uint variable to store the data.
@return UPM result.
*/
upm_result_t kx122_get_buffer_status(const kx122_context dev, uint *samples);
/**
Gets the specified amount of raw acceleration samples from the buffer.
Make sure the array size is atleast the amount of samples to be read.
@param dev The device context.
@param len The amount of samples to read from the buffer.
@param x_array Pointer to an floating point array to store the x-axis data. Can be set to NULL if not wanted.
@param y_array Pointer to an floating point array to store the y-axis data. Can be set to NULL if not wanted.
@param z_array Pointer to an floating point array to store the z-axis data. Can be set to NULL if not wanted.
@return UPM result.
*/
upm_result_t kx122_read_buffer_samples_raw(const kx122_context dev, uint len, float *x_array, float *y_array, float *z_array);
/**
Gets the specified amount of converted (m/s^2) acceleration samples from the buffer.
Make sure the array size is atleast the amount of samples to be read.
@param dev The device context.
@param len The amount of samples to read from the buffer.
@param x_array Pointer to an floating point array to store the x-axis data. Can be set to NULL if not wanted.
@param y_array Pointer to an floating point array to store the y-axis data. Can be set to NULL if not wanted.
@param z_array Pointer to an floating point array to store the z-axis data. Can be set to NULL if not wanted.
@return UPM result.
*/
upm_result_t kx122_read_buffer_samples(const kx122_context dev, uint len, float *x_array, float *y_array, float *z_array);
/**
Clears the buffer, removing all existing samples from the buffer.
@param dev The device context.
@return UPM result.
*/
upm_result_t kx122_clear_buffer(const kx122_context dev);

493
src/kx122/kx122.hpp Normal file
View File

@ -0,0 +1,493 @@
/*
* The MIT License (MIT)
*
* Author: Samuli Rissanen <samuli.rissanen@hotmail.com>
* Copyright (c) 2018 Rohm Semiconductor.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*/
#include <mraa/gpio.hpp>
extern "C"{
#include "kx122.h"
}
/**
* @file kx122.hpp
* @library kx122
* @brief C++ API for the kx122 driver
*
* @include kx122.cxx
*/
namespace upm{
class KX122{
public:
/**
KX122 constructor
Set addr to -1 if using SPI.
When using I2C, set chip_select_pin to -1
@param bus I2C or SPI bus to use.
@param addr I2C address of the sensor.
@param chip_select Chip select pin for SPI.
@throws std::runtime_error on initialization failure.
*/
KX122(int bus, int addr, int chip_select);
/**
KX122 destructor
*/
~KX122();
/**
Initializes the sensor with given sampling rate, resolution and acceleration range.
This gets called in the constructor, so it will not need to be called unless the device is reset.
Sensor is automatically set into standby mode during the initialization.
Sensor is set to active mode after initialization.
@param odr One of the KX122_ODR_T values.
@param res One of the KX122_RES_T values.
@param grange One of the KX122_RANGE_T values.
@throws std::runtime_error on failure.
*/
void deviceInit(KX122_ODR_T odr, KX122_RES_T res, KX122_RANGE_T grange);
/**
Gets the length of one sample period depeding on the sampling rate of the sensor.
@return Floating point value of the sampling period, or if error occurs returns -1.
*/
float getSamplePeriod();
/**
Gets who am i value of the sensor.
@param data Pointer to a uint8_t variable to store the value.
@throws std::runtime_error on failure.
*/
void getWhoAmI(uint8_t *data);
/**
Gets raw accelerometer data from the sensor.
@param x Pointer to a floating point variable to store the x-axis value. Can be set to NULL if not wanted.
@param y Pointer to a floating point variable to store the y-axis value. Can be set to NULL if not wanted.
@param z Pointer to a floating point variable to store the z-axis value. Can be set to NULL if not wanted.
@throws std::runtime_error on failure.
*/
void getRawAccelerationData(float *x, float *y, float *z);
/**
Gets converted (m/s^2) accelerometer data from the sensor.
@param x Pointer to a floating point variable to store the x-axis value. Can be set to NULL if not wanted.
@param y Pointer to a floating point variable to store the y-axis value. Can be set to NULL if not wanted.
@param z Pointer to a floating point variable to store the z-axis value. Can be set to NULL if not wanted.
@throws std::runtime_error on failure.
*/
void getAccelerationData(float *x, float *y, float *z);
/**
Performs a sensor software reset. The software reset clears the RAM of the sensor and resets all registers
to pre-defined values.
You should call deviceInit() after the software reset.
See the datasheet for more details.
@throws std::runtime_error on failure.
*/
void softwareReset();
/**
Enables sensor filter bypass.
Sensor needs to be in standby mode when enabling the filter bypass.
@throws std::runtime_error on failure.
*/
void enableIIR();
/**
Disables sensor filter bypass.
Sensor needs to be in standby mode when enabling the filter bypass.
@throws std::runtime_error on failure.
*/
void disableIIR();
/**
Performs a self-test of the sensor. The test applies an electrostatic force to the sensor,
simulating input acceleration. The test compares samples from all axis before and after
applying the electrostatic force to the sensor. If the amount of acceleration increases according
to the values defined in TABLE 1 of the datasheet, the test passes.
See the datasheet for more information.
@throws std::runtime_error on failure.
*/
void selfTest();
/**
Sets the sensor to the standby mode.
@throws std::runtime_error on failure.
*/
void setSensorStandby();
/**
Sets the sensor to the active mode.
@throws std::runtime_error on failure.
*/
void setSensorActive();
/**
Sets the data sampling rate of the sensor.
Sensor needs to be in standby mode when setting the data sampling rate.
@param odr One of the KX122_ODR_T values.
@throws std::runtime_error on failure.
*/
void setODR(KX122_ODR_T odr);
/**
Sets the acceleration range of the sensor.
Sensor needs to be in standby mode when setting the acceleration range value.
@param grange One of the KX122_RANGE_T values.
@throws std::runtime_error on failure.
*/
void setGrange(KX122_RANGE_T grange);
/**
Sets the resolution of the sensor. High resolution (16 bits) or low resolution (8 bits).
Sensor needs to be in standby mode when setting the sensor resolution.
@param res One of the KX122_RES_T values.
@throws std::runtime_error on failure.
*/
void setResolution(KX122_RES_T res);
/**
Sets the low pass filter roll off
Sensor needs to be in standby mode when setting the filter roll off value.
@param lpro One of the LPRO_STATE_T values.
@throws std::runtime_error on failure.
*/
void setBW(LPRO_STATE_T lpro);
/**
Set the amount of samples to be averaged in low power mode.
Sensor needs to be in standby mode when setting the average value.
@param avg One of the KX122_AVG_T values.
@throws std::runtime_error on failure.
*/
void setAverage(KX122_AVG_T avg);
/**
Installs an interrupt handler to be executed when an interrupt is detected on the interrupt pin.
@param edge One of the mraa::Edge values. Interrupt trigger edge.
@param intp One of the KX122_INTERRUPT_PIN_T values. Specifies which interrupt pin you are setting.
@param pin The GPIO pin to use as the interrupt pin.
@param isr Pointer to the function to be called, when the interrupt occurs.
@param arg The arguments to be passed to the function.
@throws std::runtime_error on failure.
*/
void installISR(mraa::Edge edge, KX122_INTERRUPT_PIN_T intp, int pin, void (*isr)(void*), void *arg);
/**
Uninstalls a previously installed interrupt handler.
@param intp One of the KX122_INTERRUPT_PIN_T values. Specifies which interrupt pin handler is uninstalled.
@throws std::runtime_error on failure.
*/
void uninstallISR(KX122_INTERRUPT_PIN_T intp);
/**
Enables interrupts on the interrupt pin 1 of the sensor.
Pulse width = 50us (10us if data sampling rate > 1600Hz).
Using pulse mode.
Sensor needs to be in standby mode when enabling the interrupt.
See datasheet for more details.
@param polarity One of the KX122_INTERRUPT_POLARITY_T values. Select the polarity of the interrupt.
@throws std::runtime_error on failure.
*/
void enableInterrupt1(KX122_INTERRUPT_POLARITY_T polarity);
/**
Enables interrupts on the interrupt pin 2 of the sensor.
Pulse width = 50us (10us if data sampling rate > 1600Hz).
Using pulse mode.
Sensor needs to be in standby mode when enabling the interrupt.
See datasheet for more details.
@param polarity One of the KX122_INTERRUPT_POLARITY_T values. Select the polarity of the interrupt.
@throws std::runtime_error on failure.
*/
void enableInterrupt2(KX122_INTERRUPT_POLARITY_T polarity);
/**
Disables interrupts on the interrupt pin 1 of the sensor.
Sensor needs to be in standby mode when disabling the interrupt pin 1.
@throws std::runtime_error on failure.
*/
void disableInterrupt1();
/**
Disables interrupts on the interrupt pin 2 of the sensor.
Sensor needs to be in standby mode when disabling the interrupt pin 2.
@throws std::runtime_error on failure.
*/
void disableInterrupt2();
/**
Routes the interrupts to the interrupt pin 1 of the sensor.
Sensor needs to be in standby mode when routing the interrupts.
See datasheet for more details.
@param bits One or more of the KX122_INTERRUPT_T values. Combine with bitwise OR (|)
@throws std::runtime_error on failure.
*/
void routeInterrupt1(uint8_t bits);
/**
Routes the interrupts to the interrupt pin 2 of the sensor.
Sensor needs to be in standby mode when routing the interrupts.
See datasheet for more details.
@param bits One or more of the KX122_INTERRUPT_T values. Combine with bitwise OR (|)
@throws std::runtime_error on failure.
*/
void routeInterrupt2(uint8_t bits);
/**
Gets the status of the interrupts. (Has an interrupt occured)
See datasheet for more details.
@param data Pointer to a uint8_t variable to store the value.
@throws std::runtime_error on failure.
*/
void getInterruptStatus(uint8_t *data);
/**
Gets the source of the interrupt.
See datasheet for more details.
@param data Pointer to a uint8_t variable to store the value.
@throws std::runtime_error on failure.
*/
void getInterruptSource(uint8_t *data);
/**
Clears latching interrupts (Wakeup, Data Ready).
See datasheet for more details.
@throws std::runtime_error on failure.
*/
void clearInterrupt();
/**
Enables the data ready interrupt. Availability of new acceleration data is
reflected as an interrupt.
Sensor needs to be in standby mode when enabling the interrupt.
@throws std::runtime_error on failure.
*/
void enableDataReadyInterrupt();
/**
Disables the data ready interrupt.
Sensor needs to be in standby mode when disabling the interrupt.
@throws std::runtime_error on failure.
*/
void disableDataReadyInterrupt();
/**
Enables the buffer full interrupt.
Buffer can hold 681 sets of values (8 bit, low resolution mode) or
340 sets of values (16 bit, high resolution mode).
Sensor needs to be in standby mode when enabling the interrupt.
@throws std::runtime_error on failure.
*/
void enableBufferFullInterrupt();
/**
Disables the buffer full interrupt.
Sensor needs to be in standby mode when disabling the interrupt.
@throws std::runtime_error on failure.
*/
void disableBufferFullInterrupt();
/**
Enables the buffer.
Sensor needs to be in standby mode when enabling the buffer.
@throws std::runtime_error on failure.
*/
void enableBuffer();
/**
Disables the buffer.
Sensor needs to be in standby mode when disabling the buffer.
@throws std::runtime_error on failure.
*/
void disableBuffer();
/**
Initializes the buffer with the given sample watermark level, buffer resolution and buffer operating mode.
Buffer is enabled after the initialization.
Sensor is automatically set into standby mode during the buffer initialization.
Sensor is set to active mode after initialization.
See the other buffer functions for details about the different parameter values.
@param samples Amount of samples to trigger the watermark interrupt.
@param res One of the KX122_RES_T values.
@param mode One of the KX122_BUFFER_MODE_T values.
@throws std::runtime_error on failure.
*/
void bufferInit(uint samples, KX122_RES_T res, KX122_BUFFER_MODE_T mode);
/**
Sets the buffer resolution.
Buffer resolution is indepedent of the sensor resolution.
Sensor needs to be in standby mode when setting the buffer resolution.
@throws std::runtime_error on failure.
*/
void setBufferResolution(KX122_RES_T res);
/**
Sets the buffer watermark interrupt threshold.
When the buffer sample count reaches the watermark, watermark interrupt will be given.
In low resolution mode, maxiumum number of samples is 681. In high resolution, the maximum
number is 340.
See datasheet for more details.
Sensor needs to be in standby mode when setting the buffer threshold.
@param samples Amount of samples to trigger the watermark interrupt.
@throws std::runtime_error on failure.
*/
void setBufferThreshold(uint samples);
/**
Sets the buffer operating mode.
The buffer can operate in FIFO,FILO or Stream mode.
The buffer gathers data, reports data and interracts with the status indicators
in a slightly different way depending on the operating mode.
See datasheet for more details.
Sensor needs to be in standby mode when setting the buffer mode.
@param mode One of the KX122_BUFFER_MODE_T values.
@throws std::runtime_error on failure.
*/
void setBufferMode(KX122_BUFFER_MODE_T mode);
/**
Gets the current amount of samples in the buffer.
@param samples Pointer to an uint variable to store the data.
@throws std::runtime_error on failure.
*/
void getBufferStatus(uint *samples);
/**
Gets the specified amount of raw acceleration samples from the buffer.
Make sure the array size is atleast the amount of samples to be read.
@param len The amount of samples to read from the buffer.
@param x_array Pointer to an floating point array to store the x-axis data. Can be set to NULL if not wanted.
@param y_array Pointer to an floating point array to store the y-axis data. Can be set to NULL if not wanted.
@param z_array Pointer to an floating point array to store the z-axis data. Can be set to NULL if not wanted.
@throws std::runtime_error on failure.
*/
void getRawBufferSamples(uint len, float *x_array, float *y_array, float *z_array);
/**
Gets the specified amount of converted (m/s^2) acceleration samples from the buffer.
Make sure the array size is atleast the amount of samples to be read.
@param len The amount of samples to read from the buffer.
@param x_array Pointer to an floating point array to store the x-axis data. Can be set to NULL if not wanted.
@param y_array Pointer to an floating point array to store the y-axis data. Can be set to NULL if not wanted.
@param z_array Pointer to an floating point array to store the z-axis data. Can be set to NULL if not wanted.
@throws std::runtime_error on failure.
*/
void getBufferSamples(uint len, float *x_array, float *y_array, float *z_array);
/**
Clears the buffer, removing all existing samples from the buffer.
@throws std::runtime_error on failure.
*/
void clearBuffer();
private:
//Device context
kx122_context m_kx122;
};
}

47
src/kx122/kx122.json Normal file
View File

@ -0,0 +1,47 @@
{
"Library": "KX122",
"Description": "Kionix KX122 accelerometer sensor library",
"Sensor Class": {
"KX122": {
"Name": "Kionix KX122 tri-axis accelerometer sensor",
"Description": "This is the UPM Module for the Kionix KX122 accelerometer sensor.
The Kionix KX122 sensor is a multifunctional sensor that provides a multitude if different functionality
in addition to the basic accelerometer functionality. The sensor has 2 interrupt pins,
that can be used to detect various interrupts. The Sensor has an additional sample buffer that can be configured.",
"Categories": ["acceleration"],
"Connections": ["i2c,spi"],
"Project Type": ["prototyping", "commercial"],
"Manufacturers": ["Kionix"],
"Examples": {
"C++":["kx122.cxx"],
"C": ["kx122.c"]
},
"Specifications": {
"Supply Voltage (VDD)": {
"unit": "V",
"min": 1.71,
"max": 3.6
},
"I/O Pads Supply Voltage (IO_VDD)": {
"unit": "V",
"min": 1.7,
"max": 3.6
},
"Supply Current": {
"unit": "uA",
"min" : 0.9,
"max" : 146
},
"Operating Temperature": {
"unit": "°C",
"min": -40,
"max": 85
}
},
"Urls": {
"Product Pages": ["http://www.kionix.com/product/KX122-1037"],
"Datasheets": ["http://kionixfs.kionix.com/en/datasheet/KX122-1037%20Specifications%20Rev%205.0.pdf"]
}
}
}
}

539
src/kx122/kx122_registers.h Normal file
View File

@ -0,0 +1,539 @@
/*
The MIT License (MIT)
Copyright (c) 2017 Kionix Inc.
Permission is hereby granted, free of charge, to any person obtaining a
copy of this software and associated documentation files (the
"Software"), to deal in the Software without restriction, including
without limitation the rights to use, copy, modify, merge, publish,
distribute, sublicense, and/or sell copies of the Software, and to
permit persons to whom the Software is furnished to do so, subject to
the following conditions:
The above copyright notice and this permission notice shall be included
in all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.
IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY
CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT,
TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE
SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*/
#ifndef __KX122_REGISTERS_H__
#define __KX122_REGISTERS_H__
/* registers */
// x- hp filter output
#define KX122_XHP_L 0x00
#define KX122_XHP_H 0x01
// y- hp filter output
#define KX122_YHP_L 0x02
#define KX122_YHP_H 0x03
// z- hpfilteroutput
#define KX122_ZHP_L 0x04
#define KX122_ZHP_H 0x05
// output register x
#define KX122_XOUT_L 0x06
#define KX122_XOUT_H 0x07
// output register y
#define KX122_YOUT_L 0x08
#define KX122_YOUT_H 0x09
// output register z
#define KX122_ZOUT_L 0x0A
#define KX122_ZOUT_H 0x0B
// communication selftest
#define KX122_COTR 0x0C
// WHO_AM_I
#define KX122_WHO_AM_I 0x0F
// current sixfacet posititions
#define KX122_TSCP 0x10
// previous six facet positions
#define KX122_TSPP 0x11
// This register indicates the triggering axis when a tap/double tap interrupt occurs.
#define KX122_INS1 0x12
// This register tells witch function caused an interrupt.
#define KX122_INS2 0x13
// This register reports the axis and direction of detected motion.
#define KX122_INS3 0x14
// This register reports the status of the interrupt.
#define KX122_STATUS_REG 0x15
#define KX122_INT_REL 0x17
// Read/write control register that controls the main feature set.
#define KX122_CNTL1 0x18
// 2' control register
#define KX122_CNTL2 0x19
// 3' controlregister
#define KX122_CNTL3 0x1A
// This register is responsible for configuring ODR (output data rate) and filter settings
#define KX122_ODCNTL 0x1B
// This register controls the settings for the physical interrupt pin INT1
#define KX122_INC1 0x1C
// This register controls which axis and direction of detected motion can cause an interrupt.
#define KX122_INC2 0x1D
// This register controls which axis and direction of tap/double tap can cause an interrup
#define KX122_INC3 0x1E
// This register controls routing of an interrupt reporting to physical interrupt pin INT1
#define KX122_INC4 0x1F
// This register controls the settings for the physical interrupt pin INT2.
#define KX122_INC5 0x20
// This register controls routing of interrupt reporting to physical interrupt pin INT2
#define KX122_INC6 0x21
#define KX122_TILT_TIMER 0x22
#define KX122_WUFC 0x23
// This register is responsible for enableing/disabling reporting of Tap/Double Tap.
#define KX122_TDTRC 0x24
#define KX122_TDTC 0x25
#define KX122_TTH 0x26
#define KX122_TTL 0x27
#define KX122_FTD 0x28
#define KX122_STD 0x29
#define KX122_TLT 0x2A
#define KX122_TWS 0x2B
#define KX122_FFTH 0x2C
#define KX122_FFC 0x2D
// Free Fall Control: This register contains the counter setting of the Free fall detection.
#define KX122_FFCNTL 0x2E
#define KX122_ATH 0x30
#define KX122_TILT_ANGLE_LL 0x32
#define KX122_TILT_ANGLE_HL 0x33
// This register sets the Hysteresis that is placed in between the Screen Rotation states
#define KX122_HYST_SET 0x34
// Low Power Control sets the number of samples of accelerometer output to be average
#define KX122_LP_CNTL 0x35
// Read/write control register that controls the buffer sample threshold
#define KX122_BUF_CNTL1 0x3A
// Read/write control register that controls sample buffer operation
#define KX122_BUF_CNTL2 0x3B
// This register reports the status of the sample buffer
#define KX122_BUF_STATUS_1 0x3C
// This register reports the status of the sample buffer trigger function
#define KX122_BUF_STATUS_2 0x3D
#define KX122_BUF_CLEAR 0x3E
#define KX122_BUF_READ 0x3F
// When 0xCA is written to this register, the MEMS self-test function is enabled. Electrostatic-actuation of the accelerometer, results in a DC shift of the X, Y and Z axis outputs. Writing 0x00 to this register will return the accelerometer to normal operation
#define KX122_SELF_TEST 0x60
// WHO_AM_I
#define KX112_WHO_AM_I 0x0F
// WHO_AM_I
#define KX123_WHO_AM_I 0x0F
// WHO_AM_I
#define KX124_WHO_AM_I 0x0F
/* registers bits */
// before set
#define KX122_COTR_DCSTR_BEFORE (0x55 << 0)
// after set
#define KX122_COTR_DCSTR_AFTER (0xAA << 0)
// WHO_AM_I -value for KX122
#define KX122_WHO_AM_I_WIA_ID (0x1B << 0)
// x-left
#define KX122_TSCP_LE (0x01 << 5)
// x+right
#define KX122_TSCP_RI (0x01 << 4)
// y-down
#define KX122_TSCP_DO (0x01 << 3)
// y+up
#define KX122_TSCP_UP (0x01 << 2)
// z-facedown
#define KX122_TSCP_FD (0x01 << 1)
// z+faceup
#define KX122_TSCP_FU (0x01 << 0)
// x-left
#define KX122_TSPP_LE (0x01 << 5)
// x+right
#define KX122_TSPP_RI (0x01 << 4)
// y-down
#define KX122_TSPP_DO (0x01 << 3)
// y+up
#define KX122_TSPP_UP (0x01 << 2)
// z-facedown
#define KX122_TSPP_FD (0x01 << 1)
// z+faceup
#define KX122_TSPP_FU (0x01 << 0)
// x-
#define KX122_INS1_TLE (0x01 << 5)
// x+
#define KX122_INS1_TRI (0x01 << 4)
// y-
#define KX122_INS1_TDO (0x01 << 3)
// y+
#define KX122_INS1_TUP (0x01 << 2)
// z-
#define KX122_INS1_TFD (0x01 << 1)
// z+
#define KX122_INS1_TFU (0x01 << 0)
// Free fall. This bit is cleared when the interrupt latch release register (INL) is read..
#define KX122_INS2_FFS (0x01 << 7)
// indicates buffer full interrupt. Automatically cleared when buffer is read.
#define KX122_INS2_BFI (0x01 << 6)
// Watermark interrupt, bit is set to one when FIFO has filled up to the value stored in the sample bits.This bit is automatically cleared when FIFO/FILO is read and the content returns to a value below the value stored in the sample bits.
#define KX122_INS2_WMI (0x01 << 5)
// indicates that new acceleration data (0x06h to 0x0Bh) is available. This bit is cleared when acceleration data is read or the interrupt release register INT_REL is read.
#define KX122_INS2_DRDY (0x01 << 4)
// no tap
#define KX122_INS2_TDTS_NOTAP (0x00 << 2)
// single tap event
#define KX122_INS2_TDTS_SINGLE (0x01 << 2)
// double tap event
#define KX122_INS2_TDTS_DOUBLE (0x02 << 2)
// do not exist
#define KX122_INS2_TDTS_NA (0x03 << 2)
// Status of Wake up. This bit is cleared when the interrupt release register INT_REL is read.
#define KX122_INS2_WUFS (0x01 << 1)
// Tilt Position status. This bit is cleared when the interrupt release register INT_REL is read.
#define KX122_INS2_TPS (0x01 << 0)
// x-
#define KX122_INS3_XNWU (0x01 << 5)
// x+
#define KX122_INS3_XPWU (0x01 << 4)
// y-
#define KX122_INS3_YNWU (0x01 << 3)
// y+
#define KX122_INS3_YPWU (0x01 << 2)
// z-
#define KX122_INS3_ZNWU (0x01 << 1)
// z+
#define KX122_INS3_ZPWU (0x01 << 0)
// INT reports the combined (OR) interrupt information of all features.
#define KX122_STATUS_REG_INT (0x01 << 4)
// controls the operating mode of the KX122.
#define KX122_CNTL1_PC1 (0x01 << 7)
// determines the performance mode of the KX122. The noise varies with ODR, RES and different LP_CNTL settings possibly reducing the effective resolution.
#define KX122_CNTL1_RES (0x01 << 6)
// enables the reporting of the availability of new acceleration data as an interrupt
#define KX122_CNTL1_DRDYE (0x01 << 5)
// 2g range
#define KX122_CNTL1_GSEL_2G (0x00 << 3)
// 4g range
#define KX122_CNTL1_GSEL_4G (0x01 << 3)
// 8g range
#define KX122_CNTL1_GSEL_8G (0x02 << 3)
// not valid settings
#define KX122_CNTL1_GSEL_NA (0x03 << 3)
// enables the Directional Tap function that will detect single and double tap events.
#define KX122_CNTL1_TDTE (0x01 << 2)
// enables the Wake Up (motion detect) function
#define KX122_CNTL1_WUFE (0x01 << 1)
// enables the Tilt Position function that will detect changes in device orientation.
#define KX122_CNTL1_TPE (0x01 << 0)
// initiates software reset, which performs the RAM reboot routine
#define KX122_CNTL2_SRST (0x01 << 7)
// command test control
#define KX122_CNTL2_COTC (0x01 << 6)
// x-
#define KX122_CNTL2_LEM (0x01 << 5)
// x+
#define KX122_CNTL2_RIM (0x01 << 4)
// y-
#define KX122_CNTL2_DOM (0x01 << 3)
// y+
#define KX122_CNTL2_UPM (0x01 << 2)
// z-
#define KX122_CNTL2_FDM (0x01 << 1)
// z+
#define KX122_CNTL2_FUM (0x01 << 0)
// 1.5Hz
#define KX122_CNTL3_OTP_1P563 (0x00 << 6)
// 6.25Hz
#define KX122_CNTL3_OTP_6P25 (0x01 << 6)
// 12.5Hz
#define KX122_CNTL3_OTP_12P5 (0x02 << 6)
// 50Hz
#define KX122_CNTL3_OTP_50 (0x03 << 6)
// 50Hz
#define KX122_CNTL3_OTDT_50 (0x00 << 3)
// 100Hz
#define KX122_CNTL3_OTDT_100 (0x01 << 3)
// 200Hz
#define KX122_CNTL3_OTDT_200 (0x02 << 3)
// 400Hz
#define KX122_CNTL3_OTDT_400 (0x03 << 3)
// 12.5Hz
#define KX122_CNTL3_OTDT_12P5 (0x04 << 3)
// 25Hz
#define KX122_CNTL3_OTDT_25 (0x05 << 3)
// 800Hz
#define KX122_CNTL3_OTDT_800 (0x06 << 3)
// 1600Hz
#define KX122_CNTL3_OTDT_1600 (0x07 << 3)
// 0.78Hz
#define KX122_CNTL3_OWUF_0P781 (0x00 << 0)
// 1.563Hz
#define KX122_CNTL3_OWUF_1P563 (0x01 << 0)
// 3.125Hz
#define KX122_CNTL3_OWUF_3P125 (0x02 << 0)
// 6.25Hz
#define KX122_CNTL3_OWUF_6P25 (0x03 << 0)
// 12.5Hz
#define KX122_CNTL3_OWUF_12P5 (0x04 << 0)
// 25Hz
#define KX122_CNTL3_OWUF_25 (0x05 << 0)
// 50Hz
#define KX122_CNTL3_OWUF_50 (0x06 << 0)
// 100Hz
#define KX122_CNTL3_OWUF_100 (0x07 << 0)
// filtering applied
#define KX122_ODCNTL_IIR_BYPASS_APPLY (0x00 << 7)
// filter bypassed
#define KX122_ODCNTL_IIR_BYPASS_BYPASS (0x01 << 7)
// filter corner frequency set to ODR/9
#define KX122_ODCNTL_LPRO_ODR_9 (0x00 << 6)
// filter corner frequency set to ODR/2
#define KX122_ODCNTL_LPRO_ODR_2 (0x01 << 6)
// 12.5Hz
#define KX122_ODCNTL_OSA_12P5 (0x00 << 0)
// 25Hz
#define KX122_ODCNTL_OSA_25 (0x01 << 0)
// 50Hz
#define KX122_ODCNTL_OSA_50 (0x02 << 0)
// 100Hz
#define KX122_ODCNTL_OSA_100 (0x03 << 0)
// 200Hz
#define KX122_ODCNTL_OSA_200 (0x04 << 0)
// 400Hz
#define KX122_ODCNTL_OSA_400 (0x05 << 0)
// 800Hz
#define KX122_ODCNTL_OSA_800 (0x06 << 0)
// 1600Hz
#define KX122_ODCNTL_OSA_1600 (0x07 << 0)
// 0.78Hz
#define KX122_ODCNTL_OSA_0P781 (0x08 << 0)
// 1.563Hz
#define KX122_ODCNTL_OSA_1P563 (0x09 << 0)
// 3.125Hz
#define KX122_ODCNTL_OSA_3P125 (0x0A << 0)
// 6.25Hz
#define KX122_ODCNTL_OSA_6P25 (0x0B << 0)
// 3200Hz
#define KX122_ODCNTL_OSA_3200 (0x0C << 0)
// 6400Hz
#define KX122_ODCNTL_OSA_6400 (0x0D << 0)
// 12800Hz
#define KX122_ODCNTL_OSA_12800 (0x0E << 0)
// 25600Hz
#define KX122_ODCNTL_OSA_25600 (0x0F << 0)
// pulse 50us, 10us 1600ODR and over
#define KX122_INC1_PWSEL1_50US_10US (0x00 << 6)
// 1*OSA period
#define KX122_INC1_PWSEL1_1XOSA (0x01 << 6)
// 2*OSA period
#define KX122_INC1_PWSEL1_2XOSA (0x02 << 6)
// 4*OSA period
#define KX122_INC1_PWSEL1_4XOSA (0x03 << 6)
// enables/disables the physical interrupt
#define KX122_INC1_IEN1 (0x01 << 5)
// sets the polarity of the physical interrupt pin
#define KX122_INC1_IEA1 (0x01 << 4)
// sets the response of the physical interrupt pin
#define KX122_INC1_IEL1 (0x01 << 3)
// sets the polarity of Self Test
#define KX122_INC1_STPOL (0x01 << 1)
// sets the 3-wire SPI interface
#define KX122_INC1_SPI3E (0x01 << 0)
// OR combination between selected directions
#define KX122_INC2_AOI_OR (0x00 << 6)
// AND combination between selected axes
#define KX122_INC2_AOI_AND (0x01 << 6)
// x negative (x-): 0 = disabled, 1 = enabled
#define KX122_INC2_XNWUE (0x01 << 5)
// x positive (x+): 0 = disabled, 1 = enabled
#define KX122_INC2_XPWUE (0x01 << 4)
// y negative (y-): 0 = disabled, 1 = enabled
#define KX122_INC2_YNWUE (0x01 << 3)
// y positive (y+): 0 = disabled, 1 = enabled
#define KX122_INC2_YPWUE (0x01 << 2)
// z negative (z-): 0 = disabled, 1 = enabled
#define KX122_INC2_ZNWUE (0x01 << 1)
// z positive (z+): 0 = disabled, 1 = enabled
#define KX122_INC2_ZPWUE (0x01 << 0)
// x negative (x-): 0 = disabled, 1 = enabled
#define KX122_INC3_TLEM (0x01 << 5)
// x positive (x+): 0 = disabled, 1 = enabled
#define KX122_INC3_TRIM (0x01 << 4)
// y negative (y-): 0 = disabled, 1 = enabled
#define KX122_INC3_TDOM (0x01 << 3)
// y positive (y+): 0 = disabled, 1 = enabled
#define KX122_INC3_TUPM (0x01 << 2)
// z negative (z-): 0 = disabled, 1 = enabled
#define KX122_INC3_TFDM (0x01 << 1)
// z positive (z+): 0 = disabled, 1 = enabled
#define KX122_INC3_TFUM (0x01 << 0)
// Free fall interrupt reported on physical interrupt INT1
#define KX122_INC4_FFI1 (0x01 << 7)
// Buffer full interrupt reported on physical interrupt pin INT1
#define KX122_INC4_BFI1 (0x01 << 6)
// Watermark interrupt reported on physical interrupt pin INT1
#define KX122_INC4_WMI1 (0x01 << 5)
// Data ready interrupt reported on physical interrupt pin INT1
#define KX122_INC4_DRDYI1 (0x01 << 4)
// Tap/Double Tap interrupt reported on physical interrupt pin INT1
#define KX122_INC4_TDTI1 (0x01 << 2)
// Wake-Up (motion detect) interrupt reported on physical interrupt pin INT1
#define KX122_INC4_WUFI1 (0x01 << 1)
// Tilt position interrupt reported on physical interrupt pin INT1
#define KX122_INC4_TPI1 (0x01 << 0)
// pulse 50us, 10us 1600ODR and over
#define KX122_INC5_PWSEL2_50US_10US (0x00 << 6)
// 1*OSA period
#define KX122_INC5_PWSEL2_1XOSA (0x01 << 6)
// 2*OSA period
#define KX122_INC5_PWSEL2_2XOSA (0x02 << 6)
// 4*OSA period
#define KX122_INC5_PWSEL2_4XOSA (0x03 << 6)
// enables/disables the physical interrupt
#define KX122_INC5_IEN2 (0x01 << 5)
// sets the polarity of the physical interrupt pin
#define KX122_INC5_IEA2 (0x01 << 4)
// sets the response of the physical interrupt pin
#define KX122_INC5_IEL2 (0x01 << 3)
// Interrupt source automatic clear at interup 2 trailing edge
#define KX122_INC5_ACLR2 (0x01 << 1)
// Interrupt source automatic clear at interup 1 trailing edge
#define KX122_INC5_ACLR1 (0x01 << 0)
// FFI2 Free fall interrupt reported on physical interrupt INT2
#define KX122_INC6_FFI2 (0x01 << 7)
// BFI2 Buffer full interrupt reported on physical interrupt pin INT2
#define KX122_INC6_BFI2 (0x01 << 6)
// WMI2 - Watermark interrupt reported on physical interrupt pin INT2
#define KX122_INC6_WMI2 (0x01 << 5)
// DRDYI2 Data ready interrupt reported on physical interrupt pin INT2
#define KX122_INC6_DRDYI2 (0x01 << 4)
// TDTI2 - Tap/Double Tap interrupt reported on physical interrupt pin INT2
#define KX122_INC6_TDTI2 (0x01 << 2)
// WUFI2 Wake-Up (motion detect) interrupt reported on physical interrupt pin INT2
#define KX122_INC6_WUFI2 (0x01 << 1)
// TPI2 Tilt position interrupt reported on physical interrupt pin INT2
#define KX122_INC6_TPI2 (0x01 << 0)
// enables/disables the double tap interrupt
#define KX122_TDTRC_DTRE (0x01 << 1)
// enables/disables single tap interrupt
#define KX122_TDTRC_STRE (0x01 << 0)
// Free fall engine enable
#define KX122_FFCNTL_FFIE (0x01 << 7)
// Free fall interrupt latch/un-latch control
#define KX122_FFCNTL_ULMODE (0x01 << 6)
// Debounce methodology control
#define KX122_FFCNTL_DCRM (0x01 << 3)
// 12.5Hz
#define KX122_FFCNTL_OFFI_12P5 (0x00 << 0)
// 25Hz
#define KX122_FFCNTL_OFFI_25 (0x01 << 0)
// 50Hz
#define KX122_FFCNTL_OFFI_50 (0x02 << 0)
// 100Hz
#define KX122_FFCNTL_OFFI_100 (0x03 << 0)
// 200Hz
#define KX122_FFCNTL_OFFI_200 (0x04 << 0)
// 400Hz
#define KX122_FFCNTL_OFFI_400 (0x05 << 0)
// 800Hz
#define KX122_FFCNTL_OFFI_800 (0x06 << 0)
// 1600Hz
#define KX122_FFCNTL_OFFI_1600 (0x07 << 0)
// No Averaging
#define KX122_LP_CNTL_AVC_NO_AVG (0x00 << 4)
// 2 Samples Averaged
#define KX122_LP_CNTL_AVC_2_SAMPLE_AVG (0x01 << 4)
// 4 Samples Averaged
#define KX122_LP_CNTL_AVC_4_SAMPLE_AVG (0x02 << 4)
// 8 Samples Averaged
#define KX122_LP_CNTL_AVC_8_SAMPLE_AVG (0x03 << 4)
// 16 Samples Averaged (default)
#define KX122_LP_CNTL_AVC_16_SAMPLE_AVG (0x04 << 4)
// 32 Samples Averaged
#define KX122_LP_CNTL_AVC_32_SAMPLE_AVG (0x05 << 4)
// 64 Samples Averaged
#define KX122_LP_CNTL_AVC_64_SAMPLE_AVG (0x06 << 4)
// 128 Samples Averaged
#define KX122_LP_CNTL_AVC_128_SAMPLE_AVG (0x07 << 4)
#define KX122_BUF_CNTL1_SMP_TH0_7 (0xFF << 0)
// controls activation of the sample buffer
#define KX122_BUF_CNTL2_BUFE (0x01 << 7)
// determines the resolution of the acceleration data samples collected by the sample
#define KX122_BUF_CNTL2_BRES (0x01 << 6)
// buffer full interrupt enable bit
#define KX122_BUF_CNTL2_BFIE (0x01 << 5)
// watermark level bits 8 and 9
#define KX122_BUF_CNTL2_SMP_TH8_9 (0x0C << 2)
// The buffer collects 681 sets of 8-bit low resolution values or 339 sets of 16-bit high resolution values and then stops collecting data, collecting new data only when the buffer is not full
#define KX122_BUF_CNTL2_BUF_M_FIFO (0x00 << 0)
// The buffer holds the last 681 sets of 8-bit low resolution values or 339 sets of 16-bit high resolution values. Once the buffer is full, the oldest data is discarded to make room for newer data.
#define KX122_BUF_CNTL2_BUF_M_STREAM (0x01 << 0)
// When a trigger event occurs, the buffer holds the last data set of SMP[9:0] samples before the trigger event and then continues to collect data until full. New data is collected only when the buffer is not full.
#define KX122_BUF_CNTL2_BUF_M_TRIGGER (0x02 << 0)
// The buffer holds the last 681 sets of 8-bit low resolution values or 339 sets of 16-bit high resolution values. Once the buffer is full, the oldest data is discarded to make room for newer data. Reading from the buffer in this mode will return the most recent data first.
#define KX122_BUF_CNTL2_BUF_M_FILO (0x03 << 0)
#define KX122_BUF_STATUS_1_SMP_LEV0_7 (0xFF << 0)
// reports the status of the buffers trigger function if this mode has been selected
#define KX122_BUF_STATUS_2_BUF_TRIG (0x01 << 7)
// level High mask
#define KX122_BUF_STATUS_2_SMP_LEV8_10 (0x07 << 0)
// MEMS Test OFF
#define KX122_SELF_TEST_MEMS_TEST_OFF (0x00 << 0)
// MEMS Test ON
#define KX122_SELF_TEST_MEMS_TEST_ON (0xCA << 0)
// WHO_AM_I -value for KX112
#define KX112_WHO_AM_I_WIA_ID (0x22 << 0)
// WHO_AM_I -value for KX123
#define KX123_WHO_AM_I_WIA_ID (0x20 << 0)
// WHO_AM_I -value for KX124
#define KX124_WHO_AM_I_WIA_ID (0x28 << 0)
/*registers bit masks */
#define KX122_COTR_DCSTR_MASK 0xFF
#define KX122_WHO_AM_I_WIA_MASK 0xFF
// status of tap/double tap, bit is released when interrupt release register INT_REL is read.
#define KX122_INS2_TDTS_MASK 0x0C
// selects the acceleration range of the accelerometer outputs
#define KX122_CNTL1_GSEL_MASK 0x18
// sets the output data rate for the Tilt Position function
#define KX122_CNTL3_OTP_MASK 0xC0
// sets the output data rate for the Directional TapTM function
#define KX122_CNTL3_OTDT_MASK 0x38
// sets the output data rate for the general motion detection function and the high-pass filtered outputs
#define KX122_CNTL3_OWUF_MASK 0x07
// filter bypass mode
#define KX122_ODCNTL_IIR_BYPASS_MASK 0x80
// low-pass filter roll off control
#define KX122_ODCNTL_LPRO_MASK 0x40
// acceleration output data rate.
#define KX122_ODCNTL_OSA_MASK 0x0F
// Pulse interrupt 1 width configuration
#define KX122_INC1_PWSEL1_MASK 0xC0
// AND OR configuration for motion detection
#define KX122_INC2_AOI_MASK 0x40
#define KX122_INC2_WUE_MASK 0x3F
#define KX122_INC3_TM_MASK 0x3F
// Pulse interrupt 2 width configuration
#define KX122_INC5_PWSEL2_MASK 0xC0
// Output Data Rate at which the Free fall engine performs its function.
#define KX122_FFCNTL_OFFI_MASK 0x07
#define KX122_HYST_SET_HYST_MASK 0x3F
// Averaging Filter Control
#define KX122_LP_CNTL_AVC_MASK 0x70
#define KX122_BUF_CNTL1_SMP_TH0_MASK 0xFF
#define KX122_BUF_CNTL1_SMP_TH0_7_MASK 0xFF
#define KX122_BUF_CNTL2_SMP_TH8_MASK 0x0C
#define KX122_BUF_CNTL2_SMP_TH8_9_MASK 0x0C
// selects the operating mode of the sample buffer
#define KX122_BUF_CNTL2_BUF_M_MASK 0x03
#define KX122_BUF_STATUS_1_SMP_LEV0_MASK 0xFF
#define KX122_BUF_STATUS_1_SMP_LEV0_7_MASK 0xFF
#define KX122_BUF_STATUS_2_SMP_LEV8_MASK 0x07
#define KX122_BUF_STATUS_2_SMP_LEV8_10_MASK 0x07
#define KX122_SELF_TEST_MEMS_TEST_MASK 0xFF
#define KX112_WHO_AM_I_WIA_MASK 0xFF
#define KX123_WHO_AM_I_WIA_MASK 0xFF
#define KX124_WHO_AM_I_WIA_MASK 0xFF
#endif