diff --git a/README.md b/README.md
index 5a77161..7afe0c3 100644
--- a/README.md
+++ b/README.md
@@ -1,2 +1,30 @@
# LIS3DHH
Arduino library to support the LIS3DHH 3D accelerometer
+
+## API
+
+This sensor uses SPI to communicate.
+
+For SPI it is then required to create a SPI interface before accessing to the sensors:
+
+ dev_spi = new SPIClass(SPI_MOSI, SPI_MISO, SPI_SCK);
+ dev_spi->begin();
+
+An instance can be created and enabled when the SPI bus is used following the procedure below:
+
+ Accelero = new LIS3DHHSensor(dev_spi, CS_PIN);
+ Accelero->Enable_X();
+
+The access to the sensor values is done as explained below:
+
+ Read accelerometer.
+
+ Accelero->Get_X_Axes(&accelerometer);
+
+## Documentation
+
+You can find the source files at
+https://github.com/stm32duino/LIS3DHH
+
+The LIS3DHH datasheet is available at
+https://www.st.com/content/st_com/en/products/mems-and-sensors/accelerometers/lis3dhh.html
diff --git a/keywords.txt b/keywords.txt
new file mode 100644
index 0000000..b69eff2
--- /dev/null
+++ b/keywords.txt
@@ -0,0 +1,38 @@
+#######################################
+# Syntax Coloring Map For LIS3DHH
+#######################################
+
+#######################################
+# Datatypes (KEYWORD1)
+#######################################
+
+LIS3DHHSensor KEYWORD1
+
+#######################################
+# Methods and Functions (KEYWORD2)
+#######################################
+
+Enable_X KEYWORD2
+Disable_X KEYWORD2
+ReadID KEYWORD2
+Get_X_Axes KEYWORD2
+Get_X_Sensitivity KEYWORD2
+Get_X_AxesRaw KEYWORD2
+Get_X_ODR KEYWORD2
+Set_X_ODR KEYWORD2
+Get_X_FS KEYWORD2
+Set_X_FS KEYWORD2
+Enable_DRDY_Interrupt KEYWORD2
+Disable_DRDY_Interrupt KEYWORD2
+Set_Filter_Mode KEYWORD2
+Get_DRDY_Status KEYWORD2
+Get_FIFO_Num_Samples KEYWORD2
+Set_FIFO_Mode KEYWORD2
+ReadReg KEYWORD2
+WriteReg KEYWORD2
+
+#######################################
+# Constants (LITERAL1)
+#######################################
+
+LIS3DHH_ACC_SENSITIVITY LITERAL1
diff --git a/library.properties b/library.properties
new file mode 100644
index 0000000..887106f
--- /dev/null
+++ b/library.properties
@@ -0,0 +1,9 @@
+name=STM32duino LIS3DHH
+version=1.0.0
+author=SRA
+maintainer=stm32duino
+sentence=Ultra High Resolution 3D accelerometer.
+paragraph=This library provides Arduino support for the ultra high resolution 3D accelerometer LIS3DHH for STM32 boards.
+category=Sensors
+url=https://github.com/stm32duino/LIS3DHH
+architectures=stm32, avr, sam
diff --git a/src/LIS3DHHSensor.cpp b/src/LIS3DHHSensor.cpp
new file mode 100644
index 0000000..d3c23a3
--- /dev/null
+++ b/src/LIS3DHHSensor.cpp
@@ -0,0 +1,463 @@
+/**
+ ******************************************************************************
+ * @file LIS3DHHSensor.cpp
+ * @author CLab
+ * @version V1.0.0
+ * @date 25 July 2019
+ * @brief Implementation of an LIS3DHH Inertial Measurement Unit (IMU) 3 axes
+ * sensor.
+ ******************************************************************************
+ * @attention
+ *
+ *
© COPYRIGHT(c) 2019 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+ */
+
+
+/* Includes ------------------------------------------------------------------*/
+
+#include "LIS3DHHSensor.h"
+
+
+/* Class Implementation ------------------------------------------------------*/
+
+/** Constructor
+ * @param spi object of an helper class which handles the SPI peripheral
+ * @param cs_pin the chip select pin
+ * @param spi_speed the SPI speed
+ */
+LIS3DHHSensor::LIS3DHHSensor(SPIClass *spi, int cs_pin, uint32_t spi_speed) : dev_spi(spi), cs_pin(cs_pin), spi_speed(spi_speed)
+{
+ reg_ctx.write_reg = LIS3DHH_io_write;
+ reg_ctx.read_reg = LIS3DHH_io_read;
+ reg_ctx.handle = (void *)this;
+
+ // Configure CS pin
+ pinMode(cs_pin, OUTPUT);
+ digitalWrite(cs_pin, HIGH);
+
+ /* Enable register address automatically incremented during a multiple byte
+ access with a serial interface. */
+ if (lis3dhh_auto_add_inc_set(®_ctx, PROPERTY_ENABLE) != 0)
+ {
+ return;
+ }
+
+ /* Enable BDU */
+ if (lis3dhh_block_data_update_set(®_ctx, PROPERTY_ENABLE) != 0)
+ {
+ return;
+ }
+
+ /* FIFO mode selection */
+ if (lis3dhh_fifo_mode_set(®_ctx, LIS3DHH_BYPASS_MODE) != 0)
+ {
+ return;
+ }
+
+ /* Output data rate selection - power down. */
+ if (lis3dhh_data_rate_set(®_ctx, LIS3DHH_POWER_DOWN) != 0)
+ {
+ return;
+ }
+
+ X_isEnabled = 0;
+
+ return;
+}
+
+/**
+ * @brief Enable LIS3DHH Accelerator
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::Enable_X(void)
+{
+ /* Check if the component is already enabled */
+ if (X_isEnabled == 1)
+ {
+ return LIS3DHH_STATUS_OK;
+ }
+
+ /* Output data rate selection - power down. */
+ if (lis3dhh_data_rate_set(®_ctx, LIS3DHH_1kHz1) != 0)
+ {
+ return LIS3DHH_STATUS_ERROR;
+ }
+
+ X_isEnabled = 1;
+
+ return LIS3DHH_STATUS_OK;
+}
+
+/**
+ * @brief Disable LIS3DHH Accelerator
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::Disable_X(void)
+{
+ /* Check if the component is already disabled */
+ if (X_isEnabled == 0)
+ {
+ return LIS3DHH_STATUS_OK;
+ }
+
+ /* Output data rate selection - power down. */
+ if (lis3dhh_data_rate_set(®_ctx, LIS3DHH_POWER_DOWN) != 0)
+ {
+ return LIS3DHH_STATUS_ERROR;
+ }
+
+ X_isEnabled = 0;
+
+ return LIS3DHH_STATUS_OK;
+}
+
+/**
+ * @brief Read ID of LIS3DHH Accelerometer and Gyroscope
+ * @param id the pointer where the ID of the device is stored
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::ReadID(uint8_t *id)
+{
+ if(!id)
+ {
+ return LIS3DHH_STATUS_ERROR;
+ }
+
+ /* Read WHO AM I register */
+ if (lis3dhh_device_id_get(®_ctx, id) != 0)
+ {
+ return LIS3DHH_STATUS_ERROR;
+ }
+
+ return LIS3DHH_STATUS_OK;
+}
+
+/**
+ * @brief Read data from LIS3DHH Accelerometer
+ * @param acceleration the pointer where the accelerometer data are stored
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::Get_X_Axes(int32_t *acceleration)
+{
+ int16_t data_raw[3];
+ float sensitivity = 0;
+
+ /* Read raw data from LIS3DHH output register. */
+ if (Get_X_AxesRaw(data_raw) != LIS3DHH_STATUS_OK)
+ {
+ return LIS3DHH_STATUS_ERROR;
+ }
+
+ /* Get LIS3DHH actual sensitivity. */
+ if (Get_X_Sensitivity(&sensitivity) != LIS3DHH_STATUS_OK)
+ {
+ return LIS3DHH_STATUS_ERROR;
+ }
+
+ /* Calculate the data. */
+ acceleration[0] = (int32_t)(data_raw[0] * sensitivity);
+ acceleration[1] = (int32_t)(data_raw[1] * sensitivity);
+ acceleration[2] = (int32_t)(data_raw[2] * sensitivity);
+
+ return LIS3DHH_STATUS_OK;
+}
+
+/**
+ * @brief Read Accelerometer Sensitivity
+ * @param sensitivity the pointer where the accelerometer sensitivity is stored
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::Get_X_Sensitivity(float *sensitivity)
+{
+ /* There is only one value of sensitivity */
+ *sensitivity = LIS3DHH_ACC_SENSITIVITY;
+
+ return LIS3DHH_STATUS_OK;
+}
+
+/**
+ * @brief Read raw data from LIS3DHH Accelerometer
+ * @param value the pointer where the accelerometer raw data are stored
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::Get_X_AxesRaw(int16_t *value)
+{
+ axis3bit16_t data_raw;
+ LIS3DHHStatusTypeDef ret = LIS3DHH_STATUS_OK;
+
+ /* Read raw data values. */
+ if (lis3dhh_acceleration_raw_get(®_ctx, data_raw.u8bit) != 0)
+ {
+ return LIS3DHH_STATUS_ERROR;
+ }
+
+ value[0] = (data_raw.i16bit[0]);
+ value[1] = (data_raw.i16bit[1]);
+ value[2] = (data_raw.i16bit[2]);
+
+ return ret;
+}
+
+/**
+ * @brief Read LIS3DHH Accelerometer output data rate
+ * @param odr the pointer to the output data rate
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::Get_X_ODR(float* odr)
+{
+ /* There is only one value of ODR */
+ *odr = 1100.0f;
+
+ return LIS3DHH_STATUS_OK;
+}
+
+/**
+ * @brief Set LIS3DHH Accelerometer output data rate
+ * @param odr the output data rate to be set
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::Set_X_ODR(float odr)
+{
+ (void)(odr);
+ return LIS3DHH_STATUS_OK;
+}
+
+/**
+ * @brief Read LIS3DHH Accelerometer full scale
+ * @param full_scale the pointer to the full scale
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::Get_X_FS(float* full_scale)
+{
+ /* There is only one value of FS */
+ *full_scale = 2.5f;
+
+ return LIS3DHH_STATUS_OK;
+}
+
+/**
+ * @brief Set LIS3DHH Accelerometer full scale
+ * @param full_scale the full scale to be set
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::Set_X_FS(float full_scale)
+{
+ (void)(full_scale);
+ return LIS3DHH_STATUS_OK;
+}
+
+/**
+ * @brief Enable Data Ready Interrupt
+ * @param int_pin interrupt pin line to be used
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::Enable_DRDY_Interrupt(LIS3DHH_SensorIntPin_t int_pin)
+{
+ LIS3DHHStatusTypeDef ret = LIS3DHH_STATUS_OK;
+
+ /* Enable Data Ready Interrupt on either INT1 or INT2 pin */
+ switch (int_pin)
+ {
+ case LIS3DHH_INT1_PIN:
+ /* Interrupt set to INT1 */
+ if(lis3dhh_drdy_on_int1_set(®_ctx, PROPERTY_ENABLE) != 0)
+ {
+ return LIS3DHH_STATUS_ERROR;
+ }
+ break;
+ case LIS3DHH_INT2_PIN:
+ /* Interrupt set to INT2 */
+ if(lis3dhh_drdy_on_int2_set(®_ctx, PROPERTY_ENABLE) != 0)
+ {
+ return LIS3DHH_STATUS_ERROR;
+ }
+ break;
+ default:
+ ret = LIS3DHH_STATUS_ERROR;
+ break;
+ }
+
+ return ret;
+}
+
+/**
+ * @brief Disable Data Ready Interrupt
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::Disable_DRDY_Interrupt(void)
+{
+ if(lis3dhh_drdy_on_int1_set(®_ctx, PROPERTY_DISABLE) != 0)
+ {
+ return LIS3DHH_STATUS_ERROR;
+ }
+
+ if(lis3dhh_drdy_on_int2_set(®_ctx, PROPERTY_DISABLE) != 0)
+ {
+ return LIS3DHH_STATUS_ERROR;
+ }
+
+ return LIS3DHH_STATUS_OK;
+}
+
+/**
+ * @brief Set Filter Mode
+ * @param filter_mode filter mode to be set
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::Set_Filter_Mode(uint8_t filter_mode)
+{
+ if(lis3dhh_filter_config_set(®_ctx, (lis3dhh_dsp_t)filter_mode) != 0)
+ {
+ return LIS3DHH_STATUS_ERROR;
+ }
+
+ return LIS3DHH_STATUS_OK;
+}
+
+/**
+ * @brief Get Data Ready status
+ * @param status the Data Ready status
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::Get_DRDY_Status(uint8_t *status)
+{
+ if(lis3dhh_xl_data_ready_get(®_ctx, status) != 0)
+ {
+ return LIS3DHH_STATUS_ERROR;
+ }
+
+ return LIS3DHH_STATUS_OK;
+}
+
+
+/**
+ * @brief Get the number of samples contained into the FIFO
+ * @param num_samples the number of samples contained into the FIFO
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::Get_FIFO_Num_Samples(uint16_t *num_samples)
+{
+ lis3dhh_fifo_src_t fifo_samples;
+
+ if (lis3dhh_read_reg(®_ctx, LIS3DHH_FIFO_SRC, (uint8_t *)&fifo_samples, 1) != 0)
+ {
+ return LIS3DHH_STATUS_ERROR;
+ }
+
+ if(fifo_samples.fss == 0x20)
+ {
+ *num_samples = 32;
+ }
+ else
+ {
+ *num_samples = fifo_samples.fss;
+ }
+
+ return LIS3DHH_STATUS_OK;
+}
+
+/**
+ * @brief Set the FIFO mode
+ * @param mode FIFO mode
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::Set_FIFO_Mode(uint8_t mode)
+{
+ LIS3DHHStatusTypeDef ret = LIS3DHH_STATUS_OK;
+
+ /* Verify that the passed parameter contains one of the valid values. */
+ switch ((lis3dhh_fmode_t)mode)
+ {
+ case LIS3DHH_BYPASS_MODE:
+ case LIS3DHH_FIFO_MODE:
+ case LIS3DHH_STREAM_TO_FIFO_MODE:
+ case LIS3DHH_BYPASS_TO_STREAM_MODE:
+ case LIS3DHH_DYNAMIC_STREAM_MODE:
+ break;
+
+ default:
+ ret = LIS3DHH_STATUS_ERROR;
+ break;
+ }
+
+ if (ret == LIS3DHH_STATUS_ERROR)
+ {
+ return ret;
+ }
+
+ if (lis3dhh_fifo_mode_set(®_ctx, (lis3dhh_fmode_t)mode) != 0)
+ {
+ ret = LIS3DHH_STATUS_ERROR;
+ }
+
+ return ret;
+}
+
+/**
+ * @brief Read the data from register
+ * @param reg register address
+ * @param data register data
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::ReadReg(uint8_t reg, uint8_t *data)
+{
+
+ if (lis3dhh_read_reg(®_ctx, reg, data, 1) != 0)
+ {
+ return LIS3DHH_STATUS_ERROR;
+ }
+
+ return LIS3DHH_STATUS_OK;
+}
+
+/**
+ * @brief Write the data to register
+ * @param reg register address
+ * @param data register data
+ * @retval 0 in case of success, an error code otherwise
+ */
+LIS3DHHStatusTypeDef LIS3DHHSensor::WriteReg(uint8_t reg, uint8_t data)
+{
+
+ if (lis3dhh_write_reg(®_ctx, reg, &data, 1) != 0)
+ {
+ return LIS3DHH_STATUS_ERROR;
+ }
+
+ return LIS3DHH_STATUS_OK;
+}
+
+
+int32_t LIS3DHH_io_write(void *handle, uint8_t WriteAddr, uint8_t *pBuffer, uint16_t nBytesToWrite)
+{
+ return ((LIS3DHHSensor *)handle)->IO_Write(pBuffer, WriteAddr, nBytesToWrite);
+}
+
+int32_t LIS3DHH_io_read(void *handle, uint8_t ReadAddr, uint8_t *pBuffer, uint16_t nBytesToRead)
+{
+ return ((LIS3DHHSensor *)handle)->IO_Read(pBuffer, ReadAddr, nBytesToRead);
+}
diff --git a/src/LIS3DHHSensor.h b/src/LIS3DHHSensor.h
new file mode 100644
index 0000000..4f7c9fd
--- /dev/null
+++ b/src/LIS3DHHSensor.h
@@ -0,0 +1,174 @@
+/**
+ ******************************************************************************
+ * @file LIS3DHHSensor.h
+ * @author CLab
+ * @version V1.0.0
+ * @date 25 July 2019
+ * @brief Abstract Class of an LIS3DHH Inertial Measurement Unit (IMU) 3 axes
+ * sensor.
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT(c) 2019 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+ */
+
+
+/* Prevent recursive inclusion -----------------------------------------------*/
+
+#ifndef __LIS3DHHSensor_H__
+#define __LIS3DHHSensor_H__
+
+
+/* Includes ------------------------------------------------------------------*/
+
+#include "SPI.h"
+#include "lis3dhh_reg.h"
+
+/* Defines -------------------------------------------------------------------*/
+
+#define LIS3DHH_ACC_SENSITIVITY 0.076f /**< Sensitivity value for 2.5g full scale [mg/LSB] */
+
+/* Typedefs ------------------------------------------------------------------*/
+typedef enum
+{
+ LIS3DHH_STATUS_OK = 0,
+ LIS3DHH_STATUS_ERROR
+} LIS3DHHStatusTypeDef;
+
+typedef enum
+{
+ LIS3DHH_INT1_PIN,
+ LIS3DHH_INT2_PIN,
+} LIS3DHH_SensorIntPin_t;
+
+/* Class Declaration ---------------------------------------------------------*/
+
+/**
+ * Abstract class of an LIS3DHH Inertial Measurement Unit (IMU) 3 axes
+ * sensor.
+ */
+class LIS3DHHSensor
+{
+ public:
+ LIS3DHHSensor(SPIClass *spi, int cs_pin, uint32_t spi_speed=2000000);
+ LIS3DHHStatusTypeDef Enable_X(void);
+ LIS3DHHStatusTypeDef Disable_X(void);
+ LIS3DHHStatusTypeDef ReadID(uint8_t *id);
+ LIS3DHHStatusTypeDef Get_X_Axes(int32_t *acceleration);
+ LIS3DHHStatusTypeDef Get_X_Sensitivity(float *sensitivity);
+ LIS3DHHStatusTypeDef Get_X_AxesRaw(int16_t *value);
+ LIS3DHHStatusTypeDef Get_X_ODR(float *odr);
+ LIS3DHHStatusTypeDef Set_X_ODR(float odr);
+ LIS3DHHStatusTypeDef Get_X_FS(float *full_scale);
+ LIS3DHHStatusTypeDef Set_X_FS(float full_scale);
+ LIS3DHHStatusTypeDef Enable_DRDY_Interrupt(LIS3DHH_SensorIntPin_t int_pin);
+ LIS3DHHStatusTypeDef Disable_DRDY_Interrupt(void);
+ LIS3DHHStatusTypeDef Set_Filter_Mode(uint8_t filter_mode);
+ LIS3DHHStatusTypeDef Get_DRDY_Status(uint8_t *status);
+ LIS3DHHStatusTypeDef Get_FIFO_Num_Samples(uint16_t *num_samples);
+ LIS3DHHStatusTypeDef Set_FIFO_Mode(uint8_t mode);
+ LIS3DHHStatusTypeDef ReadReg(uint8_t reg, uint8_t *data);
+ LIS3DHHStatusTypeDef WriteReg(uint8_t reg, uint8_t data);
+
+ /**
+ * @brief Utility function to read data.
+ * @param pBuffer: pointer to data to be read.
+ * @param RegisterAddr: specifies internal address register to be read.
+ * @param NumByteToRead: number of bytes to be read.
+ * @retval 0 if ok, an error code otherwise.
+ */
+ uint8_t IO_Read(uint8_t* pBuffer, uint8_t RegisterAddr, uint16_t NumByteToRead)
+ {
+ dev_spi->beginTransaction(SPISettings(spi_speed, MSBFIRST, SPI_MODE3));
+
+ digitalWrite(cs_pin, LOW);
+
+ /* Write Reg Address */
+ dev_spi->transfer(RegisterAddr | 0x80);
+ /* Read the data */
+ for (uint16_t i=0; itransfer(0x00);
+ }
+
+ digitalWrite(cs_pin, HIGH);
+
+ dev_spi->endTransaction();
+
+ return 0;
+ }
+
+ /**
+ * @brief Utility function to write data.
+ * @param pBuffer: pointer to data to be written.
+ * @param RegisterAddr: specifies internal address register to be written.
+ * @param NumByteToWrite: number of bytes to write.
+ * @retval 0 if ok, an error code otherwise.
+ */
+ uint8_t IO_Write(uint8_t* pBuffer, uint8_t RegisterAddr, uint16_t NumByteToWrite)
+ {
+ dev_spi->beginTransaction(SPISettings(spi_speed, MSBFIRST, SPI_MODE3));
+
+ digitalWrite(cs_pin, LOW);
+
+ /* Write Reg Address */
+ dev_spi->transfer(RegisterAddr);
+ /* Write the data */
+ for (uint16_t i=0; itransfer(pBuffer[i]);
+ }
+
+ digitalWrite(cs_pin, HIGH);
+
+ dev_spi->endTransaction();
+
+ return 0;
+ }
+
+ private:
+
+ /* Helper classes. */
+ SPIClass *dev_spi;
+
+ /* Configuration */
+ int cs_pin;
+ uint32_t spi_speed;
+
+ uint8_t X_isEnabled;
+
+ lis3dhh_ctx_t reg_ctx;
+};
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+int32_t LIS3DHH_io_write( void *handle, uint8_t WriteAddr, uint8_t *pBuffer, uint16_t nBytesToWrite );
+int32_t LIS3DHH_io_read( void *handle, uint8_t ReadAddr, uint8_t *pBuffer, uint16_t nBytesToRead );
+#ifdef __cplusplus
+ }
+#endif
+
+#endif
diff --git a/src/lis3dhh_reg.c b/src/lis3dhh_reg.c
new file mode 100644
index 0000000..d277a4d
--- /dev/null
+++ b/src/lis3dhh_reg.c
@@ -0,0 +1,1455 @@
+/*
+ ******************************************************************************
+ * @file lis3dhh_reg.c
+ * @author Sensor Solutions Software Team
+ * @brief LIS3DHH driver file
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT(c) 2019 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its
+ * contributors may be used to endorse or promote products derived from
+ * this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ */
+
+#include "lis3dhh_reg.h"
+
+/**
+ * @defgroup LIS3DHH
+ * @brief This file provides a set of functions needed to drive the
+ * lis3dhh enhanced inertial module.
+ * @{
+ *
+ */
+
+/**
+ * @defgroup LIS3DHH_Interfaces_Functions
+ * @brief This section provide a set of functions used to read and
+ * write a generic register of the device.
+ * MANDATORY: return 0 -> no Error.
+ * @{
+ *
+ */
+
+/**
+ * @brief Read generic device register
+ *
+ * @param ctx read / write interface definitions(ptr)
+ * @param reg register to read
+ * @param data pointer to buffer that store the data read(ptr)
+ * @param len number of consecutive register to read
+ * @retval interface status (MANDATORY: return 0 -> no Error)
+ *
+ */
+int32_t lis3dhh_read_reg(lis3dhh_ctx_t* ctx, uint8_t reg, uint8_t* data,
+ uint16_t len)
+{
+ int32_t ret;
+ ret = ctx->read_reg(ctx->handle, reg, data, len);
+ return ret;
+}
+
+/**
+ * @brief Write generic device register
+ *
+ * @param ctx read / write interface definitions(ptr)
+ * @param reg register to write
+ * @param data pointer to data to write in register reg(ptr)
+ * @param len number of consecutive register to write
+ * @retval interface status (MANDATORY: return 0 -> no Error)
+ *
+ */
+int32_t lis3dhh_write_reg(lis3dhh_ctx_t* ctx, uint8_t reg, uint8_t* data,
+ uint16_t len)
+{
+ int32_t ret;
+ ret = ctx->write_reg(ctx->handle, reg, data, len);
+ return ret;
+}
+
+/**
+ * @}
+ *
+ */
+
+ /**
+ * @defgroup LIS3DHH_Sensitivity
+ * @brief These functions convert raw-data into engineering units.
+ * @{
+ *
+ */
+
+float lis3dhh_from_lsb_to_mg(int16_t lsb)
+{
+ return ((float)lsb *0.076f);
+}
+
+float lis3dhh_from_lsb_to_celsius(int16_t lsb)
+{
+ return (((float)lsb / 16.0f) + 25.0f);
+}
+
+/**
+ * @}
+ *
+ */
+
+/**
+ * @defgroup LIS3DHH_Data_generation
+ * @brief This section groups all the functions concerning data
+ * generation
+ * @{
+ *
+ */
+
+/**
+ * @brief Blockdataupdate.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of bdu in reg CTRL_REG1.
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_block_data_update_set(lis3dhh_ctx_t *ctx, uint8_t val)
+{
+ lis3dhh_ctrl_reg1_t ctrl_reg1;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+ if(ret == 0){
+ ctrl_reg1.bdu = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief Blockdataupdate.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of bdu in reg CTRL_REG1.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_block_data_update_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_ctrl_reg1_t ctrl_reg1;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+ *val = ctrl_reg1.bdu;
+
+ return ret;
+}
+
+/**
+ * @brief Output data rate selection.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of norm_mod_en in reg CTRL_REG1
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_data_rate_set(lis3dhh_ctx_t *ctx, lis3dhh_norm_mod_en_t val)
+{
+ lis3dhh_ctrl_reg1_t ctrl_reg1;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+ if(ret == 0){
+ ctrl_reg1.norm_mod_en = (uint8_t)val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief Output data rate selection.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of norm_mod_en in reg CTRL_REG1.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_data_rate_get(lis3dhh_ctx_t *ctx, lis3dhh_norm_mod_en_t *val)
+{
+ lis3dhh_ctrl_reg1_t ctrl_reg1;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+
+ switch (ctrl_reg1.norm_mod_en){
+ case LIS3DHH_POWER_DOWN:
+ *val = LIS3DHH_POWER_DOWN;
+ break;
+ case LIS3DHH_1kHz1:
+ *val = LIS3DHH_1kHz1;
+ break;
+ default:
+ *val = LIS3DHH_POWER_DOWN;
+ break;
+ }
+
+ return ret;
+}
+
+/**
+ * @brief Temperature output value.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param buff Buffer that stores data read
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_temperature_raw_get(lis3dhh_ctx_t *ctx, uint8_t *buff)
+{
+ int32_t ret;
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_OUT_TEMP_L, buff, 2);
+ return ret;
+}
+
+/**
+ * @brief acceleration output value.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param buff Buffer that stores data read
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_acceleration_raw_get(lis3dhh_ctx_t *ctx, uint8_t *buff)
+{
+ int32_t ret;
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_OUT_X_L_XL, buff, 6);
+ return ret;
+}
+
+/**
+ * @brief Acceleration set of data available.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of zyxda in reg STATUS.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_xl_data_ready_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_status_t status;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_STATUS, (uint8_t*)&status, 1);
+ *val = status.zyxda;
+
+ return ret;
+}
+
+/**
+ * @brief Acceleration set of data overrun.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of zyxor in reg STATUS.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_xl_data_ovr_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_status_t status;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_STATUS, (uint8_t*)&status, 1);
+ *val = status.zyxor;
+
+ return ret;
+}
+
+/**
+ * @}
+ *
+ */
+
+/**
+ * @defgroup LIS3DHH_common
+ * @brief This section group common useful functions
+ * @{
+ *
+ */
+
+/**
+ * @brief DeviceWhoamI.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param buff Buffer that stores data read
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_device_id_get(lis3dhh_ctx_t *ctx, uint8_t *buff)
+{
+ int32_t ret;
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_WHO_AM_I, buff, 1);
+ return ret;
+}
+
+/**
+ * @brief Software reset. Restore the default values in user registers.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of sw_reset in reg CTRL_REG1.
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_reset_set(lis3dhh_ctx_t *ctx, uint8_t val)
+{
+ lis3dhh_ctrl_reg1_t ctrl_reg1;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+ if(ret == 0){
+ ctrl_reg1.sw_reset = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief Software reset. Restore the default values in user registers.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of sw_reset in reg CTRL_REG1.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_reset_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_ctrl_reg1_t ctrl_reg1;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+ *val = ctrl_reg1.sw_reset;
+
+ return ret;
+}
+
+/**
+ * @brief Reboot memory content. Reload the calibration parameters.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of boot in reg CTRL_REG1
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_boot_set(lis3dhh_ctx_t *ctx, uint8_t val)
+{
+ lis3dhh_ctrl_reg1_t ctrl_reg1;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+ if(ret == 0){
+ ctrl_reg1.boot = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief Reboot memory content. Reload the calibration parameters.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of boot in reg CTRL_REG1.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_boot_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_ctrl_reg1_t ctrl_reg1;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+ *val = ctrl_reg1.boot;
+
+ return ret;
+}
+
+/**
+ * @brief Selftest.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of st in reg CTRL_REG4
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_self_test_set(lis3dhh_ctx_t *ctx, lis3dhh_st_t val)
+{
+ lis3dhh_ctrl_reg4_t ctrl_reg4;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG4, (uint8_t*)&ctrl_reg4, 1);
+ if(ret == 0){
+ ctrl_reg4.st = (uint8_t)val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_CTRL_REG4, (uint8_t*)&ctrl_reg4, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief Selftest.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of st in reg CTRL_REG4.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_self_test_get(lis3dhh_ctx_t *ctx, lis3dhh_st_t *val)
+{
+ lis3dhh_ctrl_reg4_t ctrl_reg4;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG4, (uint8_t*)&ctrl_reg4, 1);
+
+ switch (ctrl_reg4.st){
+ case LIS3DHH_ST_DISABLE:
+ *val = LIS3DHH_ST_DISABLE;
+ break;
+ case LIS3DHH_ST_POSITIVE:
+ *val = LIS3DHH_ST_POSITIVE;
+ break;
+ case LIS3DHH_ST_NEGATIVE:
+ *val = LIS3DHH_ST_NEGATIVE;
+ break;
+ default:
+ *val = LIS3DHH_ST_DISABLE;
+ break;
+ }
+
+ return ret;
+}
+
+/**
+ * @brief Digital filtering Phase/bandwidth selection.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of dsp in reg CTRL_REG4
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_filter_config_set(lis3dhh_ctx_t *ctx, lis3dhh_dsp_t val)
+{
+ lis3dhh_ctrl_reg4_t ctrl_reg4;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG4, (uint8_t*)&ctrl_reg4, 1);
+ if(ret == 0){
+ ctrl_reg4.dsp = (uint8_t)val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_CTRL_REG4, (uint8_t*)&ctrl_reg4, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief Digital filtering Phase/bandwidth selection.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of dsp in reg CTRL_REG4.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_filter_config_get(lis3dhh_ctx_t *ctx, lis3dhh_dsp_t *val)
+{
+ lis3dhh_ctrl_reg4_t ctrl_reg4;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG4, (uint8_t*)&ctrl_reg4, 1);
+
+ switch (ctrl_reg4.dsp){
+ case LIS3DHH_LINEAR_PHASE_440Hz:
+ *val = LIS3DHH_LINEAR_PHASE_440Hz;
+ break;
+ case LIS3DHH_LINEAR_PHASE_235Hz:
+ *val = LIS3DHH_LINEAR_PHASE_235Hz;
+ break;
+ case LIS3DHH_NO_LINEAR_PHASE_440Hz:
+ *val = LIS3DHH_NO_LINEAR_PHASE_440Hz;
+ break;
+ case LIS3DHH_NO_LINEAR_PHASE_235Hz:
+ *val = LIS3DHH_NO_LINEAR_PHASE_235Hz;
+ break;
+ default:
+ *val = LIS3DHH_LINEAR_PHASE_440Hz;
+ break;
+ }
+
+ return ret;
+}
+
+/**
+ * @brief Statusregister.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get registers STATUS.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_status_get(lis3dhh_ctx_t *ctx, lis3dhh_status_t *val)
+{
+ int32_t ret;
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_STATUS, (uint8_t*) val, 1);
+ return ret;
+}
+
+/**
+ * @}
+ *
+ */
+
+/**
+ * @defgroup LIS3DHH_interrupts
+ * @brief This section group all the functions that manage interrupts
+ * @{
+ *
+ */
+
+/**
+ * @brief DRDY latched / pulsed, pulse duration is 1/4 ODR.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of drdy_pulse in reg CTRL_REG1
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_drdy_notification_mode_set(lis3dhh_ctx_t *ctx,
+ lis3dhh_drdy_pulse_t val)
+{
+ lis3dhh_ctrl_reg1_t ctrl_reg1;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+ if(ret == 0){
+ ctrl_reg1.drdy_pulse = (uint8_t)val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief DRDY latched / pulsed, pulse duration is 1/4 ODR.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of drdy_pulse in reg CTRL_REG1.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_drdy_notification_mode_get(lis3dhh_ctx_t *ctx,
+ lis3dhh_drdy_pulse_t *val)
+{
+ lis3dhh_ctrl_reg1_t ctrl_reg1;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+
+ switch (ctrl_reg1.drdy_pulse){
+ case LIS3DHH_LATCHED:
+ *val = LIS3DHH_LATCHED;
+ break;
+ case LIS3DHH_PULSED:
+ *val = LIS3DHH_PULSED;
+ break;
+ default:
+ *val = LIS3DHH_LATCHED;
+ break;
+ }
+
+ return ret;
+}
+
+/**
+ * @brief It configures the INT1 pad as output for FIFO flags or as
+ * external asynchronous input trigger to FIFO.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of int1_ext in reg INT1_CTRL
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_int1_mode_set(lis3dhh_ctx_t *ctx, lis3dhh_int1_ext_t val)
+{
+ lis3dhh_int1_ctrl_t int1_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ if(ret == 0){
+ int1_ctrl.int1_ext = (uint8_t)val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief It configures the INT1 pad as output for FIFO flags or as
+ * external asynchronous input trigger to FIFO.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of int1_ext in reg INT1_CTRL.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_int1_mode_get(lis3dhh_ctx_t *ctx, lis3dhh_int1_ext_t *val)
+{
+ lis3dhh_int1_ctrl_t int1_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+
+ switch (int1_ctrl.int1_ext){
+ case LIS3DHH_PIN_AS_INTERRUPT:
+ *val = LIS3DHH_PIN_AS_INTERRUPT;
+ break;
+ case LIS3DHH_PIN_AS_TRIGGER:
+ *val = LIS3DHH_PIN_AS_TRIGGER;
+ break;
+ default:
+ *val = LIS3DHH_PIN_AS_INTERRUPT;
+ break;
+ }
+
+ return ret;
+}
+
+/**
+ * @brief FIFO watermark status on INT1 pin.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of int1_fth in reg INT1_CTRL
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_threshold_on_int1_set(lis3dhh_ctx_t *ctx,
+ uint8_t val)
+{
+ lis3dhh_int1_ctrl_t int1_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ if(ret == 0){
+ int1_ctrl.int1_fth = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief FIFO watermark status on INT1 pin.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of int1_fth in reg INT1_CTRL.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_threshold_on_int1_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_int1_ctrl_t int1_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ *val = int1_ctrl.int1_fth;
+
+ return ret;
+}
+
+/**
+ * @brief FIFO full flag on INT1 pin.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of int1_fss5 in reg INT1_CTRL
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_full_on_int1_set(lis3dhh_ctx_t *ctx, uint8_t val)
+{
+ lis3dhh_int1_ctrl_t int1_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ if(ret == 0){
+ int1_ctrl.int1_fss5 = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief FIFO full flag on INT1 pin.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of int1_fss5 in reg INT1_CTRL.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_full_on_int1_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_int1_ctrl_t int1_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ *val = int1_ctrl.int1_fss5;
+
+ return ret;
+}
+
+/**
+ * @brief FIFO overrun interrupt on INT1 pin.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of int1_ovr in reg INT1_CTRL
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_ovr_on_int1_set(lis3dhh_ctx_t *ctx, uint8_t val)
+{
+ lis3dhh_int1_ctrl_t int1_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ if(ret == 0){
+ int1_ctrl.int1_ovr = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief FIFO overrun interrupt on INT1 pin.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of int1_ovr in reg INT1_CTRL.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_ovr_on_int1_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_int1_ctrl_t int1_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ *val = int1_ctrl.int1_ovr;
+
+ return ret;
+}
+
+/**
+ * @brief BOOT status on INT1 pin.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of int1_boot in reg INT1_CTRL
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_boot_on_int1_set(lis3dhh_ctx_t *ctx, uint8_t val)
+{
+ lis3dhh_int1_ctrl_t int1_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ if(ret == 0){
+ int1_ctrl.int1_boot = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief BOOT status on INT1 pin.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of int1_boot in reg INT1_CTRL.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_boot_on_int1_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_int1_ctrl_t int1_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ *val = int1_ctrl.int1_boot;
+
+ return ret;
+}
+
+/**
+ * @brief Data-ready signal on INT1 pin.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of int1_drdy in reg INT1_CTRL
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_drdy_on_int1_set(lis3dhh_ctx_t *ctx, uint8_t val)
+{
+ lis3dhh_int1_ctrl_t int1_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ if(ret == 0){
+ int1_ctrl.int1_drdy = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief Data-ready signal on INT1 pin.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of int1_drdy in reg INT1_CTRL.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_drdy_on_int1_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_int1_ctrl_t int1_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT1_CTRL, (uint8_t*)&int1_ctrl, 1);
+ *val = int1_ctrl.int1_drdy;
+
+ return ret;
+}
+
+/**
+ * @brief FIFO watermark status on INT2 pin.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of int2_fth in reg INT2_CTRL
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_threshold_on_int2_set(lis3dhh_ctx_t *ctx, uint8_t val)
+{
+ lis3dhh_int2_ctrl_t int2_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT2_CTRL, (uint8_t*)&int2_ctrl, 1);
+ if(ret == 0){
+ int2_ctrl.int2_fth = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_INT2_CTRL, (uint8_t*)&int2_ctrl, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief FIFO watermark status on INT2 pin.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of int2_fth in reg INT2_CTRL.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_threshold_on_int2_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_int2_ctrl_t int2_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT2_CTRL, (uint8_t*)&int2_ctrl, 1);
+ *val = int2_ctrl.int2_fth;
+
+ return ret;
+}
+
+/**
+ * @brief FIFO full flag on INT2 pin.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of int2_fss5 in reg INT2_CTRL
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_full_on_int2_set(lis3dhh_ctx_t *ctx, uint8_t val)
+{
+ lis3dhh_int2_ctrl_t int2_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT2_CTRL, (uint8_t*)&int2_ctrl, 1);
+ if(ret == 0){
+ int2_ctrl.int2_fss5 = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_INT2_CTRL, (uint8_t*)&int2_ctrl, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief FIFO full flag on INT2 pin.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of int2_fss5 in reg INT2_CTRL.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_full_on_int2_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_int2_ctrl_t int2_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT2_CTRL, (uint8_t*)&int2_ctrl, 1);
+ *val = int2_ctrl.int2_fss5;
+
+ return ret;
+}
+
+/**
+ * @brief FIFO overrun interrupt on INT2 pin.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of int2_ovr in reg INT2_CTRL
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_ovr_on_int2_set(lis3dhh_ctx_t *ctx, uint8_t val)
+{
+ lis3dhh_int2_ctrl_t int2_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT2_CTRL, (uint8_t*)&int2_ctrl, 1);
+ if(ret == 0){
+ int2_ctrl.int2_ovr = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_INT2_CTRL, (uint8_t*)&int2_ctrl, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief FIFO overrun interrupt on INT2 pin.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of int2_ovr in reg INT2_CTRL.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_ovr_on_int2_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_int2_ctrl_t int2_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT2_CTRL, (uint8_t*)&int2_ctrl, 1);
+ *val = int2_ctrl.int2_ovr;
+
+ return ret;
+}
+
+/**
+ * @brief BOOT status on INT2 pin.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of int2_boot in reg INT2_CTRL
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_boot_on_int2_set(lis3dhh_ctx_t *ctx, uint8_t val)
+{
+ lis3dhh_int2_ctrl_t int2_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT2_CTRL, (uint8_t*)&int2_ctrl, 1);
+ if(ret == 0){
+ int2_ctrl.int2_boot = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_INT2_CTRL, (uint8_t*)&int2_ctrl, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief BOOT status on INT2 pin.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of int2_boot in reg INT2_CTRL.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_boot_on_int2_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_int2_ctrl_t int2_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT2_CTRL, (uint8_t*)&int2_ctrl, 1);
+ *val = int2_ctrl.int2_boot;
+
+ return ret;
+}
+
+/**
+ * @brief Data-ready signal on INT2 pin.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of int2_drdy in reg INT2_CTRL
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_drdy_on_int2_set(lis3dhh_ctx_t *ctx, uint8_t val)
+{
+ lis3dhh_int2_ctrl_t int2_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT2_CTRL, (uint8_t*)&int2_ctrl, 1);
+ if(ret == 0){
+ int2_ctrl.int2_drdy = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_INT2_CTRL, (uint8_t*)&int2_ctrl, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief Data-ready signal on INT2 pin.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of int2_drdy in reg INT2_CTRL.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_drdy_on_int2_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_int2_ctrl_t int2_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_INT2_CTRL, (uint8_t*)&int2_ctrl, 1);
+ *val = int2_ctrl.int2_drdy;
+
+ return ret;
+}
+
+/**
+ * @brief Push-pull/open drain selection on interrupt pads.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of pp_od in reg CTRL_REG4
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_pin_mode_set(lis3dhh_ctx_t *ctx, lis3dhh_pp_od_t val)
+{
+ lis3dhh_ctrl_reg4_t ctrl_reg4;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG4, (uint8_t*)&ctrl_reg4, 1);
+ if(ret == 0){
+ ctrl_reg4.pp_od = (uint8_t)val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_CTRL_REG4, (uint8_t*)&ctrl_reg4, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief Push-pull/open drain selection on interrupt pads.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of pp_od in reg CTRL_REG4.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_pin_mode_get(lis3dhh_ctx_t *ctx, lis3dhh_pp_od_t *val)
+{
+ lis3dhh_ctrl_reg4_t ctrl_reg4;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG4, (uint8_t*)&ctrl_reg4, 1);
+
+ switch (ctrl_reg4.pp_od){
+ case LIS3DHH_ALL_PUSH_PULL:
+ *val = LIS3DHH_ALL_PUSH_PULL;
+ break;
+ case LIS3DHH_INT1_OD_INT2_PP:
+ *val = LIS3DHH_INT1_OD_INT2_PP;
+ break;
+ case LIS3DHH_INT1_PP_INT2_OD:
+ *val = LIS3DHH_INT1_PP_INT2_OD;
+ break;
+ case LIS3DHH_ALL_OPEN_DRAIN:
+ *val = LIS3DHH_ALL_OPEN_DRAIN;
+ break;
+ default:
+ *val = LIS3DHH_ALL_PUSH_PULL;
+ break;
+ }
+
+ return ret;
+}
+
+/**
+ * @}
+ *
+ */
+
+/**
+ * @defgroup LIS3DHH_fifo
+ * @brief This section group all the functions concerning the
+ * fifo usage
+ * @{
+ *
+ */
+
+/**
+ * @brief FIFOenable.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of fifo_en in reg CTRL_REG4
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_set(lis3dhh_ctx_t *ctx, uint8_t val)
+{
+ lis3dhh_ctrl_reg4_t ctrl_reg4;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG4, (uint8_t*)&ctrl_reg4, 1);
+ if(ret == 0){
+ ctrl_reg4.fifo_en = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_CTRL_REG4, (uint8_t*)&ctrl_reg4, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief FIFOenable.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of fifo_en in reg CTRL_REG4.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_ctrl_reg4_t ctrl_reg4;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG4, (uint8_t*)&ctrl_reg4, 1);
+ *val = ctrl_reg4.fifo_en;
+
+ return ret;
+}
+
+/**
+ * @brief Enables the SPI high speed configuration for the FIFO block that
+ is used to guarantee a minimum duration of the window in which
+ writing operation of RAM output is blocked. This bit is recommended
+ for SPI clock frequencies higher than 6 MHz.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of fifo_spi_hs_on in reg CTRL_REG5
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_block_spi_hs_set(lis3dhh_ctx_t *ctx, uint8_t val)
+{
+ lis3dhh_ctrl_reg5_t ctrl_reg5;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG5, (uint8_t*)&ctrl_reg5, 1);
+ if(ret == 0){
+ ctrl_reg5.fifo_spi_hs_on = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_CTRL_REG5, (uint8_t*)&ctrl_reg5, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief Enables the SPI high speed configuration for the FIFO block that
+ is used to guarantee a minimum duration of the window in which
+ writing operation of RAM output is blocked. This bit is recommended
+ for SPI clock frequencies higher than 6 MHz.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of fifo_spi_hs_on in reg CTRL_REG5.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_block_spi_hs_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_ctrl_reg5_t ctrl_reg5;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG5, (uint8_t*)&ctrl_reg5, 1);
+ *val = ctrl_reg5.fifo_spi_hs_on;
+
+ return ret;
+}
+
+/**
+ * @brief FIFO watermark level selection.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of fth in reg FIFO_CTRL
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_watermark_set(lis3dhh_ctx_t *ctx, uint8_t val)
+{
+ lis3dhh_fifo_ctrl_t fifo_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_FIFO_CTRL, (uint8_t*)&fifo_ctrl, 1);
+ if(ret == 0){
+ fifo_ctrl.fth = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_FIFO_CTRL, (uint8_t*)&fifo_ctrl, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief FIFO watermark level selection.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of fth in reg FIFO_CTRL.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_watermark_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_fifo_ctrl_t fifo_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_FIFO_CTRL, (uint8_t*)&fifo_ctrl, 1);
+ *val = fifo_ctrl.fth;
+
+ return ret;
+}
+
+/**
+ * @brief FIFO mode selection.[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of fmode in reg FIFO_CTRL
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_mode_set(lis3dhh_ctx_t *ctx, lis3dhh_fmode_t val)
+{
+ lis3dhh_fifo_ctrl_t fifo_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_FIFO_CTRL, (uint8_t*)&fifo_ctrl, 1);
+ if(ret == 0){
+ fifo_ctrl.fmode = (uint8_t)val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_FIFO_CTRL, (uint8_t*)&fifo_ctrl, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief FIFO mode selection.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of fmode in reg FIFO_CTRL.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_mode_get(lis3dhh_ctx_t *ctx, lis3dhh_fmode_t *val)
+{
+ lis3dhh_fifo_ctrl_t fifo_ctrl;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_FIFO_CTRL, (uint8_t*)&fifo_ctrl, 1);
+
+ switch (fifo_ctrl.fmode){
+ case LIS3DHH_BYPASS_MODE:
+ *val = LIS3DHH_BYPASS_MODE;
+ break;
+ case LIS3DHH_FIFO_MODE:
+ *val = LIS3DHH_FIFO_MODE;
+ break;
+ case LIS3DHH_STREAM_TO_FIFO_MODE:
+ *val = LIS3DHH_STREAM_TO_FIFO_MODE;
+ break;
+ case LIS3DHH_BYPASS_TO_STREAM_MODE:
+ *val = LIS3DHH_BYPASS_TO_STREAM_MODE;
+ break;
+ case LIS3DHH_DYNAMIC_STREAM_MODE:
+ *val = LIS3DHH_DYNAMIC_STREAM_MODE;
+ break;
+ default:
+ *val = LIS3DHH_BYPASS_MODE;
+ break;
+ }
+
+ return ret;
+}
+
+/**
+ * @brief FIFO status register.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get registers FIFO_SRC.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_status_get(lis3dhh_ctx_t *ctx, lis3dhh_fifo_src_t *val)
+{
+ int32_t ret;
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_FIFO_SRC, (uint8_t*) val, 1);
+ return ret;
+}
+
+/**
+ * @brief FIFO stored data level.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of fss in reg FIFO_SRC.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_full_flag_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_fifo_src_t fifo_src;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_FIFO_SRC, (uint8_t*)&fifo_src, 1);
+ *val = fifo_src.fss;
+
+ return ret;
+}
+
+/**
+ * @brief FIFO overrun status flag.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of ovrn in reg FIFO_SRC.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_ovr_flag_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_fifo_src_t fifo_src;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_FIFO_SRC, (uint8_t*)&fifo_src, 1);
+ *val = fifo_src.ovrn;
+
+ return ret;
+}
+
+/**
+ * @brief FIFO watermark status.[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of fth in reg FIFO_SRC.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_fifo_fth_flag_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_fifo_src_t fifo_src;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_FIFO_SRC, (uint8_t*)&fifo_src, 1);
+ *val = fifo_src.fth;
+
+ return ret;
+}
+
+/**
+ * @}
+ *
+ */
+
+/**
+ * @defgroup LIS3DHH_serial_interface
+ * @brief This section group all the functions concerning serial
+ * interface management
+ * @{
+ *
+ */
+
+/**
+ * @brief Register address automatically incremented during a multiple byte
+ * access with a serial interface (I2C or SPI).[set]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Change the values of if_add_inc in reg CTRL_REG1
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_auto_add_inc_set(lis3dhh_ctx_t *ctx, uint8_t val)
+{
+ lis3dhh_ctrl_reg1_t ctrl_reg1;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+ if(ret == 0){
+ ctrl_reg1.if_add_inc = val;
+ ret = lis3dhh_write_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+ }
+
+ return ret;
+}
+
+/**
+ * @brief Register address automatically incremented during a multiple byte
+ * access with a serial interface (I2C or SPI).[get]
+ *
+ * @param ctx Read / write interface definitions.(ptr)
+ * @param val Get the values of if_add_inc in reg CTRL_REG1.(ptr)
+ * @retval Interface status (MANDATORY: return 0 -> no Error).
+ *
+ */
+int32_t lis3dhh_auto_add_inc_get(lis3dhh_ctx_t *ctx, uint8_t *val)
+{
+ lis3dhh_ctrl_reg1_t ctrl_reg1;
+ int32_t ret;
+
+ ret = lis3dhh_read_reg(ctx, LIS3DHH_CTRL_REG1, (uint8_t*)&ctrl_reg1, 1);
+ *val = ctrl_reg1.if_add_inc;
+
+ return ret;
+}
+
+/**
+ * @}
+ *
+ */
+
+/**
+ * @}
+ *
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
\ No newline at end of file
diff --git a/src/lis3dhh_reg.h b/src/lis3dhh_reg.h
new file mode 100644
index 0000000..56115b0
--- /dev/null
+++ b/src/lis3dhh_reg.h
@@ -0,0 +1,419 @@
+/*
+ ******************************************************************************
+ * @file li3dhh_reg.h
+ * @author Sensors Software Solution Team
+ * @brief This file contains all the functions prototypes for the
+ * li3dhh_reg.c driver.
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT(c) 2019 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its
+ * contributors may be used to endorse or promote products derived from
+ * this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef LIS3DHH_REGS_H
+#define LIS3DHH_REGS_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include
+#include
+
+/** @addtogroup LIS3DHH
+ * @{
+ *
+ */
+
+/** @defgroup LIS3DHH_sensors_common_types
+ * @{
+ *
+ */
+
+#ifndef MEMS_SHARED_TYPES
+#define MEMS_SHARED_TYPES
+
+/**
+ * @defgroup axisXbitXX_t
+ * @brief These unions are useful to represent different sensors data type.
+ * These unions are not need by the driver.
+ *
+ * REMOVING the unions you are compliant with:
+ * MISRA-C 2012 [Rule 19.2] -> " Union are not allowed "
+ *
+ * @{
+ *
+ */
+
+typedef union{
+ int16_t i16bit[3];
+ uint8_t u8bit[6];
+} axis3bit16_t;
+
+typedef union{
+ int16_t i16bit;
+ uint8_t u8bit[2];
+} axis1bit16_t;
+
+typedef union{
+ int32_t i32bit[3];
+ uint8_t u8bit[12];
+} axis3bit32_t;
+
+typedef union{
+ int32_t i32bit;
+ uint8_t u8bit[4];
+} axis1bit32_t;
+
+/**
+ * @}
+ *
+ */
+
+typedef struct{
+ uint8_t bit0 : 1;
+ uint8_t bit1 : 1;
+ uint8_t bit2 : 1;
+ uint8_t bit3 : 1;
+ uint8_t bit4 : 1;
+ uint8_t bit5 : 1;
+ uint8_t bit6 : 1;
+ uint8_t bit7 : 1;
+} bitwise_t;
+
+#define PROPERTY_DISABLE (0U)
+#define PROPERTY_ENABLE (1U)
+
+#endif /* MEMS_SHARED_TYPES */
+
+/**
+ * @}
+ *
+ */
+
+/** @addtogroup LIS3DHH_Interfaces_Functions
+ * @brief This section provide a set of functions used to read and
+ * write a generic register of the device.
+ * MANDATORY: return 0 -> no Error.
+ * @{
+ *
+ */
+
+typedef int32_t (*lis3dhh_write_ptr)(void *, uint8_t, uint8_t*, uint16_t);
+typedef int32_t (*lis3dhh_read_ptr) (void *, uint8_t, uint8_t*, uint16_t);
+
+typedef struct {
+ /** Component mandatory fields **/
+ lis3dhh_write_ptr write_reg;
+ lis3dhh_read_ptr read_reg;
+ /** Customizable optional pointer **/
+ void *handle;
+} lis3dhh_ctx_t;
+
+/**
+ * @}
+ *
+ */
+
+/** @defgroup LIS3DHH_Infos
+ * @{
+ *
+ */
+
+/** Device Identification (Who am I) **/
+#define LIS3DHH_ID 0x11U
+
+/**
+ * @}
+ *
+ */
+
+#define LIS3DHH_WHO_AM_I 0x0FU
+#define LIS3DHH_CTRL_REG1 0x20U
+typedef struct {
+ uint8_t bdu : 1;
+ uint8_t drdy_pulse : 1;
+ uint8_t sw_reset : 1;
+ uint8_t boot : 1;
+ uint8_t not_used_01 : 2;
+ uint8_t if_add_inc : 1;
+ uint8_t norm_mod_en : 1;
+} lis3dhh_ctrl_reg1_t;
+
+#define LIS3DHH_INT1_CTRL 0x21U
+typedef struct {
+ uint8_t not_used_01 : 2;
+ uint8_t int1_ext : 1;
+ uint8_t int1_fth : 1;
+ uint8_t int1_fss5 : 1;
+ uint8_t int1_ovr : 1;
+ uint8_t int1_boot : 1;
+ uint8_t int1_drdy : 1;
+} lis3dhh_int1_ctrl_t;
+
+#define LIS3DHH_INT2_CTRL 0x22U
+typedef struct {
+ uint8_t not_used_01 : 3;
+ uint8_t int2_fth : 1;
+ uint8_t int2_fss5 : 1;
+ uint8_t int2_ovr : 1;
+ uint8_t int2_boot : 1;
+ uint8_t int2_drdy : 1;
+} lis3dhh_int2_ctrl_t;
+
+#define LIS3DHH_CTRL_REG4 0x23U
+typedef struct {
+ uint8_t not_used_01 : 1;
+ uint8_t fifo_en : 1;
+ uint8_t pp_od : 2;
+ uint8_t st : 2;
+ uint8_t dsp : 2;
+} lis3dhh_ctrl_reg4_t;
+
+#define LIS3DHH_CTRL_REG5 0x24U
+typedef struct {
+ uint8_t fifo_spi_hs_on : 1;
+ uint8_t not_used_01 : 7;
+} lis3dhh_ctrl_reg5_t;
+
+#define LIS3DHH_OUT_TEMP_L 0x25U
+#define LIS3DHH_OUT_TEMP_H 0x26U
+#define LIS3DHH_STATUS 0x27U
+typedef struct {
+ uint8_t xda : 1;
+ uint8_t yda : 1;
+ uint8_t zda : 1;
+ uint8_t zyxda : 1;
+ uint8_t _xor : 1;
+ uint8_t yor : 1;
+ uint8_t zor : 1;
+ uint8_t zyxor : 1;
+} lis3dhh_status_t;
+
+#define LIS3DHH_OUT_X_L_XL 0x28U
+#define LIS3DHH_OUT_X_H_XL 0x29U
+#define LIS3DHH_OUT_Y_L_XL 0x2AU
+#define LIS3DHH_OUT_Y_H_XL 0x2BU
+#define LIS3DHH_OUT_Z_L_XL 0x2CU
+#define LIS3DHH_OUT_Z_H_XL 0x2DU
+#define LIS3DHH_FIFO_CTRL 0x2EU
+typedef struct {
+ uint8_t fth : 5;
+ uint8_t fmode : 3;
+} lis3dhh_fifo_ctrl_t;
+
+#define LIS3DHH_FIFO_SRC 0x2FU
+typedef struct {
+ uint8_t fss : 6;
+ uint8_t ovrn : 1;
+ uint8_t fth : 1;
+} lis3dhh_fifo_src_t;
+
+/**
+ * @defgroup LIS3DHH_Register_Union
+ * @brief This union group all the registers that has a bit-field
+ * description.
+ * This union is useful but not need by the driver.
+ *
+ * REMOVING this union you are compliant with:
+ * MISRA-C 2012 [Rule 19.2] -> " Union are not allowed "
+ *
+ * @{
+ *
+ */
+typedef union{
+ lis3dhh_ctrl_reg1_t ctrl_reg1;
+ lis3dhh_int1_ctrl_t int1_ctrl;
+ lis3dhh_int2_ctrl_t int2_ctrl;
+ lis3dhh_ctrl_reg4_t ctrl_reg4;
+ lis3dhh_ctrl_reg5_t ctrl_reg5;
+ lis3dhh_status_t status;
+ lis3dhh_fifo_ctrl_t fifo_ctrl;
+ lis3dhh_fifo_src_t fifo_src;
+ bitwise_t bitwise;
+ uint8_t byte;
+} lis3dhh_reg_t;
+
+/**
+ * @}
+ *
+ */
+
+int32_t lis3dhh_read_reg(lis3dhh_ctx_t *ctx, uint8_t reg, uint8_t* data,
+ uint16_t len);
+int32_t lis3dhh_write_reg(lis3dhh_ctx_t *ctx, uint8_t reg, uint8_t* data,
+ uint16_t len);
+
+extern float lis3dhh_from_lsb_to_mg(int16_t lsb);
+extern float lis3dhh_from_lsb_to_celsius(int16_t lsb);
+
+int32_t lis3dhh_block_data_update_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_block_data_update_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+typedef enum {
+ LIS3DHH_POWER_DOWN = 0,
+ LIS3DHH_1kHz1 = 1,
+} lis3dhh_norm_mod_en_t;
+int32_t lis3dhh_data_rate_set(lis3dhh_ctx_t *ctx, lis3dhh_norm_mod_en_t val);
+int32_t lis3dhh_data_rate_get(lis3dhh_ctx_t *ctx, lis3dhh_norm_mod_en_t *val);
+
+int32_t lis3dhh_temperature_raw_get(lis3dhh_ctx_t *ctx, uint8_t *buff);
+int32_t lis3dhh_acceleration_raw_get(lis3dhh_ctx_t *ctx, uint8_t *buff);
+
+int32_t lis3dhh_xl_data_ready_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_xl_data_ovr_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_device_id_get(lis3dhh_ctx_t *ctx, uint8_t *buff);
+
+int32_t lis3dhh_reset_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_reset_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_boot_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_boot_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+typedef enum {
+ LIS3DHH_ST_DISABLE = 0,
+ LIS3DHH_ST_POSITIVE = 1,
+ LIS3DHH_ST_NEGATIVE = 2,
+} lis3dhh_st_t;
+int32_t lis3dhh_self_test_set(lis3dhh_ctx_t *ctx, lis3dhh_st_t val);
+int32_t lis3dhh_self_test_get(lis3dhh_ctx_t *ctx, lis3dhh_st_t *val);
+
+typedef enum {
+ LIS3DHH_LINEAR_PHASE_440Hz = 0,
+ LIS3DHH_LINEAR_PHASE_235Hz = 1,
+ LIS3DHH_NO_LINEAR_PHASE_440Hz = 2,
+ LIS3DHH_NO_LINEAR_PHASE_235Hz = 3,
+} lis3dhh_dsp_t;
+int32_t lis3dhh_filter_config_set(lis3dhh_ctx_t *ctx, lis3dhh_dsp_t val);
+int32_t lis3dhh_filter_config_get(lis3dhh_ctx_t *ctx, lis3dhh_dsp_t *val);
+
+int32_t lis3dhh_status_get(lis3dhh_ctx_t *ctx, lis3dhh_status_t *val);
+
+typedef enum {
+ LIS3DHH_LATCHED = 0,
+ LIS3DHH_PULSED = 1,
+} lis3dhh_drdy_pulse_t;
+int32_t lis3dhh_drdy_notification_mode_set(lis3dhh_ctx_t *ctx,
+ lis3dhh_drdy_pulse_t val);
+int32_t lis3dhh_drdy_notification_mode_get(lis3dhh_ctx_t *ctx,
+ lis3dhh_drdy_pulse_t *val);
+
+
+typedef enum {
+ LIS3DHH_PIN_AS_INTERRUPT = 0,
+ LIS3DHH_PIN_AS_TRIGGER = 1,
+} lis3dhh_int1_ext_t;
+int32_t lis3dhh_int1_mode_set(lis3dhh_ctx_t *ctx, lis3dhh_int1_ext_t val);
+int32_t lis3dhh_int1_mode_get(lis3dhh_ctx_t *ctx, lis3dhh_int1_ext_t *val);
+
+
+int32_t lis3dhh_fifo_threshold_on_int1_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_fifo_threshold_on_int1_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_fifo_full_on_int1_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_fifo_full_on_int1_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_fifo_ovr_on_int1_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_fifo_ovr_on_int1_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_boot_on_int1_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_boot_on_int1_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_drdy_on_int1_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_drdy_on_int1_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_fifo_threshold_on_int2_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_fifo_threshold_on_int2_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_fifo_full_on_int2_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_fifo_full_on_int2_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_fifo_ovr_on_int2_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_fifo_ovr_on_int2_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_boot_on_int2_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_boot_on_int2_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_drdy_on_int2_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_drdy_on_int2_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+typedef enum {
+ LIS3DHH_ALL_PUSH_PULL = 0,
+ LIS3DHH_INT1_OD_INT2_PP = 1,
+ LIS3DHH_INT1_PP_INT2_OD = 2,
+ LIS3DHH_ALL_OPEN_DRAIN = 3,
+} lis3dhh_pp_od_t;
+int32_t lis3dhh_pin_mode_set(lis3dhh_ctx_t *ctx, lis3dhh_pp_od_t val);
+int32_t lis3dhh_pin_mode_get(lis3dhh_ctx_t *ctx, lis3dhh_pp_od_t *val);
+
+int32_t lis3dhh_fifo_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_fifo_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_fifo_block_spi_hs_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_fifo_block_spi_hs_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_fifo_watermark_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_fifo_watermark_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+typedef enum {
+ LIS3DHH_BYPASS_MODE = 0,
+ LIS3DHH_FIFO_MODE = 1,
+ LIS3DHH_STREAM_TO_FIFO_MODE = 3,
+ LIS3DHH_BYPASS_TO_STREAM_MODE = 4,
+ LIS3DHH_DYNAMIC_STREAM_MODE = 6,
+} lis3dhh_fmode_t;
+int32_t lis3dhh_fifo_mode_set(lis3dhh_ctx_t *ctx, lis3dhh_fmode_t val);
+int32_t lis3dhh_fifo_mode_get(lis3dhh_ctx_t *ctx, lis3dhh_fmode_t *val);
+
+int32_t lis3dhh_fifo_status_get(lis3dhh_ctx_t *ctx, lis3dhh_fifo_src_t *val);
+
+int32_t lis3dhh_fifo_full_flag_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_fifo_ovr_flag_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_fifo_fth_flag_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+int32_t lis3dhh_auto_add_inc_set(lis3dhh_ctx_t *ctx, uint8_t val);
+int32_t lis3dhh_auto_add_inc_get(lis3dhh_ctx_t *ctx, uint8_t *val);
+
+/**
+ *@}
+ *
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* LIS3DHH_REGS_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/