diff --git a/README.md b/README.md index 282ac91..2121a23 100644 --- a/README.md +++ b/README.md @@ -53,6 +53,8 @@ The access to the sensor values is done as explained below: * LSM6DSV16X_Qvar_Polling: This application shows how to use LSM6DSV16X Qvar features in polling mode. +* LSM6DSV16X_Sensor_Fusion: This application shows how to use LSM6DSV16X Sensor Fusion features for reading quaternions. + * LSM6DSV16X_Single_Tap_Detection: This application shows how to detect the single tap event using the LSM6DSV16X accelerometer. * LSM6DSV16X_Tilt_Detection: This application shows how to detect the tilt event using the LSM6DSV16X accelerometer. diff --git a/examples/LSM6DSV16X_DataLog_Terminal/LSM6DSV16X_DataLog_Terminal.ino b/examples/LSM6DSV16X_DataLog_Terminal/LSM6DSV16X_DataLog_Terminal.ino index 11deeb7..52727ee 100644 --- a/examples/LSM6DSV16X_DataLog_Terminal/LSM6DSV16X_DataLog_Terminal.ino +++ b/examples/LSM6DSV16X_DataLog_Terminal/LSM6DSV16X_DataLog_Terminal.ino @@ -1,6 +1,6 @@ /* @file LSM6DSV16X_DataLog_Terminal.ino - @author Giuseppe Roberti + @author STMicroelectronics @brief Example to use the LSM6DSV16X inertial measurement sensor ******************************************************************************* Copyright (c) 2022, STMicroelectronics diff --git a/examples/LSM6DSV16X_Sensor_Fusion/LSM6DSV16X_Sensor_Fusion.ino b/examples/LSM6DSV16X_Sensor_Fusion/LSM6DSV16X_Sensor_Fusion.ino new file mode 100644 index 0000000..6002c43 --- /dev/null +++ b/examples/LSM6DSV16X_Sensor_Fusion/LSM6DSV16X_Sensor_Fusion.ino @@ -0,0 +1,79 @@ +/* + @file LSM6DSV16X_Sensor_Fusion.ino + @author STMicroelectronics + @brief Example to use the LSM6DSV16X library with Sensor Fusion Low Power. + ******************************************************************************* + Copyright (c) 2022, STMicroelectronics + All rights reserved. + + This software component is licensed by ST under BSD 3-Clause license, + the "License"; You may not use this file except in compliance with the + License. You may obtain a copy of the License at: + opensource.org/licenses/BSD-3-Clause + + ******************************************************************************* +*/ +#include + +#define ALGO_FREQ 120U /* Algorithm frequency 120Hz */ +#define ALGO_PERIOD (1000U / ALGO_FREQ) /* Algorithm period [ms] */ +unsigned long startTime, elapsedTime; + +LSM6DSV16XSensor AccGyr(&Wire); +uint8_t status = 0; +uint8_t tag = 0; +float quaternions[4]={0}; + +void setup() { + + Serial.begin(115200); + while (!Serial) yield(); + + Wire.begin(); + // Initialize LSM6DSV16X. + AccGyr.begin(); + + // Enable Sensor Fusion + status |= AccGyr.Enable_Rotation_Vector(); + + if(status != LSM6DSV16X_OK) { + Serial.println("LSM6DSV16X Sensor failed to init/configure"); + while(1); + } + Serial.println("LSM6DSV16X SFLP Demo"); +} + +void loop() { + uint16_t fifo_samples; + // Get start time of loop cycle + startTime = millis(); + // Check the number of samples inside FIFO + if(AccGyr.FIFO_Get_Num_Samples(&fifo_samples) != LSM6DSV16X_OK){ + Serial.println("LSM6DSV16X Sensor failed to get number of samples inside FIFO"); + while(1); + } + + // Read the FIFO if there is one stored sample + if (fifo_samples > 0) { + for (int i = 0; i < fifo_samples; i++) { + AccGyr.FIFO_Get_Tag(&tag); + if(tag==0x13u){ + AccGyr.FIFO_Get_Rotation_Vector(&quaternions[0]); + + // Print Quaternion data + Serial.print("Quaternion: "); + Serial.print(quaternions[3], 4); + Serial.print(", "); + Serial.print(-quaternions[1], 4); + Serial.print(", "); + Serial.print(quaternions[0], 4); + Serial.print(", "); + Serial.println(quaternions[2], 4); + + // Compute the elapsed time within loop cycle and wait + elapsedTime = millis() - startTime; + delay(ALGO_PERIOD - elapsedTime); + } + } + } +} diff --git a/keywords.txt b/keywords.txt index 9036bbc..bf52b84 100644 --- a/keywords.txt +++ b/keywords.txt @@ -7,7 +7,7 @@ ####################################### LSM6DSV16XSensor KEYWORD1 -LSM6DSV16XStatusTypeDef KEYWORD1 +LSM6DSV16XStatusTypeDef KEYWORD1 LSM6DSV16X_Event_Status_t KEYWORD1 LSM6DSV16X_SensorIntPin_t KEYWORD1 LSM6DSV16X_ACC_Operating_Mode_t KEYWORD1 @@ -90,12 +90,22 @@ FIFO_Set_X_BDR KEYWORD2 FIFO_Get_G_Axes KEYWORD2 FIFO_Set_G_BDR KEYWORD2 QVAR_Enable KEYWORD2 +QVAR_Disable KEYWORD2 QVAR_GetStatus KEYWORD2 +QVAR_GetImpedance KEYWORD2 QVAR_SetImpedance KEYWORD2 QVAR_GetData KEYWORD2 Get_MLC_Status KEYWORD2 Get_MLC_Output KEYWORD2 - +Enable_Rotation_Vector KEYWORD2 +Disable_Rotation_Vector KEYWORD2 +Enable_Gravity_Vector() KEYWORD2 +Disable_Gravity_Vector KEYWORD2 +Enable_Gyroscope_Bias KEYWORD2 +Disable_Gyroscope_Bias KEYWORD2 +FIFO_Get_Rotation_Vector KEYWORD2 +FIFO_Get_Gravity_Vector KEYWORD2 +FIFO_Get_Gyroscope_Bias KEYWORD2 ####################################### # Constants (LITERAL1) ####################################### diff --git a/library.properties b/library.properties index 6459863..d464e70 100644 --- a/library.properties +++ b/library.properties @@ -1,5 +1,5 @@ name=STM32duino LSM6DSV16X -version=1.5.1 +version=1.6.0 author=SRA maintainer=stm32duino sentence=Ultra Low Power inertial measurement unit. diff --git a/src/LSM6DSV16XSensor.cpp b/src/LSM6DSV16XSensor.cpp index 5d47adb..94af8dc 100644 --- a/src/LSM6DSV16XSensor.cpp +++ b/src/LSM6DSV16XSensor.cpp @@ -1,7 +1,7 @@ /** ****************************************************************************** * @file LSM6DSV16XSensor.cpp - * @author SRA + * @author STMicroelectronics * @version V1.0.0 * @date July 2022 * @brief Implementation of a LSM6DSV16X inertial measurement sensor. @@ -42,10 +42,9 @@ /* Class Implementation ------------------------------------------------------*/ - /** Constructor * @param i2c object of an helper class which handles the I2C peripheral - * @param address the address of the component's instance + * @param address the address of the component"s instance */ LSM6DSV16XSensor::LSM6DSV16XSensor(TwoWire *i2c, uint8_t address) : dev_i2c(i2c), address(address) { @@ -101,10 +100,10 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::begin() } /* Select default output data rate. */ - acc_odr = LSM6DSV16X_XL_ODR_AT_120Hz; + acc_odr = LSM6DSV16X_ODR_AT_120Hz; /* Output data rate selection - power down. */ - if (lsm6dsv16x_xl_data_rate_set(®_ctx, LSM6DSV16X_XL_ODR_OFF) != LSM6DSV16X_OK) { + if (lsm6dsv16x_xl_data_rate_set(®_ctx, LSM6DSV16X_ODR_OFF) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } @@ -114,10 +113,10 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::begin() } /* Select default output data rate. */ - gyro_odr = LSM6DSV16X_GY_ODR_AT_120Hz; + gyro_odr = LSM6DSV16X_ODR_AT_120Hz; /* Output data rate selection - power down. */ - if (lsm6dsv16x_gy_data_rate_set(®_ctx, LSM6DSV16X_GY_ODR_OFF) != LSM6DSV16X_OK) { + if (lsm6dsv16x_gy_data_rate_set(®_ctx, LSM6DSV16X_ODR_OFF) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } @@ -147,8 +146,8 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::end() } /* Reset output data rate. */ - acc_odr = LSM6DSV16X_XL_ODR_OFF; - gyro_odr = LSM6DSV16X_GY_ODR_OFF; + acc_odr = LSM6DSV16X_ODR_OFF; + gyro_odr = LSM6DSV16X_ODR_OFF; initialized = 0U; @@ -207,7 +206,7 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Disable_X() } /* Output data rate selection - power down. */ - if (lsm6dsv16x_xl_data_rate_set(®_ctx, LSM6DSV16X_XL_ODR_OFF) != LSM6DSV16X_OK) { + if (lsm6dsv16x_xl_data_rate_set(®_ctx, LSM6DSV16X_ODR_OFF) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } @@ -265,7 +264,7 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Get_X_Sensitivity(float *Sensitivity) LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Get_X_ODR(float *Odr) { LSM6DSV16XStatusTypeDef ret = LSM6DSV16X_OK; - lsm6dsv16x_xl_data_rate_t odr_low_level; + lsm6dsv16x_data_rate_t odr_low_level; /* Get current output data rate. */ if (lsm6dsv16x_xl_data_rate_get(®_ctx, &odr_low_level) != LSM6DSV16X_OK) { @@ -273,55 +272,55 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Get_X_ODR(float *Odr) } switch (odr_low_level) { - case LSM6DSV16X_XL_ODR_OFF: + case LSM6DSV16X_ODR_OFF: *Odr = 0.0f; break; - case LSM6DSV16X_XL_ODR_AT_1Hz875: + case LSM6DSV16X_ODR_AT_1Hz875: *Odr = 1.875f; break; - case LSM6DSV16X_XL_ODR_AT_7Hz5: + case LSM6DSV16X_ODR_AT_7Hz5: *Odr = 7.5f; break; - case LSM6DSV16X_XL_ODR_AT_15Hz: + case LSM6DSV16X_ODR_AT_15Hz: *Odr = 15.0f; break; - case LSM6DSV16X_XL_ODR_AT_30Hz: + case LSM6DSV16X_ODR_AT_30Hz: *Odr = 30.0f; break; - case LSM6DSV16X_XL_ODR_AT_60Hz: + case LSM6DSV16X_ODR_AT_60Hz: *Odr = 60.0f; break; - case LSM6DSV16X_XL_ODR_AT_120Hz: + case LSM6DSV16X_ODR_AT_120Hz: *Odr = 120.0f; break; - case LSM6DSV16X_XL_ODR_AT_240Hz: + case LSM6DSV16X_ODR_AT_240Hz: *Odr = 240.0f; break; - case LSM6DSV16X_XL_ODR_AT_480Hz: + case LSM6DSV16X_ODR_AT_480Hz: *Odr = 480.0f; break; - case LSM6DSV16X_XL_ODR_AT_960Hz: + case LSM6DSV16X_ODR_AT_960Hz: *Odr = 960.0f; break; - case LSM6DSV16X_XL_ODR_AT_1920Hz: + case LSM6DSV16X_ODR_AT_1920Hz: *Odr = 1920.0f; break; - case LSM6DSV16X_XL_ODR_AT_3840Hz: + case LSM6DSV16X_ODR_AT_3840Hz: *Odr = 3840.0f; break; - case LSM6DSV16X_XL_ODR_AT_7680Hz: + case LSM6DSV16X_ODR_AT_7680Hz: *Odr = 7680.0f; break; @@ -456,20 +455,20 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Set_X_ODR(float Odr, LSM6DSV16X_ACC_Op */ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Set_X_ODR_When_Enabled(float Odr) { - lsm6dsv16x_xl_data_rate_t new_odr; - - new_odr = (Odr <= 1.875f) ? LSM6DSV16X_XL_ODR_AT_1Hz875 - : (Odr <= 7.5f) ? LSM6DSV16X_XL_ODR_AT_7Hz5 - : (Odr <= 15.0f) ? LSM6DSV16X_XL_ODR_AT_15Hz - : (Odr <= 30.0f) ? LSM6DSV16X_XL_ODR_AT_30Hz - : (Odr <= 60.0f) ? LSM6DSV16X_XL_ODR_AT_60Hz - : (Odr <= 120.0f) ? LSM6DSV16X_XL_ODR_AT_120Hz - : (Odr <= 240.0f) ? LSM6DSV16X_XL_ODR_AT_240Hz - : (Odr <= 480.0f) ? LSM6DSV16X_XL_ODR_AT_480Hz - : (Odr <= 960.0f) ? LSM6DSV16X_XL_ODR_AT_960Hz - : (Odr <= 1920.0f) ? LSM6DSV16X_XL_ODR_AT_1920Hz - : (Odr <= 3840.0f) ? LSM6DSV16X_XL_ODR_AT_3840Hz - : LSM6DSV16X_XL_ODR_AT_7680Hz; + lsm6dsv16x_data_rate_t new_odr; + + new_odr = (Odr <= 1.875f) ? LSM6DSV16X_ODR_AT_1Hz875 + : (Odr <= 7.5f) ? LSM6DSV16X_ODR_AT_7Hz5 + : (Odr <= 15.0f) ? LSM6DSV16X_ODR_AT_15Hz + : (Odr <= 30.0f) ? LSM6DSV16X_ODR_AT_30Hz + : (Odr <= 60.0f) ? LSM6DSV16X_ODR_AT_60Hz + : (Odr <= 120.0f) ? LSM6DSV16X_ODR_AT_120Hz + : (Odr <= 240.0f) ? LSM6DSV16X_ODR_AT_240Hz + : (Odr <= 480.0f) ? LSM6DSV16X_ODR_AT_480Hz + : (Odr <= 960.0f) ? LSM6DSV16X_ODR_AT_960Hz + : (Odr <= 1920.0f) ? LSM6DSV16X_ODR_AT_1920Hz + : (Odr <= 3840.0f) ? LSM6DSV16X_ODR_AT_3840Hz + : LSM6DSV16X_ODR_AT_7680Hz; /* Output data rate selection. */ if (lsm6dsv16x_xl_data_rate_set(®_ctx, new_odr) != LSM6DSV16X_OK) { @@ -486,18 +485,18 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Set_X_ODR_When_Enabled(float Odr) */ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Set_X_ODR_When_Disabled(float Odr) { - acc_odr = (Odr <= 1.875f) ? LSM6DSV16X_XL_ODR_AT_1Hz875 - : (Odr <= 7.5f) ? LSM6DSV16X_XL_ODR_AT_7Hz5 - : (Odr <= 15.0f) ? LSM6DSV16X_XL_ODR_AT_15Hz - : (Odr <= 30.0f) ? LSM6DSV16X_XL_ODR_AT_30Hz - : (Odr <= 60.0f) ? LSM6DSV16X_XL_ODR_AT_60Hz - : (Odr <= 120.0f) ? LSM6DSV16X_XL_ODR_AT_120Hz - : (Odr <= 240.0f) ? LSM6DSV16X_XL_ODR_AT_240Hz - : (Odr <= 480.0f) ? LSM6DSV16X_XL_ODR_AT_480Hz - : (Odr <= 960.0f) ? LSM6DSV16X_XL_ODR_AT_960Hz - : (Odr <= 1920.0f) ? LSM6DSV16X_XL_ODR_AT_1920Hz - : (Odr <= 3840.0f) ? LSM6DSV16X_XL_ODR_AT_3840Hz - : LSM6DSV16X_XL_ODR_AT_7680Hz; + acc_odr = (Odr <= 1.875f) ? LSM6DSV16X_ODR_AT_1Hz875 + : (Odr <= 7.5f) ? LSM6DSV16X_ODR_AT_7Hz5 + : (Odr <= 15.0f) ? LSM6DSV16X_ODR_AT_15Hz + : (Odr <= 30.0f) ? LSM6DSV16X_ODR_AT_30Hz + : (Odr <= 60.0f) ? LSM6DSV16X_ODR_AT_60Hz + : (Odr <= 120.0f) ? LSM6DSV16X_ODR_AT_120Hz + : (Odr <= 240.0f) ? LSM6DSV16X_ODR_AT_240Hz + : (Odr <= 480.0f) ? LSM6DSV16X_ODR_AT_480Hz + : (Odr <= 960.0f) ? LSM6DSV16X_ODR_AT_960Hz + : (Odr <= 1920.0f) ? LSM6DSV16X_ODR_AT_1920Hz + : (Odr <= 3840.0f) ? LSM6DSV16X_ODR_AT_3840Hz + : LSM6DSV16X_ODR_AT_7680Hz; return LSM6DSV16X_OK; } @@ -1366,9 +1365,9 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Set_Wake_Up_Threshold(uint32_t Thresho return LSM6DSV16X_ERROR; } - wake_up_ths.wk_ths_mg = Threshold; + wake_up_ths.threshold = Threshold; - if (lsm6dsv16x_act_thresholds_set(®_ctx, wake_up_ths) != LSM6DSV16X_OK) { + if (lsm6dsv16x_act_thresholds_set(®_ctx, &wake_up_ths) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } @@ -1409,7 +1408,7 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Enable_Single_Tap_Detection(LSM6DSV16X lsm6dsv16x_md2_cfg_t val2; lsm6dsv16x_functions_enable_t functions_enable; - lsm6dsv16x_int_dur2_t tap_dur; + lsm6dsv16x_tap_dur_t tap_dur; lsm6dsv16x_tap_cfg0_t tap_cfg0; lsm6dsv16x_tap_ths_6d_t tap_ths_6d; @@ -1446,14 +1445,14 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Enable_Single_Tap_Detection(LSM6DSV16X } /* Set quiet and shock time windows. */ - if (lsm6dsv16x_read_reg(®_ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { + if (lsm6dsv16x_read_reg(®_ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } tap_dur.quiet = (uint8_t)0x02U; tap_dur.shock = (uint8_t)0x01U; - if (lsm6dsv16x_write_reg(®_ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { + if (lsm6dsv16x_write_reg(®_ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } @@ -1524,7 +1523,7 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Disable_Single_Tap_Detection() { lsm6dsv16x_md1_cfg_t val1; lsm6dsv16x_md2_cfg_t val2; - lsm6dsv16x_int_dur2_t tap_dur; + lsm6dsv16x_tap_dur_t tap_dur; lsm6dsv16x_tap_cfg0_t tap_cfg0; lsm6dsv16x_tap_ths_6d_t tap_ths_6d; @@ -1573,14 +1572,14 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Disable_Single_Tap_Detection() } /* Reset quiet and shock time windows. */ - if (lsm6dsv16x_read_reg(®_ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { + if (lsm6dsv16x_read_reg(®_ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } tap_dur.quiet = (uint8_t)0x0U; tap_dur.shock = (uint8_t)0x0U; - if (lsm6dsv16x_write_reg(®_ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { + if (lsm6dsv16x_write_reg(®_ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } @@ -1599,7 +1598,7 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Enable_Double_Tap_Detection(LSM6DSV16X lsm6dsv16x_md2_cfg_t val2; lsm6dsv16x_functions_enable_t functions_enable; - lsm6dsv16x_int_dur2_t tap_dur; + lsm6dsv16x_tap_dur_t tap_dur; lsm6dsv16x_tap_cfg0_t tap_cfg0; lsm6dsv16x_tap_ths_6d_t tap_ths_6d; @@ -1627,7 +1626,7 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Enable_Double_Tap_Detection(LSM6DSV16X } /* Set quiet shock and duration. */ - if (lsm6dsv16x_read_reg(®_ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { + if (lsm6dsv16x_read_reg(®_ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } @@ -1635,7 +1634,7 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Enable_Double_Tap_Detection(LSM6DSV16X tap_dur.quiet = (uint8_t)0x02U; tap_dur.shock = (uint8_t)0x02U; - if (lsm6dsv16x_write_reg(®_ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { + if (lsm6dsv16x_write_reg(®_ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } @@ -1717,7 +1716,7 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Disable_Double_Tap_Detection() lsm6dsv16x_md1_cfg_t val1; lsm6dsv16x_md2_cfg_t val2; - lsm6dsv16x_int_dur2_t tap_dur; + lsm6dsv16x_tap_dur_t tap_dur; lsm6dsv16x_tap_cfg0_t tap_cfg0; lsm6dsv16x_tap_ths_6d_t tap_ths_6d; @@ -1765,7 +1764,7 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Disable_Double_Tap_Detection() } /* Reset quiet shock and duratio. */ - if (lsm6dsv16x_read_reg(®_ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { + if (lsm6dsv16x_read_reg(®_ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } @@ -1773,7 +1772,7 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Disable_Double_Tap_Detection() tap_dur.quiet = (uint8_t)0x0U; tap_dur.shock = (uint8_t)0x0U; - if (lsm6dsv16x_write_reg(®_ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { + if (lsm6dsv16x_write_reg(®_ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } @@ -1816,16 +1815,16 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Set_Tap_Threshold(uint8_t Threshold) */ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Set_Tap_Shock_Time(uint8_t Time) { - lsm6dsv16x_int_dur2_t tap_dur; + lsm6dsv16x_tap_dur_t tap_dur; /* Set shock time */ - if (lsm6dsv16x_read_reg(®_ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { + if (lsm6dsv16x_read_reg(®_ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } tap_dur.shock = Time; - if (lsm6dsv16x_write_reg(®_ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { + if (lsm6dsv16x_write_reg(®_ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } } @@ -1837,16 +1836,16 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Set_Tap_Shock_Time(uint8_t Time) */ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Set_Tap_Quiet_Time(uint8_t Time) { - lsm6dsv16x_int_dur2_t tap_dur; + lsm6dsv16x_tap_dur_t tap_dur; /* Set quiet time */ - if (lsm6dsv16x_read_reg(®_ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { + if (lsm6dsv16x_read_reg(®_ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } tap_dur.quiet = Time; - if (lsm6dsv16x_write_reg(®_ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { + if (lsm6dsv16x_write_reg(®_ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } return LSM6DSV16X_OK; @@ -1859,16 +1858,16 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Set_Tap_Quiet_Time(uint8_t Time) */ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Set_Tap_Duration_Time(uint8_t Time) { - lsm6dsv16x_int_dur2_t tap_dur; + lsm6dsv16x_tap_dur_t tap_dur; /* Set duration time */ - if (lsm6dsv16x_read_reg(®_ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { + if (lsm6dsv16x_read_reg(®_ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } tap_dur.dur = Time; - if (lsm6dsv16x_write_reg(®_ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { + if (lsm6dsv16x_write_reg(®_ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } return LSM6DSV16X_OK; @@ -2311,7 +2310,13 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Disable_Tilt_Detection() */ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::FIFO_Get_Num_Samples(uint16_t *NumSamples) { - return (LSM6DSV16XStatusTypeDef) lsm6dsv16x_fifo_data_level_get(®_ctx, NumSamples); + lsm6dsv16x_fifo_status_t status; + if (lsm6dsv16x_fifo_status_get(®_ctx, &status) != LSM6DSV16X_OK) { + return LSM6DSV16X_ERROR; + } + *NumSamples = status.fifo_level; + + return LSM6DSV16X_OK; } /** @@ -2630,7 +2635,7 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Disable_G() } /* Output data rate selection - power down. */ - if (lsm6dsv16x_gy_data_rate_set(®_ctx, LSM6DSV16X_GY_ODR_OFF) != LSM6DSV16X_OK) { + if (lsm6dsv16x_gy_data_rate_set(®_ctx, LSM6DSV16X_ODR_OFF) != LSM6DSV16X_OK) { return LSM6DSV16X_ERROR; } @@ -2696,7 +2701,7 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Get_G_Sensitivity(float *Sensitivity) LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Get_G_ODR(float *Odr) { LSM6DSV16XStatusTypeDef ret = LSM6DSV16X_OK; - lsm6dsv16x_gy_data_rate_t odr_low_level; + lsm6dsv16x_data_rate_t odr_low_level; /* Get current output data rate. */ if (lsm6dsv16x_gy_data_rate_get(®_ctx, &odr_low_level) != LSM6DSV16X_OK) { @@ -2704,51 +2709,51 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Get_G_ODR(float *Odr) } switch (odr_low_level) { - case LSM6DSV16X_GY_ODR_OFF: + case LSM6DSV16X_ODR_OFF: *Odr = 0.0f; break; - case LSM6DSV16X_GY_ODR_AT_7Hz5: + case LSM6DSV16X_ODR_AT_7Hz5: *Odr = 7.5f; break; - case LSM6DSV16X_GY_ODR_AT_15Hz: + case LSM6DSV16X_ODR_AT_15Hz: *Odr = 15.0f; break; - case LSM6DSV16X_GY_ODR_AT_30Hz: + case LSM6DSV16X_ODR_AT_30Hz: *Odr = 30.0f; break; - case LSM6DSV16X_GY_ODR_AT_60Hz: + case LSM6DSV16X_ODR_AT_60Hz: *Odr = 60.0f; break; - case LSM6DSV16X_GY_ODR_AT_120Hz: + case LSM6DSV16X_ODR_AT_120Hz: *Odr = 120.0f; break; - case LSM6DSV16X_GY_ODR_AT_240Hz: + case LSM6DSV16X_ODR_AT_240Hz: *Odr = 240.0f; break; - case LSM6DSV16X_GY_ODR_AT_480Hz: + case LSM6DSV16X_ODR_AT_480Hz: *Odr = 480.0f; break; - case LSM6DSV16X_GY_ODR_AT_960Hz: + case LSM6DSV16X_ODR_AT_960Hz: *Odr = 960.0f; break; - case LSM6DSV16X_GY_ODR_AT_1920Hz: + case LSM6DSV16X_ODR_AT_1920Hz: *Odr = 1920.0f; break; - case LSM6DSV16X_GY_ODR_AT_3840Hz: + case LSM6DSV16X_ODR_AT_3840Hz: *Odr = 3840.0f; break; - case LSM6DSV16X_GY_ODR_AT_7680Hz: + case LSM6DSV16X_ODR_AT_7680Hz: *Odr = 7680.0f; break; @@ -2822,19 +2827,19 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Set_G_ODR(float Odr, LSM6DSV16X_GYRO_O */ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Set_G_ODR_When_Enabled(float Odr) { - lsm6dsv16x_gy_data_rate_t new_odr; + lsm6dsv16x_data_rate_t new_odr; - new_odr = (Odr <= 7.5f) ? LSM6DSV16X_GY_ODR_AT_7Hz5 - : (Odr <= 15.0f) ? LSM6DSV16X_GY_ODR_AT_15Hz - : (Odr <= 30.0f) ? LSM6DSV16X_GY_ODR_AT_30Hz - : (Odr <= 60.0f) ? LSM6DSV16X_GY_ODR_AT_60Hz - : (Odr <= 120.0f) ? LSM6DSV16X_GY_ODR_AT_120Hz - : (Odr <= 240.0f) ? LSM6DSV16X_GY_ODR_AT_240Hz - : (Odr <= 480.0f) ? LSM6DSV16X_GY_ODR_AT_480Hz - : (Odr <= 960.0f) ? LSM6DSV16X_GY_ODR_AT_960Hz - : (Odr <= 1920.0f) ? LSM6DSV16X_GY_ODR_AT_1920Hz - : (Odr <= 3840.0f) ? LSM6DSV16X_GY_ODR_AT_3840Hz - : LSM6DSV16X_GY_ODR_AT_7680Hz; + new_odr = (Odr <= 7.5f) ? LSM6DSV16X_ODR_AT_7Hz5 + : (Odr <= 15.0f) ? LSM6DSV16X_ODR_AT_15Hz + : (Odr <= 30.0f) ? LSM6DSV16X_ODR_AT_30Hz + : (Odr <= 60.0f) ? LSM6DSV16X_ODR_AT_60Hz + : (Odr <= 120.0f) ? LSM6DSV16X_ODR_AT_120Hz + : (Odr <= 240.0f) ? LSM6DSV16X_ODR_AT_240Hz + : (Odr <= 480.0f) ? LSM6DSV16X_ODR_AT_480Hz + : (Odr <= 960.0f) ? LSM6DSV16X_ODR_AT_960Hz + : (Odr <= 1920.0f) ? LSM6DSV16X_ODR_AT_1920Hz + : (Odr <= 3840.0f) ? LSM6DSV16X_ODR_AT_3840Hz + : LSM6DSV16X_ODR_AT_7680Hz; /* Output data rate selection. */ if (lsm6dsv16x_gy_data_rate_set(®_ctx, new_odr) != LSM6DSV16X_OK) { @@ -2851,17 +2856,17 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Set_G_ODR_When_Enabled(float Odr) */ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Set_G_ODR_When_Disabled(float Odr) { - gyro_odr = (Odr <= 7.5f) ? LSM6DSV16X_GY_ODR_AT_7Hz5 - : (Odr <= 15.0f) ? LSM6DSV16X_GY_ODR_AT_15Hz - : (Odr <= 30.0f) ? LSM6DSV16X_GY_ODR_AT_30Hz - : (Odr <= 60.0f) ? LSM6DSV16X_GY_ODR_AT_60Hz - : (Odr <= 120.0f) ? LSM6DSV16X_GY_ODR_AT_120Hz - : (Odr <= 240.0f) ? LSM6DSV16X_GY_ODR_AT_240Hz - : (Odr <= 480.0f) ? LSM6DSV16X_GY_ODR_AT_480Hz - : (Odr <= 960.0f) ? LSM6DSV16X_GY_ODR_AT_960Hz - : (Odr <= 1920.0f) ? LSM6DSV16X_GY_ODR_AT_1920Hz - : (Odr <= 3840.0f) ? LSM6DSV16X_GY_ODR_AT_3840Hz - : LSM6DSV16X_GY_ODR_AT_7680Hz; + gyro_odr = (Odr <= 7.5f) ? LSM6DSV16X_ODR_AT_7Hz5 + : (Odr <= 15.0f) ? LSM6DSV16X_ODR_AT_15Hz + : (Odr <= 30.0f) ? LSM6DSV16X_ODR_AT_30Hz + : (Odr <= 60.0f) ? LSM6DSV16X_ODR_AT_60Hz + : (Odr <= 120.0f) ? LSM6DSV16X_ODR_AT_120Hz + : (Odr <= 240.0f) ? LSM6DSV16X_ODR_AT_240Hz + : (Odr <= 480.0f) ? LSM6DSV16X_ODR_AT_480Hz + : (Odr <= 960.0f) ? LSM6DSV16X_ODR_AT_960Hz + : (Odr <= 1920.0f) ? LSM6DSV16X_ODR_AT_1920Hz + : (Odr <= 3840.0f) ? LSM6DSV16X_ODR_AT_3840Hz + : LSM6DSV16X_ODR_AT_7680Hz; return LSM6DSV16X_OK; } @@ -3050,7 +3055,7 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Set_G_Filter_Mode(uint8_t LowHighPassF /** - * @brief Enable the LSM6DSV16X QVAR sensor + * @brief Enable the LSM6DSV16X QVAR feature * @retval 0 in case of success, an error code otherwise */ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::QVAR_Enable() @@ -3071,6 +3076,28 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::QVAR_Enable() return LSM6DSV16X_OK; } +/** + * @brief Disable the LSM6DSV16X QVAR feature + * @retval 0 in case of success, an error code otherwise + */ +LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::QVAR_Disable() +{ + lsm6dsv16x_ctrl7_t ctrl7; + + if (lsm6dsv16x_read_reg(®_ctx, LSM6DSV16X_CTRL7, (uint8_t *)&ctrl7, 1) != LSM6DSV16X_OK) { + return LSM6DSV16X_ERROR; + } + + ctrl7.ah_qvar_en = 0; + ctrl7.int2_drdy_ah_qvar = 0; + + if (lsm6dsv16x_write_reg(®_ctx, LSM6DSV16X_CTRL7, (uint8_t *)&ctrl7, 1) != LSM6DSV16X_OK) { + return LSM6DSV16X_ERROR; + } + + return LSM6DSV16X_OK; +} + /** * @brief Read LSM6DSV16X QVAR output data @@ -3090,6 +3117,40 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::QVAR_GetData(float *Data) return LSM6DSV16X_OK; } +/** + * @brief Get LSM6DSV16X QVAR equivalent input impedance + * @param val pointer where the value is written + * @retval 0 in case of success, an error code otherwise + */ +LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::QVAR_GetImpedance(uint16_t *val) +{ + LSM6DSV16XStatusTypeDef ret = LSM6DSV16X_OK; + lsm6dsv16x_ah_qvar_zin_t imp; + + if (lsm6dsv16x_ah_qvar_zin_get(®_ctx, &imp) != LSM6DSV16X_OK) { + ret = LSM6DSV16X_ERROR; + } + switch (imp) { + case LSM6DSV16X_2400MOhm: + *val = 2400; + break; + case LSM6DSV16X_730MOhm: + *val = 730; + break; + case LSM6DSV16X_300MOhm: + *val = 300; + break; + case LSM6DSV16X_255MOhm: + *val = 255; + break; + default: + ret = LSM6DSV16X_ERROR; + break; + } + + return ret; +} + /** * @brief Set LSM6DSV16X QVAR equivalent input impedance @@ -3172,6 +3233,320 @@ LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Get_MLC_Output(lsm6dsv16x_mlc_out_t *o return LSM6DSV16X_OK; } +/** + * @brief Enable Rotation Vector SFLP feature + * @retval 0 in case of success, an error code otherwise + */ +LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Enable_Rotation_Vector() +{ + lsm6dsv16x_fifo_sflp_raw_t fifo_sflp; + + /* Set full scale */ + if (lsm6dsv16x_xl_full_scale_set(®_ctx, LSM6DSV16X_4g)) { + return LSM6DSV16X_ERROR; + } + if (lsm6dsv16x_gy_full_scale_set(®_ctx, LSM6DSV16X_2000dps)) { + return LSM6DSV16X_ERROR; + } + + if (lsm6dsv16x_fifo_sflp_batch_get(®_ctx, &fifo_sflp)) { + return LSM6DSV16X_ERROR; + } + /* Enable Rotation Vector SFLP feature */ + fifo_sflp.game_rotation = 1; + + if (lsm6dsv16x_fifo_sflp_batch_set(®_ctx, fifo_sflp)) { + return LSM6DSV16X_ERROR; + } + + /* Set FIFO mode to Stream mode (aka Continuous Mode) */ + if (lsm6dsv16x_fifo_mode_set(®_ctx, LSM6DSV16X_STREAM_MODE)) { + return LSM6DSV16X_ERROR; + } + + /* Set Output Data Rate */ + if (lsm6dsv16x_xl_data_rate_set(®_ctx, LSM6DSV16X_ODR_AT_120Hz)) { + return LSM6DSV16X_ERROR; + } + if (lsm6dsv16x_gy_data_rate_set(®_ctx, LSM6DSV16X_ODR_AT_120Hz)) { + return LSM6DSV16X_ERROR; + } + if (lsm6dsv16x_sflp_data_rate_set(®_ctx, LSM6DSV16X_SFLP_120Hz)) { + return LSM6DSV16X_ERROR; + } + + /* Enable SFLP low power */ + if (lsm6dsv16x_sflp_game_rotation_set(®_ctx, PROPERTY_ENABLE)) { + return LSM6DSV16X_ERROR; + } + return LSM6DSV16X_OK; +} + +/** + * @brief Disable Rotation Vector SFLP feature + * @retval 0 in case of success, an error code otherwise + */ +LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Disable_Rotation_Vector() +{ + lsm6dsv16x_fifo_sflp_raw_t fifo_sflp; + + /* Set full scale */ + if (lsm6dsv16x_xl_full_scale_set(®_ctx, LSM6DSV16X_4g)) { + return LSM6DSV16X_ERROR; + } + if (lsm6dsv16x_gy_full_scale_set(®_ctx, LSM6DSV16X_2000dps)) { + return LSM6DSV16X_ERROR; + } + + if (lsm6dsv16x_fifo_sflp_batch_get(®_ctx, &fifo_sflp)) { + return LSM6DSV16X_ERROR; + } + /* Disable Rotation Vector SFLP feature */ + fifo_sflp.game_rotation = 0; + + if (lsm6dsv16x_fifo_sflp_batch_set(®_ctx, fifo_sflp)) { + return LSM6DSV16X_ERROR; + } + + /* Check if all SFLP features are disabled */ + if (!fifo_sflp.game_rotation && !fifo_sflp.gravity && !fifo_sflp.gbias) { + /* Disable SFLP */ + if (lsm6dsv16x_sflp_game_rotation_set(®_ctx, PROPERTY_DISABLE)) { + return LSM6DSV16X_ERROR; + } + } + return LSM6DSV16X_OK; +} + +/** + * @brief Enable Gravity Vector SFLP feature + * @retval 0 in case of success, an error code otherwise + */ +LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Enable_Gravity_Vector() +{ + lsm6dsv16x_fifo_sflp_raw_t fifo_sflp; + + /* Set full scale */ + if (lsm6dsv16x_xl_full_scale_set(®_ctx, LSM6DSV16X_4g)) { + return LSM6DSV16X_ERROR; + } + if (lsm6dsv16x_gy_full_scale_set(®_ctx, LSM6DSV16X_2000dps)) { + return LSM6DSV16X_ERROR; + } + + if (lsm6dsv16x_fifo_sflp_batch_get(®_ctx, &fifo_sflp)) { + return LSM6DSV16X_ERROR; + } + /* Enable Gravity Vector SFLP feature */ + fifo_sflp.gravity = 1; + + if (lsm6dsv16x_fifo_sflp_batch_set(®_ctx, fifo_sflp)) { + return LSM6DSV16X_ERROR; + } + + /* Set FIFO mode to Stream mode (aka Continuous Mode) */ + if (lsm6dsv16x_fifo_mode_set(®_ctx, LSM6DSV16X_STREAM_MODE)) { + return LSM6DSV16X_ERROR; + } + + /* Set Output Data Rate */ + if (lsm6dsv16x_xl_data_rate_set(®_ctx, LSM6DSV16X_ODR_AT_120Hz)) { + return LSM6DSV16X_ERROR; + } + if (lsm6dsv16x_gy_data_rate_set(®_ctx, LSM6DSV16X_ODR_AT_120Hz)) { + return LSM6DSV16X_ERROR; + } + if (lsm6dsv16x_sflp_data_rate_set(®_ctx, LSM6DSV16X_SFLP_120Hz)) { + return LSM6DSV16X_ERROR; + } + + /* Enable SFLP low power */ + if (lsm6dsv16x_sflp_game_rotation_set(®_ctx, PROPERTY_ENABLE)) { + return LSM6DSV16X_ERROR; + } + return LSM6DSV16X_OK; +} + +/** + * @brief Disable Gravity Vector SFLP feature + * @retval 0 in case of success, an error code otherwise + */ +LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Disable_Gravity_Vector() +{ + lsm6dsv16x_fifo_sflp_raw_t fifo_sflp; + + /* Set full scale */ + if (lsm6dsv16x_xl_full_scale_set(®_ctx, LSM6DSV16X_4g)) { + return LSM6DSV16X_ERROR; + } + if (lsm6dsv16x_gy_full_scale_set(®_ctx, LSM6DSV16X_2000dps)) { + return LSM6DSV16X_ERROR; + } + + if (lsm6dsv16x_fifo_sflp_batch_get(®_ctx, &fifo_sflp)) { + return LSM6DSV16X_ERROR; + } + /* Disable Gravity Vector SFLP feature */ + fifo_sflp.gravity = 0; + + if (lsm6dsv16x_fifo_sflp_batch_set(®_ctx, fifo_sflp)) { + return LSM6DSV16X_ERROR; + } + + /* Check if all SFLP features are disabled */ + if (!fifo_sflp.game_rotation && !fifo_sflp.gravity && !fifo_sflp.gbias) { + /* Disable SFLP */ + if (lsm6dsv16x_sflp_game_rotation_set(®_ctx, PROPERTY_DISABLE)) { + return LSM6DSV16X_ERROR; + } + } + return LSM6DSV16X_OK; +} + +/** + * @brief Enable Gyroscope Bias SFLP feature + * @retval 0 in case of success, an error code otherwise + */ +LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Enable_Gyroscope_Bias() +{ + lsm6dsv16x_fifo_sflp_raw_t fifo_sflp; + + /* Set full scale */ + if (lsm6dsv16x_xl_full_scale_set(®_ctx, LSM6DSV16X_4g)) { + return LSM6DSV16X_ERROR; + } + if (lsm6dsv16x_gy_full_scale_set(®_ctx, LSM6DSV16X_2000dps)) { + return LSM6DSV16X_ERROR; + } + + if (lsm6dsv16x_fifo_sflp_batch_get(®_ctx, &fifo_sflp)) { + return LSM6DSV16X_ERROR; + } + /* Enable Gyroscope Bias SFLP feature */ + fifo_sflp.gbias = 1; + + if (lsm6dsv16x_fifo_sflp_batch_set(®_ctx, fifo_sflp)) { + return LSM6DSV16X_ERROR; + } + + /* Set FIFO mode to Stream mode (aka Continuous Mode) */ + if (lsm6dsv16x_fifo_mode_set(®_ctx, LSM6DSV16X_STREAM_MODE)) { + return LSM6DSV16X_ERROR; + } + + /* Set Output Data Rate */ + if (lsm6dsv16x_xl_data_rate_set(®_ctx, LSM6DSV16X_ODR_AT_120Hz)) { + return LSM6DSV16X_ERROR; + } + if (lsm6dsv16x_gy_data_rate_set(®_ctx, LSM6DSV16X_ODR_AT_120Hz)) { + return LSM6DSV16X_ERROR; + } + if (lsm6dsv16x_sflp_data_rate_set(®_ctx, LSM6DSV16X_SFLP_120Hz)) { + return LSM6DSV16X_ERROR; + } + + /* Enable SFLP low power */ + if (lsm6dsv16x_sflp_game_rotation_set(®_ctx, PROPERTY_ENABLE)) { + return LSM6DSV16X_ERROR; + } + return LSM6DSV16X_OK; +} + +/** + * @brief Disable Gyroscope Bias SFLP feature + * @retval 0 in case of success, an error code otherwise + */ +LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::Disable_Gyroscope_Bias() +{ + lsm6dsv16x_fifo_sflp_raw_t fifo_sflp; + + /* Set full scale */ + if (lsm6dsv16x_xl_full_scale_set(®_ctx, LSM6DSV16X_4g)) { + return LSM6DSV16X_ERROR; + } + if (lsm6dsv16x_gy_full_scale_set(®_ctx, LSM6DSV16X_2000dps)) { + return LSM6DSV16X_ERROR; + } + + if (lsm6dsv16x_fifo_sflp_batch_get(®_ctx, &fifo_sflp)) { + return LSM6DSV16X_ERROR; + } + /* Disable Gyroscope Bias SFLP feature */ + fifo_sflp.gbias = 0; + + if (lsm6dsv16x_fifo_sflp_batch_set(®_ctx, fifo_sflp)) { + return LSM6DSV16X_ERROR; + } + + /* Check if all SFLP features are disabled */ + if (!fifo_sflp.game_rotation && !fifo_sflp.gravity && !fifo_sflp.gbias) { + /* Disable SFLP */ + if (lsm6dsv16x_sflp_game_rotation_set(®_ctx, PROPERTY_DISABLE)) { + return LSM6DSV16X_ERROR; + } + } + return LSM6DSV16X_OK; +} + +/** + * @brief Get the Rotation Vector values + * @param rvec pointer where the Rotation Vector values are written + * @retval 0 in case of success, an error code otherwise + */ +LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::FIFO_Get_Rotation_Vector(float *rvec) +{ + lsm6dsv16x_axis3bit16_t data_raw; + + if (FIFO_Get_Data(data_raw.u8bit) != LSM6DSV16X_OK) { + return LSM6DSV16X_ERROR; + } + sflp2q(rvec, (uint16_t *)&data_raw.i16bit[0]); + + return LSM6DSV16X_OK; +} + +/** + * @brief Get the Gravity Vector values + * @param gvec pointer where the Gravity Vector values are written + * @retval 0 in case of success, an error code otherwise + */ +LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::FIFO_Get_Gravity_Vector(float *gvec) +{ + lsm6dsv16x_axis3bit16_t data_raw; + float gvec_float[3]; + + if (FIFO_Get_Data(data_raw.u8bit) != LSM6DSV16X_OK) { + return LSM6DSV16X_ERROR; + } + + gvec[0] = lsm6dsv16x_from_sflp_to_mg(data_raw.i16bit[0]); + gvec[1] = lsm6dsv16x_from_sflp_to_mg(data_raw.i16bit[1]); + gvec[2] = lsm6dsv16x_from_sflp_to_mg(data_raw.i16bit[2]); + + return LSM6DSV16X_OK; +} + +/** + * @brief Get the Gravity Bias values + * @param gbias pointer where the Gravity Bias values are written + * @retval 0 in case of success, an error code otherwise + */ +LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::FIFO_Get_Gyroscope_Bias(float *gbias) +{ + lsm6dsv16x_axis3bit16_t data_raw; + + if (FIFO_Get_Data(data_raw.u8bit) != LSM6DSV16X_OK) { + return LSM6DSV16X_ERROR; + } + + gbias[0] = lsm6dsv16x_from_fs125_to_mdps(data_raw.i16bit[0]); + gbias[1] = lsm6dsv16x_from_fs125_to_mdps(data_raw.i16bit[1]); + gbias[2] = lsm6dsv16x_from_fs125_to_mdps(data_raw.i16bit[2]); + + return LSM6DSV16X_OK; +} + + /** * @brief Get the LSM6DSV16X register value * @param Reg address to be read @@ -3211,3 +3586,92 @@ int32_t LSM6DSV16X_io_read(void *handle, uint8_t ReadAddr, uint8_t *pBuffer, uin { return ((LSM6DSV16XSensor *)handle)->IO_Read(pBuffer, ReadAddr, nBytesToRead); } + +/** + * @brief Converts uint16_t half-precision number into a uint32_t single-precision number. + * @param h half-precision number + * @param f pointer where the result of the conversion is written + * @retval 0 + */ +LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::npy_halfbits_to_floatbits(uint16_t h, uint32_t *f) +{ + uint16_t h_exp, h_sig; + uint32_t f_sgn, f_exp, f_sig; + + h_exp = (h & 0x7c00u); + f_sgn = ((uint32_t)h & 0x8000u) << 16; + switch (h_exp) { + case 0x0000u: /* 0 or subnormal */ + h_sig = (h & 0x03ffu); + /* Signed zero */ + if (h_sig == 0) { + *f = f_sgn; + return LSM6DSV16X_OK; + } + /* Subnormal */ + h_sig <<= 1; + while ((h_sig & 0x0400u) == 0) { + h_sig <<= 1; + h_exp++; + } + f_exp = ((uint32_t)(127 - 15 - h_exp)) << 23; + f_sig = ((uint32_t)(h_sig & 0x03ffu)) << 13; + *f = f_sgn + f_exp + f_sig; + return LSM6DSV16X_OK; + case 0x7c00u: /* inf or NaN */ + /* All-ones exponent and a copy of the significand */ + *f = f_sgn + 0x7f800000u + (((uint32_t)(h & 0x03ffu)) << 13); + return LSM6DSV16X_OK; + default: /* normalized */ + /* Just need to adjust the exponent and shift */ + *f = f_sgn + (((uint32_t)(h & 0x7fffu) + 0x1c000u) << 13); + return LSM6DSV16X_OK; + } +} + +/** + * @brief Converts uint16_t half-precision number into a float single-precision number. + * @param h half-precision number + * @param f pointer where the result of the conversion is written + * @retval 0 + */ +LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::npy_half_to_float(uint16_t h, float *f) +{ + union { + float ret; + uint32_t retbits; + } conv; + npy_halfbits_to_floatbits(h, &conv.retbits); + *f = conv.ret; + return LSM6DSV16X_OK; +} + +/** + * @brief Compute quaternions. + * @param quat results of the computation + * @param sflp raw value of the quaternions + * @retval 0 + */ +LSM6DSV16XStatusTypeDef LSM6DSV16XSensor::sflp2q(float quat[4], uint16_t sflp[3]) +{ + float sumsq = 0; + + npy_half_to_float(sflp[0], &quat[0]); + npy_half_to_float(sflp[1], &quat[1]); + npy_half_to_float(sflp[2], &quat[2]); + + for (uint8_t i = 0; i < 3; i++) { + sumsq += quat[i] * quat[i]; + } + + if (sumsq > 1.0f) { + float n = sqrtf(sumsq); + quat[0] /= n; + quat[1] /= n; + quat[2] /= n; + sumsq = 1.0f; + } + + quat[3] = sqrtf(1.0f - sumsq); + return LSM6DSV16X_OK; +} \ No newline at end of file diff --git a/src/LSM6DSV16XSensor.h b/src/LSM6DSV16XSensor.h index 7f7b3fd..07fd67c 100644 --- a/src/LSM6DSV16XSensor.h +++ b/src/LSM6DSV16XSensor.h @@ -1,7 +1,7 @@ /** ****************************************************************************** * @file LSM6DSV16XSensor.h - * @author SRA + * @author STMicroelectronics * @version V1.0.0 * @date July 2022 * @brief Abstract Class of a LSM6DSV16X inertial measurement sensor. @@ -208,13 +208,25 @@ class LSM6DSV16XSensor { LSM6DSV16XStatusTypeDef FIFO_Set_G_BDR(float Bdr); LSM6DSV16XStatusTypeDef QVAR_Enable(); + LSM6DSV16XStatusTypeDef QVAR_Disable(); LSM6DSV16XStatusTypeDef QVAR_GetStatus(uint8_t *val); + LSM6DSV16XStatusTypeDef QVAR_GetImpedance(uint16_t *val); LSM6DSV16XStatusTypeDef QVAR_SetImpedance(uint16_t val); LSM6DSV16XStatusTypeDef QVAR_GetData(float *Data); LSM6DSV16XStatusTypeDef Get_MLC_Status(lsm6dsv16x_mlc_status_mainpage_t *status); LSM6DSV16XStatusTypeDef Get_MLC_Output(lsm6dsv16x_mlc_out_t *output); + LSM6DSV16XStatusTypeDef Enable_Rotation_Vector(); + LSM6DSV16XStatusTypeDef Disable_Rotation_Vector(); + LSM6DSV16XStatusTypeDef Enable_Gravity_Vector(); + LSM6DSV16XStatusTypeDef Disable_Gravity_Vector(); + LSM6DSV16XStatusTypeDef Enable_Gyroscope_Bias(); + LSM6DSV16XStatusTypeDef Disable_Gyroscope_Bias(); + LSM6DSV16XStatusTypeDef FIFO_Get_Rotation_Vector(float *rvec); + LSM6DSV16XStatusTypeDef FIFO_Get_Gravity_Vector(float *gvec); + LSM6DSV16XStatusTypeDef FIFO_Get_Gyroscope_Bias(float *gbias); + LSM6DSV16XStatusTypeDef Read_Reg(uint8_t Reg, uint8_t *Data); LSM6DSV16XStatusTypeDef Write_Reg(uint8_t Reg, uint8_t Data); @@ -314,6 +326,9 @@ class LSM6DSV16XSensor { LSM6DSV16XStatusTypeDef Set_X_ODR_When_Disabled(float Odr); LSM6DSV16XStatusTypeDef Set_G_ODR_When_Enabled(float Odr); LSM6DSV16XStatusTypeDef Set_G_ODR_When_Disabled(float Odr); + LSM6DSV16XStatusTypeDef npy_halfbits_to_floatbits(uint16_t h, uint32_t *f); + LSM6DSV16XStatusTypeDef npy_half_to_float(uint16_t h, float *f); + LSM6DSV16XStatusTypeDef sflp2q(float quat[4], uint16_t sflp[3]); /* Helper classes. */ TwoWire *dev_i2c; @@ -324,8 +339,8 @@ class LSM6DSV16XSensor { int cs_pin; uint32_t spi_speed; - lsm6dsv16x_xl_data_rate_t acc_odr; - lsm6dsv16x_gy_data_rate_t gyro_odr; + lsm6dsv16x_data_rate_t acc_odr; + lsm6dsv16x_data_rate_t gyro_odr; uint8_t acc_is_enabled; uint8_t gyro_is_enabled; uint8_t initialized; diff --git a/src/lsm6dsv16x_reg.c b/src/lsm6dsv16x_reg.c index d77236c..4e9d4e2 100644 --- a/src/lsm6dsv16x_reg.c +++ b/src/lsm6dsv16x_reg.c @@ -6,7 +6,7 @@ ****************************************************************************** * @attention * - *

© Copyright (c) 2021 STMicroelectronics. + *

© Copyright (c) 2022 STMicroelectronics. * All rights reserved.

* * This software component is licensed by ST under BSD 3-Clause license, @@ -46,9 +46,9 @@ * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_read_reg(lsm6dsv16x_ctx_t *ctx, uint8_t reg, - uint8_t *data, - uint16_t len) +int32_t __weak lsm6dsv16x_read_reg(lsm6dsv16x_ctx_t *ctx, uint8_t reg, + uint8_t *data, + uint16_t len) { int32_t ret; @@ -67,9 +67,9 @@ int32_t lsm6dsv16x_read_reg(lsm6dsv16x_ctx_t *ctx, uint8_t reg, * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_write_reg(lsm6dsv16x_ctx_t *ctx, uint8_t reg, - uint8_t *data, - uint16_t len) +int32_t __weak lsm6dsv16x_write_reg(lsm6dsv16x_ctx_t *ctx, uint8_t reg, + uint8_t *data, + uint16_t len) { int32_t ret; @@ -108,64 +108,69 @@ static void bytecpy(uint8_t *target, uint8_t *source) * @{ * */ -float lsm6dsv16x_from_fs2_to_mg(int16_t lsb) +float_t lsm6dsv16x_from_sflp_to_mg(int16_t lsb) { - return ((float)lsb) * 0.061f; + return ((float_t)lsb) * 0.061f; } -float lsm6dsv16x_from_fs4_to_mg(int16_t lsb) +float_t lsm6dsv16x_from_fs2_to_mg(int16_t lsb) { - return ((float)lsb) * 0.122f; + return ((float_t)lsb) * 0.061f; } -float lsm6dsv16x_from_fs8_to_mg(int16_t lsb) +float_t lsm6dsv16x_from_fs4_to_mg(int16_t lsb) { - return ((float)lsb) * 0.244f; + return ((float_t)lsb) * 0.122f; } -float lsm6dsv16x_from_fs16_to_mg(int16_t lsb) +float_t lsm6dsv16x_from_fs8_to_mg(int16_t lsb) { - return ((float)lsb) * 0.488f; + return ((float_t)lsb) * 0.244f; } -float lsm6dsv16x_from_fs125_to_mdps(int16_t lsb) +float_t lsm6dsv16x_from_fs16_to_mg(int16_t lsb) { - return ((float)lsb) * 4.375f; + return ((float_t)lsb) * 0.488f; } -float lsm6dsv16x_from_fs250_to_mdps(int16_t lsb) +float_t lsm6dsv16x_from_fs125_to_mdps(int16_t lsb) { - return ((float)lsb) * 8.750f; + return ((float_t)lsb) * 4.375f; } -float lsm6dsv16x_from_fs500_to_mdps(int16_t lsb) +float_t lsm6dsv16x_from_fs250_to_mdps(int16_t lsb) { - return ((float)lsb) * 17.50f; + return ((float_t)lsb) * 8.750f; } -float lsm6dsv16x_from_fs1000_to_mdps(int16_t lsb) +float_t lsm6dsv16x_from_fs500_to_mdps(int16_t lsb) { - return ((float)lsb) * 35.0f; + return ((float_t)lsb) * 17.50f; } -float lsm6dsv16x_from_fs2000_to_mdps(int16_t lsb) +float_t lsm6dsv16x_from_fs1000_to_mdps(int16_t lsb) { - return ((float)lsb) * 70.0f; + return ((float_t)lsb) * 35.0f; } -float lsm6dsv16x_from_fs4000_to_mdps(int16_t lsb) +float_t lsm6dsv16x_from_fs2000_to_mdps(int16_t lsb) { - return ((float)lsb) * 140.0f; + return ((float_t)lsb) * 70.0f; } -float lsm6dsv16x_from_lsb_to_celsius(int16_t lsb) +float_t lsm6dsv16x_from_fs4000_to_mdps(int16_t lsb) { - return (((float)lsb / 256.0f) + 25.0f); + return ((float_t)lsb) * 140.0f; } -float lsm6dsv16x_from_lsb_to_nsec(uint32_t lsb) +float_t lsm6dsv16x_from_lsb_to_celsius(int16_t lsb) { - return ((float)lsb * 21750.0f); + return (((float_t)lsb / 256.0f) + 25.0f); +} + +float_t lsm6dsv16x_from_lsb_to_nsec(uint32_t lsb) +{ + return ((float_t)lsb * 21750.0f); } /** @@ -230,21 +235,21 @@ int32_t lsm6dsv16x_xl_offset_on_out_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_xl_offset_mg_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_offset_mg_t val) +int32_t lsm6dsv16x_xl_offset_mg_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_offset_mg_t val) { lsm6dsv16x_z_ofs_usr_t z_ofs_usr; lsm6dsv16x_y_ofs_usr_t y_ofs_usr; lsm6dsv16x_x_ofs_usr_t x_ofs_usr; lsm6dsv16x_ctrl9_t ctrl9; int32_t ret; - float tmp; + float_t tmp; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_Z_OFS_USR, (uint8_t *)&z_ofs_usr, 1); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_Y_OFS_USR, (uint8_t *)&y_ofs_usr, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_X_OFS_USR, (uint8_t *)&x_ofs_usr, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_Y_OFS_USR, (uint8_t *)&y_ofs_usr, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_X_OFS_USR, (uint8_t *)&x_ofs_usr, 1); + if (ret != 0) { + return ret; } @@ -281,18 +286,11 @@ int32_t lsm6dsv16x_xl_offset_mg_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_offset_ x_ofs_usr.x_ofs_usr = 0xFFU; } - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_Z_OFS_USR, (uint8_t *)&z_ofs_usr, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_Y_OFS_USR, (uint8_t *)&y_ofs_usr, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_X_OFS_USR, (uint8_t *)&x_ofs_usr, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_CTRL9, (uint8_t *)&ctrl9, 1); - } + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_Z_OFS_USR, (uint8_t *)&z_ofs_usr, 1); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_Y_OFS_USR, (uint8_t *)&y_ofs_usr, 1); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_X_OFS_USR, (uint8_t *)&x_ofs_usr, 1); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_CTRL9, (uint8_t *)&ctrl9, 1); + return ret; } @@ -304,7 +302,8 @@ int32_t lsm6dsv16x_xl_offset_mg_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_offset_ * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_xl_offset_mg_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_offset_mg_t *val) +int32_t lsm6dsv16x_xl_offset_mg_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_offset_mg_t *val) { lsm6dsv16x_z_ofs_usr_t z_ofs_usr; lsm6dsv16x_y_ofs_usr_t y_ofs_usr; @@ -313,24 +312,21 @@ int32_t lsm6dsv16x_xl_offset_mg_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_offset_ int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL9, (uint8_t *)&ctrl9, 1); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_Z_OFS_USR, (uint8_t *)&z_ofs_usr, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_Y_OFS_USR, (uint8_t *)&y_ofs_usr, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_X_OFS_USR, (uint8_t *)&x_ofs_usr, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_Z_OFS_USR, (uint8_t *)&z_ofs_usr, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_Y_OFS_USR, (uint8_t *)&y_ofs_usr, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_X_OFS_USR, (uint8_t *)&x_ofs_usr, 1); + if (ret != 0) { + return ret; } if (ctrl9.usr_off_w == PROPERTY_DISABLE) { - val->z_mg = ((float)z_ofs_usr.z_ofs_usr * 0.0078125f); - val->y_mg = ((float)y_ofs_usr.y_ofs_usr * 0.0078125f); - val->x_mg = ((float)x_ofs_usr.x_ofs_usr * 0.0078125f); + val->z_mg = ((float_t)z_ofs_usr.z_ofs_usr * 0.0078125f); + val->y_mg = ((float_t)y_ofs_usr.y_ofs_usr * 0.0078125f); + val->x_mg = ((float_t)x_ofs_usr.x_ofs_usr * 0.0078125f); } else { - val->z_mg = ((float)z_ofs_usr.z_ofs_usr * 0.125f); - val->y_mg = ((float)y_ofs_usr.y_ofs_usr * 0.125f); - val->x_mg = ((float)x_ofs_usr.x_ofs_usr * 0.125f); + val->z_mg = ((float_t)z_ofs_usr.z_ofs_usr * 0.125f); + val->y_mg = ((float_t)y_ofs_usr.y_ofs_usr * 0.125f); + val->x_mg = ((float_t)x_ofs_usr.x_ofs_usr * 0.125f); } return ret; @@ -356,20 +352,17 @@ int32_t lsm6dsv16x_reset_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_reset_t val) int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL3, (uint8_t *)&ctrl3, 1); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FUNC_CFG_ACCESS, (uint8_t *)&func_cfg_access, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FUNC_CFG_ACCESS, (uint8_t *)&func_cfg_access, 1); + if (ret != 0) { + return ret; } ctrl3.boot = ((uint8_t)val & 0x04U) >> 2; ctrl3.sw_reset = ((uint8_t)val & 0x02U) >> 1; func_cfg_access.sw_por = (uint8_t)val & 0x01U; - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_CTRL3, (uint8_t *)&ctrl3, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FUNC_CFG_ACCESS, (uint8_t *)&func_cfg_access, 1); - } + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_CTRL3, (uint8_t *)&ctrl3, 1); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FUNC_CFG_ACCESS, (uint8_t *)&func_cfg_access, 1); return ret; } @@ -389,8 +382,9 @@ int32_t lsm6dsv16x_reset_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_reset_t *val) int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL3, (uint8_t *)&ctrl3, 1); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FUNC_CFG_ACCESS, (uint8_t *)&func_cfg_access, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FUNC_CFG_ACCESS, (uint8_t *)&func_cfg_access, 1); + if (ret != 0) { + return ret; } switch ((ctrl3.sw_reset << 2) + (ctrl3.boot << 1) + func_cfg_access.sw_por) { @@ -414,6 +408,7 @@ int32_t lsm6dsv16x_reset_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_reset_t *val) *val = LSM6DSV16X_GLOBAL_RST; break; } + return ret; } @@ -431,13 +426,14 @@ int32_t lsm6dsv16x_mem_bank_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mem_bank_t val int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FUNC_CFG_ACCESS, (uint8_t *)&func_cfg_access, 1); - - if (ret == 0) { - func_cfg_access.shub_reg_access = ((uint8_t)val & 0x02U) >> 1; - func_cfg_access.emb_func_reg_access = (uint8_t)val & 0x01U; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FUNC_CFG_ACCESS, (uint8_t *)&func_cfg_access, 1); + if (ret != 0) { + return ret; } + func_cfg_access.shub_reg_access = ((uint8_t)val & 0x02U) >> 1; + func_cfg_access.emb_func_reg_access = (uint8_t)val & 0x01U; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FUNC_CFG_ACCESS, (uint8_t *)&func_cfg_access, 1); + return ret; } @@ -455,6 +451,9 @@ int32_t lsm6dsv16x_mem_bank_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mem_bank_t *va int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FUNC_CFG_ACCESS, (uint8_t *)&func_cfg_access, 1); + if (ret != 0) { + return ret; + } switch ((func_cfg_access.shub_reg_access << 1) + func_cfg_access.emb_func_reg_access) { case LSM6DSV16X_MAIN_MEM_BANK: @@ -473,6 +472,7 @@ int32_t lsm6dsv16x_mem_bank_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mem_bank_t *va *val = LSM6DSV16X_MAIN_MEM_BANK; break; } + return ret; } @@ -498,19 +498,34 @@ int32_t lsm6dsv16x_device_id_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) * @brief Accelerometer output data rate (ODR) selection.[set] * * @param ctx read / write interface definitions - * @param val XL_ODR_OFF, XL_ODR_AT_1Hz875, XL_ODR_AT_7Hz5, XL_ODR_AT_15Hz, XL_ODR_AT_30Hz, XL_ODR_AT_60Hz, XL_ODR_AT_120Hz, XL_ODR_AT_240Hz, XL_ODR_AT_480Hz, XL_ODR_AT_960Hz, XL_ODR_AT_1920Hz, XL_ODR_AT_3840Hz, XL_ODR_AT_7680Hz, + * @param val lsm6dsv16x_data_rate_t enum * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_xl_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_data_rate_t val) +int32_t lsm6dsv16x_xl_data_rate_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_data_rate_t val) { lsm6dsv16x_ctrl1_t ctrl1; + lsm6dsv16x_haodr_cfg_t haodr; + uint8_t sel; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL1, (uint8_t *)&ctrl1, 1); - if (ret == 0) { - ctrl1.odr_xl = (uint8_t)val & 0x0Fu; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_CTRL1, (uint8_t *)&ctrl1, 1); + if (ret != 0) { + return ret; + } + + ctrl1.odr_xl = (uint8_t)val & 0x0Fu; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_CTRL1, (uint8_t *)&ctrl1, 1); + if (ret != 0) { + return ret; + } + + sel = ((uint8_t)val >> 4) & 0xFU; + if (sel != 0U) { + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_HAODR_CFG, (uint8_t *)&haodr, 1); + haodr.haodr_sel = sel; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_HAODR_CFG, (uint8_t *)&haodr, 1); } return ret; @@ -520,74 +535,194 @@ int32_t lsm6dsv16x_xl_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_data_ra * @brief Accelerometer output data rate (ODR) selection.[get] * * @param ctx read / write interface definitions - * @param val XL_ODR_OFF, XL_ODR_AT_1Hz875, XL_ODR_AT_7Hz5, XL_ODR_AT_15Hz, XL_ODR_AT_30Hz, XL_ODR_AT_60Hz, XL_ODR_AT_120Hz, XL_ODR_AT_240Hz, XL_ODR_AT_480Hz, XL_ODR_AT_960Hz, XL_ODR_AT_1920Hz, XL_ODR_AT_3840Hz, XL_ODR_AT_7680Hz, + * @param val lsm6dsv16x_data_rate_t enum * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_xl_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_data_rate_t *val) +int32_t lsm6dsv16x_xl_data_rate_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_data_rate_t *val) { lsm6dsv16x_ctrl1_t ctrl1; + lsm6dsv16x_haodr_cfg_t haodr; + uint8_t sel; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL1, (uint8_t *)&ctrl1, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_HAODR_CFG, (uint8_t *)&haodr, 1); + if (ret != 0) { + return ret; + } + + sel = haodr.haodr_sel; switch (ctrl1.odr_xl) { - case LSM6DSV16X_XL_ODR_OFF: - *val = LSM6DSV16X_XL_ODR_OFF; + case LSM6DSV16X_ODR_OFF: + *val = LSM6DSV16X_ODR_OFF; break; - case LSM6DSV16X_XL_ODR_AT_1Hz875: - *val = LSM6DSV16X_XL_ODR_AT_1Hz875; + case LSM6DSV16X_ODR_AT_1Hz875: + *val = LSM6DSV16X_ODR_AT_1Hz875; break; - case LSM6DSV16X_XL_ODR_AT_7Hz5: - *val = LSM6DSV16X_XL_ODR_AT_7Hz5; + case LSM6DSV16X_ODR_AT_7Hz5: + *val = LSM6DSV16X_ODR_AT_7Hz5; break; - case LSM6DSV16X_XL_ODR_AT_15Hz: - *val = LSM6DSV16X_XL_ODR_AT_15Hz; + case LSM6DSV16X_ODR_AT_15Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_15Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_15Hz625; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_12Hz5; + break; + } break; - case LSM6DSV16X_XL_ODR_AT_30Hz: - *val = LSM6DSV16X_XL_ODR_AT_30Hz; + case LSM6DSV16X_ODR_AT_30Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_30Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_31Hz25; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_25Hz; + break; + } break; - case LSM6DSV16X_XL_ODR_AT_60Hz: - *val = LSM6DSV16X_XL_ODR_AT_60Hz; + case LSM6DSV16X_ODR_AT_60Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_60Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_62Hz5; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_50Hz; + break; + } break; - case LSM6DSV16X_XL_ODR_AT_120Hz: - *val = LSM6DSV16X_XL_ODR_AT_120Hz; + case LSM6DSV16X_ODR_AT_120Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_120Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_125Hz; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_100Hz; + break; + } break; - case LSM6DSV16X_XL_ODR_AT_240Hz: - *val = LSM6DSV16X_XL_ODR_AT_240Hz; + case LSM6DSV16X_ODR_AT_240Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_240Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_250Hz; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_200Hz; + break; + } break; - case LSM6DSV16X_XL_ODR_AT_480Hz: - *val = LSM6DSV16X_XL_ODR_AT_480Hz; + case LSM6DSV16X_ODR_AT_480Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_480Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_500Hz; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_400Hz; + break; + } break; - case LSM6DSV16X_XL_ODR_AT_960Hz: - *val = LSM6DSV16X_XL_ODR_AT_960Hz; + case LSM6DSV16X_ODR_AT_960Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_960Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_1000Hz; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_800Hz; + break; + } break; - case LSM6DSV16X_XL_ODR_AT_1920Hz: - *val = LSM6DSV16X_XL_ODR_AT_1920Hz; + case LSM6DSV16X_ODR_AT_1920Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_1920Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_2000Hz; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_1600Hz; + break; + } break; - case LSM6DSV16X_XL_ODR_AT_3840Hz: - *val = LSM6DSV16X_XL_ODR_AT_3840Hz; + case LSM6DSV16X_ODR_AT_3840Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_3840Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_4000Hz; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_3200Hz; + break; + } break; - case LSM6DSV16X_XL_ODR_AT_7680Hz: - *val = LSM6DSV16X_XL_ODR_AT_7680Hz; + case LSM6DSV16X_ODR_AT_7680Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_7680Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_8000Hz; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_6400Hz; + break; + } break; default: - *val = LSM6DSV16X_XL_ODR_OFF; + *val = LSM6DSV16X_ODR_OFF; break; } + return ret; } @@ -595,7 +730,7 @@ int32_t lsm6dsv16x_xl_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_data_ra * @brief Accelerometer operating mode selection.[set] * * @param ctx read / write interface definitions - * @param val XL_HIGH_PERFORMANCE_MD, XL_HIGH_ACCURANCY_ODR_MD, XL_LOW_POWER_2_AVG_MD, XL_LOW_POWER_4_AVG_MD, XL_LOW_POWER_8_AVG_MD, XL_NORMAL_MD, + * @param val XL_HIGH_PERFORMANCE_MD, XL_HIGH_ACCURACY_ODR_MD, XL_LOW_POWER_2_AVG_MD, XL_LOW_POWER_4_AVG_MD, XL_LOW_POWER_8_AVG_MD, XL_NORMAL_MD, * @retval interface status (MANDATORY: return 0 -> no Error) * */ @@ -618,7 +753,7 @@ int32_t lsm6dsv16x_xl_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_mode_t val) * @brief Accelerometer operating mode selection.[get] * * @param ctx read / write interface definitions - * @param val XL_HIGH_PERFORMANCE_MD, XL_HIGH_ACCURANCY_ODR_MD, XL_LOW_POWER_2_AVG_MD, XL_LOW_POWER_4_AVG_MD, XL_LOW_POWER_8_AVG_MD, XL_NORMAL_MD, + * @param val XL_HIGH_PERFORMANCE_MD, XL_HIGH_ACCURACY_ODR_MD, XL_LOW_POWER_2_AVG_MD, XL_LOW_POWER_4_AVG_MD, XL_LOW_POWER_8_AVG_MD, XL_NORMAL_MD, * @retval interface status (MANDATORY: return 0 -> no Error) * */ @@ -628,14 +763,21 @@ int32_t lsm6dsv16x_xl_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_mode_t *val) int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL1, (uint8_t *)&ctrl1, 1); + if (ret != 0) { + return ret; + } switch (ctrl1.op_mode_xl) { case LSM6DSV16X_XL_HIGH_PERFORMANCE_MD: *val = LSM6DSV16X_XL_HIGH_PERFORMANCE_MD; break; - case LSM6DSV16X_XL_HIGH_ACCURANCY_ODR_MD: - *val = LSM6DSV16X_XL_HIGH_ACCURANCY_ODR_MD; + case LSM6DSV16X_XL_HIGH_ACCURACY_ODR_MD: + *val = LSM6DSV16X_XL_HIGH_ACCURACY_ODR_MD; + break; + + case LSM6DSV16X_XL_ODR_TRIGGERED_MD: + *val = LSM6DSV16X_XL_ODR_TRIGGERED_MD; break; case LSM6DSV16X_XL_LOW_POWER_2_AVG_MD: @@ -658,6 +800,7 @@ int32_t lsm6dsv16x_xl_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_mode_t *val) *val = LSM6DSV16X_XL_HIGH_PERFORMANCE_MD; break; } + return ret; } @@ -665,20 +808,30 @@ int32_t lsm6dsv16x_xl_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_mode_t *val) * @brief Gyroscope output data rate (ODR) selection.[set] * * @param ctx read / write interface definitions - * @param val GY_ODR_OFF, GY_ODR_AT_7Hz5, GY_ODR_AT_15Hz, GY_ODR_AT_30Hz, GY_ODR_AT_60Hz, GY_ODR_AT_120Hz, GY_ODR_AT_240Hz, GY_ODR_AT_480Hz, GY_ODR_AT_960Hz, GY_ODR_AT_1920Hz, GY_ODR_AT_3840Hz, GY_ODR_AT_7680Hz, + * @param val lsm6dsv16x_data_rate_t enum * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_gy_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_data_rate_t val) +int32_t lsm6dsv16x_gy_data_rate_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_data_rate_t val) { lsm6dsv16x_ctrl2_t ctrl2; + lsm6dsv16x_haodr_cfg_t haodr; + uint8_t sel; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL2, (uint8_t *)&ctrl2, 1); + ctrl2.odr_g = (uint8_t)val & 0x0Fu; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_CTRL2, (uint8_t *)&ctrl2, 1); + if (ret != 0) { + return ret; + } - if (ret == 0) { - ctrl2.odr_g = (uint8_t)val & 0x0Fu; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_CTRL2, (uint8_t *)&ctrl2, 1); + sel = ((uint8_t)val >> 4) & 0xFU; + if (sel != 0U) { + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_HAODR_CFG, (uint8_t *)&haodr, 1); + haodr.haodr_sel = sel; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_HAODR_CFG, (uint8_t *)&haodr, 1); } return ret; @@ -688,70 +841,194 @@ int32_t lsm6dsv16x_gy_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_data_ra * @brief Gyroscope output data rate (ODR) selection.[get] * * @param ctx read / write interface definitions - * @param val GY_ODR_OFF, GY_ODR_AT_7Hz5, GY_ODR_AT_15Hz, GY_ODR_AT_30Hz, GY_ODR_AT_60Hz, GY_ODR_AT_120Hz, GY_ODR_AT_240Hz, GY_ODR_AT_480Hz, GY_ODR_AT_960Hz, GY_ODR_AT_1920Hz, GY_ODR_AT_3840Hz, GY_ODR_AT_7680Hz, + * @param val lsm6dsv16x_data_rate_t enum * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_gy_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_data_rate_t *val) +int32_t lsm6dsv16x_gy_data_rate_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_data_rate_t *val) { lsm6dsv16x_ctrl2_t ctrl2; + lsm6dsv16x_haodr_cfg_t haodr; + uint8_t sel; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL2, (uint8_t *)&ctrl2, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_HAODR_CFG, (uint8_t *)&haodr, 1); + if (ret != 0) { + return ret; + } + + sel = haodr.haodr_sel; switch (ctrl2.odr_g) { - case LSM6DSV16X_GY_ODR_OFF: - *val = LSM6DSV16X_GY_ODR_OFF; + case LSM6DSV16X_ODR_OFF: + *val = LSM6DSV16X_ODR_OFF; break; - case LSM6DSV16X_GY_ODR_AT_7Hz5: - *val = LSM6DSV16X_GY_ODR_AT_7Hz5; + case LSM6DSV16X_ODR_AT_1Hz875: + *val = LSM6DSV16X_ODR_AT_1Hz875; break; - case LSM6DSV16X_GY_ODR_AT_15Hz: - *val = LSM6DSV16X_GY_ODR_AT_15Hz; + case LSM6DSV16X_ODR_AT_7Hz5: + *val = LSM6DSV16X_ODR_AT_7Hz5; break; - case LSM6DSV16X_GY_ODR_AT_30Hz: - *val = LSM6DSV16X_GY_ODR_AT_30Hz; + case LSM6DSV16X_ODR_AT_15Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_15Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_15Hz625; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_12Hz5; + break; + } + break; + + case LSM6DSV16X_ODR_AT_30Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_30Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_31Hz25; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_25Hz; + break; + } break; - case LSM6DSV16X_GY_ODR_AT_60Hz: - *val = LSM6DSV16X_GY_ODR_AT_60Hz; + case LSM6DSV16X_ODR_AT_60Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_60Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_62Hz5; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_50Hz; + break; + } break; - case LSM6DSV16X_GY_ODR_AT_120Hz: - *val = LSM6DSV16X_GY_ODR_AT_120Hz; + case LSM6DSV16X_ODR_AT_120Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_120Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_125Hz; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_100Hz; + break; + } break; - case LSM6DSV16X_GY_ODR_AT_240Hz: - *val = LSM6DSV16X_GY_ODR_AT_240Hz; + case LSM6DSV16X_ODR_AT_240Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_240Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_250Hz; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_200Hz; + break; + } break; - case LSM6DSV16X_GY_ODR_AT_480Hz: - *val = LSM6DSV16X_GY_ODR_AT_480Hz; + case LSM6DSV16X_ODR_AT_480Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_480Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_500Hz; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_400Hz; + break; + } break; - case LSM6DSV16X_GY_ODR_AT_960Hz: - *val = LSM6DSV16X_GY_ODR_AT_960Hz; + case LSM6DSV16X_ODR_AT_960Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_960Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_1000Hz; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_800Hz; + break; + } break; - case LSM6DSV16X_GY_ODR_AT_1920Hz: - *val = LSM6DSV16X_GY_ODR_AT_1920Hz; + case LSM6DSV16X_ODR_AT_1920Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_1920Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_2000Hz; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_1600Hz; + break; + } break; - case LSM6DSV16X_GY_ODR_AT_3840Hz: - *val = LSM6DSV16X_GY_ODR_AT_3840Hz; + case LSM6DSV16X_ODR_AT_3840Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_3840Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_4000Hz; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_3200Hz; + break; + } break; - case LSM6DSV16X_GY_ODR_AT_7680Hz: - *val = LSM6DSV16X_GY_ODR_AT_7680Hz; + case LSM6DSV16X_ODR_AT_7680Hz: + switch (sel) { + default: + case 0: + *val = LSM6DSV16X_ODR_AT_7680Hz; + break; + case 1: + *val = LSM6DSV16X_ODR_HA01_AT_8000Hz; + break; + case 2: + *val = LSM6DSV16X_ODR_HA02_AT_6400Hz; + break; + } break; default: - *val = LSM6DSV16X_GY_ODR_OFF; + *val = LSM6DSV16X_ODR_OFF; break; } + return ret; } @@ -759,7 +1036,7 @@ int32_t lsm6dsv16x_gy_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_data_ra * @brief Gyroscope operating mode selection.[set] * * @param ctx read / write interface definitions - * @param val GY_HIGH_PERFORMANCE_MD, GY_HIGH_ACCURANCY_ODR_MD, GY_SLEEP_MD, GY_LOW_POWER_MD, + * @param val GY_HIGH_PERFORMANCE_MD, GY_HIGH_ACCURACY_ODR_MD, GY_SLEEP_MD, GY_LOW_POWER_MD, * @retval interface status (MANDATORY: return 0 -> no Error) * */ @@ -781,7 +1058,7 @@ int32_t lsm6dsv16x_gy_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_mode_t val) * @brief Gyroscope operating mode selection.[get] * * @param ctx read / write interface definitions - * @param val GY_HIGH_PERFORMANCE_MD, GY_HIGH_ACCURANCY_ODR_MD, GY_SLEEP_MD, GY_LOW_POWER_MD, + * @param val GY_HIGH_PERFORMANCE_MD, GY_HIGH_ACCURACY_ODR_MD, GY_SLEEP_MD, GY_LOW_POWER_MD, * @retval interface status (MANDATORY: return 0 -> no Error) * */ @@ -791,13 +1068,17 @@ int32_t lsm6dsv16x_gy_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_mode_t *val) int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL2, (uint8_t *)&ctrl2, 1); + if (ret != 0) { + return ret; + } + switch (ctrl2.op_mode_g) { case LSM6DSV16X_GY_HIGH_PERFORMANCE_MD: *val = LSM6DSV16X_GY_HIGH_PERFORMANCE_MD; break; - case LSM6DSV16X_GY_HIGH_ACCURANCY_ODR_MD: - *val = LSM6DSV16X_GY_HIGH_ACCURANCY_ODR_MD; + case LSM6DSV16X_GY_HIGH_ACCURACY_ODR_MD: + *val = LSM6DSV16X_GY_HIGH_ACCURACY_ODR_MD; break; case LSM6DSV16X_GY_SLEEP_MD: @@ -812,6 +1093,7 @@ int32_t lsm6dsv16x_gy_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_mode_t *val) *val = LSM6DSV16X_GY_HIGH_PERFORMANCE_MD; break; } + return ret; } @@ -853,7 +1135,6 @@ int32_t lsm6dsv16x_auto_increment_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL3, (uint8_t *)&ctrl3, 1); *val = ctrl3.if_inc; - return ret; } @@ -899,6 +1180,52 @@ int32_t lsm6dsv16x_block_data_update_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) return ret; } +/** + * @brief Configure ODR trigger. [set] + * + * @param ctx read / write interface definitions + * @param val number of data in the reference period. + * @retval interface status (MANDATORY: return 0 -> no Error) + * + */ +int32_t lsm6dsv16x_odr_trig_cfg_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) +{ + lsm6dsv16x_odr_trig_cfg_t odr_trig; + int32_t ret; + + if (val >= 1U && val <= 3U) { + return -1; + } + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_ODR_TRIG_CFG, (uint8_t *)&odr_trig, 1); + + if (ret == 0) { + odr_trig.odr_trig_nodr = val; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_ODR_TRIG_CFG, (uint8_t *)&odr_trig, 1); + } + + return ret; +} + +/** + * @brief Configure ODR trigger. [get] + * + * @param ctx read / write interface definitions + * @param val number of data in the reference period. + * @retval interface status (MANDATORY: return 0 -> no Error) + * + */ +int32_t lsm6dsv16x_odr_trig_cfg_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) +{ + lsm6dsv16x_odr_trig_cfg_t odr_trig; + int32_t ret; + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_ODR_TRIG_CFG, (uint8_t *)&odr_trig, 1); + *val = odr_trig.odr_trig_nodr; + + return ret; +} + /** * @brief Enables pulsed data-ready mode (~75 us).[set] * @@ -907,7 +1234,8 @@ int32_t lsm6dsv16x_block_data_update_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_data_ready_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_data_ready_mode_t val) +int32_t lsm6dsv16x_data_ready_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_data_ready_mode_t val) { lsm6dsv16x_ctrl4_t ctrl4; int32_t ret; @@ -930,7 +1258,8 @@ int32_t lsm6dsv16x_data_ready_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_data_re * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_data_ready_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_data_ready_mode_t *val) +int32_t lsm6dsv16x_data_ready_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_data_ready_mode_t *val) { lsm6dsv16x_ctrl4_t ctrl4; int32_t ret; @@ -950,6 +1279,63 @@ int32_t lsm6dsv16x_data_ready_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_data_re *val = LSM6DSV16X_DRDY_LATCHED; break; } + + return ret; +} + +/** + * @brief Enables interrupt.[set] + * + * @param ctx read / write interface definitions + * @param val enable/disable, latched/pulsed + * @retval interface status (MANDATORY: return 0 -> no Error) + * + */ +int32_t lsm6dsv16x_interrupt_enable_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_interrupt_mode_t val) +{ + lsm6dsv16x_tap_cfg0_t cfg; + lsm6dsv16x_functions_enable_t func; + int32_t ret; + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FUNCTIONS_ENABLE, (uint8_t *)&func, 1); + func.interrupts_enable = val.enable; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FUNCTIONS_ENABLE, (uint8_t *)&func, 1); + if (ret != 0) { + return ret; + } + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG0, (uint8_t *)&cfg, 1); + cfg.lir = val.lir; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_TAP_CFG0, (uint8_t *)&cfg, 1); + + return ret; +} + +/** + * @brief Enables latched interrupt mode.[get] + * + * @param ctx read / write interface definitions + * @param val enable/disable, latched/pulsed + * @retval interface status (MANDATORY: return 0 -> no Error) + * + */ +int32_t lsm6dsv16x_interrupt_enable_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_interrupt_mode_t *val) +{ + lsm6dsv16x_tap_cfg0_t cfg; + lsm6dsv16x_functions_enable_t func; + int32_t ret; + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FUNCTIONS_ENABLE, (uint8_t *)&func, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG0, (uint8_t *)&cfg, 1); + if (ret != 0) { + return ret; + } + + val->enable = func.interrupts_enable; + val->lir = cfg.lir; + return ret; } @@ -961,7 +1347,8 @@ int32_t lsm6dsv16x_data_ready_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_data_re * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_gy_full_scale_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_full_scale_t val) +int32_t lsm6dsv16x_gy_full_scale_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_gy_full_scale_t val) { lsm6dsv16x_ctrl6_t ctrl6; int32_t ret; @@ -984,12 +1371,16 @@ int32_t lsm6dsv16x_gy_full_scale_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_full_s * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_gy_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_full_scale_t *val) +int32_t lsm6dsv16x_gy_full_scale_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_gy_full_scale_t *val) { lsm6dsv16x_ctrl6_t ctrl6; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL6, (uint8_t *)&ctrl6, 1); + if (ret != 0) { + return ret; + } switch (ctrl6.fs_g) { case LSM6DSV16X_125dps: @@ -1020,6 +1411,7 @@ int32_t lsm6dsv16x_gy_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_full_s *val = LSM6DSV16X_125dps; break; } + return ret; } @@ -1031,7 +1423,8 @@ int32_t lsm6dsv16x_gy_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_full_s * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_xl_full_scale_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_full_scale_t val) +int32_t lsm6dsv16x_xl_full_scale_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_full_scale_t val) { lsm6dsv16x_ctrl8_t ctrl8; int32_t ret; @@ -1054,12 +1447,16 @@ int32_t lsm6dsv16x_xl_full_scale_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_full_s * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_xl_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_full_scale_t *val) +int32_t lsm6dsv16x_xl_full_scale_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_full_scale_t *val) { lsm6dsv16x_ctrl8_t ctrl8; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL8, (uint8_t *)&ctrl8, 1); + if (ret != 0) { + return ret; + } switch (ctrl8.fs_xl) { case LSM6DSV16X_2g: @@ -1082,6 +1479,7 @@ int32_t lsm6dsv16x_xl_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_full_s *val = LSM6DSV16X_2g; break; } + return ret; } @@ -1135,7 +1533,8 @@ int32_t lsm6dsv16x_xl_dual_channel_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_xl_self_test_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_self_test_t val) +int32_t lsm6dsv16x_xl_self_test_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_self_test_t val) { lsm6dsv16x_ctrl10_t ctrl10; int32_t ret; @@ -1158,12 +1557,16 @@ int32_t lsm6dsv16x_xl_self_test_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_self_te * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_xl_self_test_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_self_test_t *val) +int32_t lsm6dsv16x_xl_self_test_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_self_test_t *val) { lsm6dsv16x_ctrl10_t ctrl10; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL10, (uint8_t *)&ctrl10, 1); + if (ret != 0) { + return ret; + } switch (ctrl10.st_xl) { case LSM6DSV16X_XL_ST_DISABLE: @@ -1182,6 +1585,7 @@ int32_t lsm6dsv16x_xl_self_test_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_self_te *val = LSM6DSV16X_XL_ST_DISABLE; break; } + return ret; } @@ -1193,7 +1597,8 @@ int32_t lsm6dsv16x_xl_self_test_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_self_te * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_gy_self_test_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_self_test_t val) +int32_t lsm6dsv16x_gy_self_test_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_gy_self_test_t val) { lsm6dsv16x_ctrl10_t ctrl10; int32_t ret; @@ -1216,12 +1621,16 @@ int32_t lsm6dsv16x_gy_self_test_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_self_te * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_gy_self_test_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_self_test_t *val) +int32_t lsm6dsv16x_gy_self_test_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_gy_self_test_t *val) { lsm6dsv16x_ctrl10_t ctrl10; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL10, (uint8_t *)&ctrl10, 1); + if (ret != 0) { + return ret; + } switch (ctrl10.st_g) { case LSM6DSV16X_GY_ST_DISABLE: @@ -1240,6 +1649,7 @@ int32_t lsm6dsv16x_gy_self_test_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_self_te *val = LSM6DSV16X_GY_ST_DISABLE; break; } + return ret; } @@ -1251,7 +1661,8 @@ int32_t lsm6dsv16x_gy_self_test_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_self_te * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ois_xl_self_test_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_xl_self_test_t val) +int32_t lsm6dsv16x_ois_xl_self_test_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_xl_self_test_t val) { lsm6dsv16x_spi2_int_ois_t spi2_int_ois; int32_t ret; @@ -1274,12 +1685,16 @@ int32_t lsm6dsv16x_ois_xl_self_test_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_xl * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ois_xl_self_test_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_xl_self_test_t *val) +int32_t lsm6dsv16x_ois_xl_self_test_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_xl_self_test_t *val) { lsm6dsv16x_spi2_int_ois_t spi2_int_ois; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SPI2_INT_OIS, (uint8_t *)&spi2_int_ois, 1); + if (ret != 0) { + return ret; + } switch (spi2_int_ois.st_xl_ois) { case LSM6DSV16X_OIS_XL_ST_DISABLE: @@ -1298,6 +1713,7 @@ int32_t lsm6dsv16x_ois_xl_self_test_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_xl *val = LSM6DSV16X_OIS_XL_ST_DISABLE; break; } + return ret; } @@ -1309,7 +1725,8 @@ int32_t lsm6dsv16x_ois_xl_self_test_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_xl * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ois_gy_self_test_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_gy_self_test_t val) +int32_t lsm6dsv16x_ois_gy_self_test_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_gy_self_test_t val) { lsm6dsv16x_spi2_int_ois_t spi2_int_ois; int32_t ret; @@ -1333,12 +1750,16 @@ int32_t lsm6dsv16x_ois_gy_self_test_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_gy * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ois_gy_self_test_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_gy_self_test_t *val) +int32_t lsm6dsv16x_ois_gy_self_test_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_gy_self_test_t *val) { lsm6dsv16x_spi2_int_ois_t spi2_int_ois; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SPI2_INT_OIS, (uint8_t *)&spi2_int_ois, 1); + if (ret != 0) { + return ret; + } switch (spi2_int_ois.st_g_ois) { case LSM6DSV16X_OIS_GY_ST_DISABLE: @@ -1357,9 +1778,217 @@ int32_t lsm6dsv16x_ois_gy_self_test_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_gy *val = LSM6DSV16X_OIS_GY_ST_DISABLE; break; } + + return ret; +} + +/** + * @defgroup interrupt_pins + * @brief This section groups all the functions that manage + * interrupt pins + * @{ + * + */ + +/** + * @brief Select the signal that need to route on int1 pad[set] + * + * @param ctx Read / write interface definitions.(ptr) + * @param val the signals to route on int1 pin. + * @retval Interface status (MANDATORY: return 0 -> no Error). + * + */ +int32_t lsm6dsv16x_pin_int1_route_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_pin_int_route_t *val) +{ + lsm6dsv16x_int1_ctrl_t int1_ctrl; + lsm6dsv16x_md1_cfg_t md1_cfg; + int32_t ret; + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_INT1_CTRL, (uint8_t *)&int1_ctrl, 1); + if (ret != 0) { + return ret; + } + + int1_ctrl.int1_drdy_xl = val->drdy_xl; + int1_ctrl.int1_drdy_g = val->drdy_g; + int1_ctrl.int1_fifo_th = val->fifo_th; + int1_ctrl.int1_fifo_ovr = val->fifo_ovr; + int1_ctrl.int1_fifo_full = val->fifo_full; + int1_ctrl.int1_cnt_bdr = val->cnt_bdr; + + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_INT1_CTRL, (uint8_t *)&int1_ctrl, 1); + if (ret != 0) { + return ret; + } + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MD1_CFG, (uint8_t *)&md1_cfg, 1); + if (ret != 0) { + return ret; + } + + md1_cfg.int1_shub = val->shub; + md1_cfg.int1_emb_func = val->emb_func; + md1_cfg.int1_6d = val->sixd; + md1_cfg.int1_single_tap = val->single_tap; + md1_cfg.int1_double_tap = val->double_tap; + md1_cfg.int1_wu = val->wakeup; + md1_cfg.int1_ff = val->freefall; + md1_cfg.int1_sleep_change = val->sleep_change; + + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_MD1_CFG, (uint8_t *)&md1_cfg, 1); + + return ret; +} + +/** + * @brief Select the signal that need to route on int1 pad.[get] + * + * @param ctx Read / write interface definitions.(ptr) + * @param val the signals that are routed on int1 pin.(ptr) + * @retval Interface status (MANDATORY: return 0 -> no Error). + * + */ +int32_t lsm6dsv16x_pin_int1_route_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_pin_int_route_t *val) +{ + lsm6dsv16x_int1_ctrl_t int1_ctrl; + lsm6dsv16x_md1_cfg_t md1_cfg; + int32_t ret; + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_INT1_CTRL, (uint8_t *)&int1_ctrl, 1); + if (ret != 0) { + return ret; + } + + val->drdy_xl = int1_ctrl.int1_drdy_xl; + val->drdy_g = int1_ctrl.int1_drdy_g; + val->fifo_th = int1_ctrl.int1_fifo_th; + val->fifo_ovr = int1_ctrl.int1_fifo_ovr; + val->fifo_full = int1_ctrl.int1_fifo_full; + val->cnt_bdr = int1_ctrl.int1_cnt_bdr; + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MD1_CFG, (uint8_t *)&md1_cfg, 1); + if (ret != 0) { + return ret; + } + + val->shub = md1_cfg.int1_shub; + val->emb_func = md1_cfg.int1_emb_func; + val->sixd = md1_cfg.int1_6d; + val->single_tap = md1_cfg.int1_single_tap; + val->double_tap = md1_cfg.int1_double_tap; + val->wakeup = md1_cfg.int1_wu; + val->freefall = md1_cfg.int1_ff; + val->sleep_change = md1_cfg.int1_sleep_change; + + return ret; +} + +/** + * @brief Select the signal that need to route on int2 pad[set] + * + * @param ctx Read / write interface definitions.(ptr) + * @param val the signals to route on int1 pin. + * @retval Interface status (MANDATORY: return 0 -> no Error). + * + */ +int32_t lsm6dsv16x_pin_int2_route_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_pin_int_route_t *val) +{ + lsm6dsv16x_int2_ctrl_t int2_ctrl; + lsm6dsv16x_md2_cfg_t md2_cfg; + int32_t ret; + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_INT2_CTRL, (uint8_t *)&int2_ctrl, 1); + if (ret != 0) { + return ret; + } + + int2_ctrl.int2_drdy_xl = val->drdy_xl; + int2_ctrl.int2_drdy_g = val->drdy_g; + int2_ctrl.int2_fifo_th = val->fifo_th; + int2_ctrl.int2_fifo_ovr = val->fifo_ovr; + int2_ctrl.int2_fifo_full = val->fifo_full; + int2_ctrl.int2_cnt_bdr = val->cnt_bdr; + int2_ctrl.int2_drdy_g_eis = val->drdy_g_eis; + int2_ctrl.int2_emb_func_endop = val->emb_func_endop; + + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_INT2_CTRL, (uint8_t *)&int2_ctrl, 1); + if (ret != 0) { + return ret; + } + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MD2_CFG, (uint8_t *)&md2_cfg, 1); + if (ret != 0) { + return ret; + } + + md2_cfg.int2_timestamp = val->timestamp; + md2_cfg.int2_emb_func = val->emb_func; + md2_cfg.int2_6d = val->sixd; + md2_cfg.int2_single_tap = val->single_tap; + md2_cfg.int2_double_tap = val->double_tap; + md2_cfg.int2_wu = val->wakeup; + md2_cfg.int2_ff = val->freefall; + md2_cfg.int2_sleep_change = val->sleep_change; + + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_MD2_CFG, (uint8_t *)&md2_cfg, 1); + + return ret; +} + +/** + * @brief Select the signal that need to route on int2 pad.[get] + * + * @param ctx Read / write interface definitions.(ptr) + * @param val the signals that are routed on int1 pin.(ptr) + * @retval Interface status (MANDATORY: return 0 -> no Error). + * + */ +int32_t lsm6dsv16x_pin_int2_route_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_pin_int_route_t *val) +{ + lsm6dsv16x_int2_ctrl_t int2_ctrl; + lsm6dsv16x_md2_cfg_t md2_cfg; + int32_t ret; + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_INT2_CTRL, (uint8_t *)&int2_ctrl, 1); + if (ret != 0) { + return ret; + } + + val->drdy_xl = int2_ctrl.int2_drdy_xl; + val->drdy_g = int2_ctrl.int2_drdy_g; + val->fifo_th = int2_ctrl.int2_fifo_th; + val->fifo_ovr = int2_ctrl.int2_fifo_ovr; + val->fifo_full = int2_ctrl.int2_fifo_full; + val->cnt_bdr = int2_ctrl.int2_cnt_bdr; + val->drdy_g_eis = int2_ctrl.int2_drdy_g_eis; + val->emb_func_endop = int2_ctrl.int2_emb_func_endop; + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MD2_CFG, (uint8_t *)&md2_cfg, 1); + if (ret != 0) { + return ret; + } + + val->timestamp = md2_cfg.int2_timestamp; + val->emb_func = md2_cfg.int2_emb_func; + val->sixd = md2_cfg.int2_6d; + val->single_tap = md2_cfg.int2_single_tap; + val->double_tap = md2_cfg.int2_double_tap; + val->wakeup = md2_cfg.int2_wu; + val->freefall = md2_cfg.int2_ff; + val->sleep_change = md2_cfg.int2_sleep_change; + return ret; } +/** + * @} + * + */ + /** * @brief Get the status of all the interrupt sources.[get] * @@ -1368,7 +1997,8 @@ int32_t lsm6dsv16x_ois_gy_self_test_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_gy * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_all_sources_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_all_sources_t *val) +int32_t lsm6dsv16x_all_sources_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_all_sources_t *val) { lsm6dsv16x_emb_func_status_mainpage_t emb_func_status_mainpage; lsm6dsv16x_emb_func_exec_status_t emb_func_exec_status; @@ -1388,14 +2018,17 @@ int32_t lsm6dsv16x_all_sources_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_all_sources int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FUNCTIONS_ENABLE, (uint8_t *)&functions_enable, 1); - if (ret == 0) { - functions_enable.dis_rst_lir_all_int = PROPERTY_ENABLE; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FUNCTIONS_ENABLE, (uint8_t *)&functions_enable, 1); + functions_enable.dis_rst_lir_all_int = PROPERTY_ENABLE; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FUNCTIONS_ENABLE, (uint8_t *)&functions_enable, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FIFO_STATUS1, (uint8_t *)&buff, 4); + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FIFO_STATUS1, (uint8_t *)&buff, 4); + if (ret != 0) { + return ret; } + bytecpy((uint8_t *)&fifo_status2, &buff[1]); bytecpy((uint8_t *)&all_int_src, &buff[2]); bytecpy((uint8_t *)&status_reg, &buff[3]); @@ -1417,16 +2050,16 @@ int32_t lsm6dsv16x_all_sources_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_all_sources val->drdy_ois = status_reg.ois_drdy; val->timestamp = status_reg.timestamp_endcount; - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FUNCTIONS_ENABLE, (uint8_t *)&functions_enable, 1); - } - if (ret == 0) { - functions_enable.dis_rst_lir_all_int = PROPERTY_DISABLE; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FUNCTIONS_ENABLE, (uint8_t *)&functions_enable, 1); + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FUNCTIONS_ENABLE, (uint8_t *)&functions_enable, 1); + functions_enable.dis_rst_lir_all_int = PROPERTY_DISABLE; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FUNCTIONS_ENABLE, (uint8_t *)&functions_enable, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_UI_STATUS_REG_OIS, (uint8_t *)&buff, 8); + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_UI_STATUS_REG_OIS, (uint8_t *)&buff, 8); + if (ret != 0) { + return ret; } bytecpy((uint8_t *)&status_reg_ois, &buff[0]); @@ -1478,17 +2111,13 @@ int32_t lsm6dsv16x_all_sources_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_all_sources val->mlc4 = mlc_status_mainpage.is_mlc4; - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EXEC_STATUS, (uint8_t *)&emb_func_exec_status, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_SRC, (uint8_t *)&emb_func_src, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + /* embedded func */ + ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EXEC_STATUS, (uint8_t *)&emb_func_exec_status, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_SRC, (uint8_t *)&emb_func_src, 1); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + if (ret != 0) { + return ret; } val->emb_func_stand_by = emb_func_exec_status.emb_func_endop; @@ -1500,14 +2129,9 @@ int32_t lsm6dsv16x_all_sources_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_all_sources val->step_detector = emb_func_src.step_detected; /* sensor hub */ - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_STATUS_MASTER, (uint8_t *)&status_shub, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_STATUS_MASTER_MAINPAGE, (uint8_t *)&status_shub, 1); + if (ret != 0) { + return ret; } val->sh_endop = status_shub.sens_hub_endop; @@ -1520,6 +2144,24 @@ int32_t lsm6dsv16x_all_sources_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_all_sources return ret; } +int32_t lsm6dsv16x_flag_data_ready_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_data_ready_t *val) +{ + lsm6dsv16x_status_reg_t status; + int32_t ret; + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_STATUS_REG, (uint8_t *)&status, 1); + if (ret != 0) { + return ret; + } + + val->drdy_xl = status.xlda; + val->drdy_gy = status.gda; + val->drdy_temp = status.tda; + + return ret; +} + /** * @brief Mask status bit reset[set] * @@ -1568,6 +2210,10 @@ int32_t lsm6dsv16x_temperature_raw_get(lsm6dsv16x_ctx_t *ctx, int16_t *val) int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_OUT_TEMP_L, &buff[0], 2); + if (ret != 0) { + return ret; + } + *val = (int16_t)buff[1]; *val = (*val * 256) + (int16_t)buff[0]; @@ -1588,6 +2234,10 @@ int32_t lsm6dsv16x_angular_rate_raw_get(lsm6dsv16x_ctx_t *ctx, int16_t *val) int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_OUTX_L_G, &buff[0], 6); + if (ret != 0) { + return ret; + } + val[0] = (int16_t)buff[1]; val[0] = (val[0] * 256) + (int16_t)buff[0]; val[1] = (int16_t)buff[3]; @@ -1612,6 +2262,10 @@ int32_t lsm6dsv16x_ois_angular_rate_raw_get(lsm6dsv16x_ctx_t *ctx, int16_t *val) int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SPI2_OUTX_L_G_OIS, &buff[0], 6); + if (ret != 0) { + return ret; + } + val[0] = (int16_t)buff[1]; val[0] = (*val * 256) + (int16_t)buff[0]; val[1] = (int16_t)buff[3]; @@ -1636,6 +2290,10 @@ int32_t lsm6dsv16x_ois_eis_angular_rate_raw_get(lsm6dsv16x_ctx_t *ctx, int16_t * int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_UI_OUTX_L_G_OIS_EIS, &buff[0], 6); + if (ret != 0) { + return ret; + } + val[0] = (int16_t)buff[1]; val[0] = (*val * 256) + (int16_t)buff[0]; val[1] = (int16_t)buff[3]; @@ -1660,6 +2318,10 @@ int32_t lsm6dsv16x_acceleration_raw_get(lsm6dsv16x_ctx_t *ctx, int16_t *val) int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_OUTX_L_A, &buff[0], 6); + if (ret != 0) { + return ret; + } + val[0] = (int16_t)buff[1]; val[0] = (val[0] * 256) + (int16_t)buff[0]; val[1] = (int16_t)buff[3]; @@ -1684,6 +2346,10 @@ int32_t lsm6dsv16x_dual_acceleration_raw_get(lsm6dsv16x_ctx_t *ctx, int16_t *val int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_UI_OUTX_L_A_OIS_DUALC, &buff[0], 6); + if (ret != 0) { + return ret; + } + val[0] = (int16_t)buff[1]; val[0] = (val[0] * 256) + (int16_t)buff[0]; val[1] = (int16_t)buff[3]; @@ -1708,6 +2374,10 @@ int32_t lsm6dsv16x_ah_qvar_raw_get(lsm6dsv16x_ctx_t *ctx, int16_t *val) int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_AH_QVAR_OUT_L, &buff[0], 2); + if (ret != 0) { + return ret; + } + *val = (int16_t)buff[1]; *val = (*val * 256) + (int16_t)buff[0]; @@ -1741,7 +2411,8 @@ int32_t lsm6dsv16x_odr_cal_reg_get(lsm6dsv16x_ctx_t *ctx, int8_t *val) * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ln_pg_write(lsm6dsv16x_ctx_t *ctx, uint16_t address, uint8_t *buf, uint8_t len) +int32_t lsm6dsv16x_ln_pg_write(lsm6dsv16x_ctx_t *ctx, uint16_t address, + uint8_t *buf, uint8_t len) { lsm6dsv16x_page_address_t page_address; lsm6dsv16x_page_sel_t page_sel; @@ -1755,66 +2426,76 @@ int32_t lsm6dsv16x_ln_pg_write(lsm6dsv16x_ctx_t *ctx, uint16_t address, uint8_t lsb = (uint8_t)address & 0xFFU; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_RW, (uint8_t *)&page_rw, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - page_rw.page_read = PROPERTY_DISABLE; - page_rw.page_write = PROPERTY_ENABLE; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_RW, (uint8_t *)&page_rw, 1); + /* set page write */ + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_RW, (uint8_t *)&page_rw, 1); + page_rw.page_read = PROPERTY_DISABLE; + page_rw.page_write = PROPERTY_ENABLE; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_RW, (uint8_t *)&page_rw, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); - } - if (ret == 0) { - page_sel.page_sel = msb; - page_sel.not_used0 = 1; // Default value - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); + + /* select page */ + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); + page_sel.page_sel = msb; + page_sel.not_used0 = 1; // Default value + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - page_address.page_addr = lsb; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_ADDRESS, (uint8_t *)&page_address, 1); + + /* set page addr */ + page_address.page_addr = lsb; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_ADDRESS, + (uint8_t *)&page_address, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - for (i = 0; ((i < len) && (ret == 0)); i++) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_RW, &buf[i], 1); - lsb++; - - /* Check if page wrap */ - if (((lsb & 0xFFU) == 0x00U) && (ret == 0)) { - msb++; - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); - - if (ret == 0) { - page_sel.page_sel = msb; - page_sel.not_used0 = 1; // Default value - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); - } + for (i = 0; ((i < len) && (ret == 0)); i++) { + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_VALUE, &buf[i], 1); + if (ret != 0) { + goto exit; + } + + lsb++; + + /* Check if page wrap */ + if (((lsb & 0xFFU) == 0x00U) && (ret == 0)) { + msb++; + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); + if (ret != 0) { + goto exit; + } + + page_sel.page_sel = msb; + page_sel.not_used0 = 1; // Default value + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); + if (ret != 0) { + goto exit; } } } - if (ret == 0) { - page_sel.page_sel = 0; - page_sel.not_used0 = 1;// Default value - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); + page_sel.page_sel = 0; + page_sel.not_used0 = 1;// Default value + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_RW, (uint8_t *)&page_rw, 1); - } - if (ret == 0) { - page_rw.page_read = PROPERTY_DISABLE; - page_rw.page_write = PROPERTY_DISABLE; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_RW, (uint8_t *)&page_rw, 1); - } + /* unset page write */ + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_RW, (uint8_t *)&page_rw, 1); + page_rw.page_read = PROPERTY_DISABLE; + page_rw.page_write = PROPERTY_DISABLE; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_RW, (uint8_t *)&page_rw, 1); - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -1827,14 +2508,15 @@ int32_t lsm6dsv16x_ln_pg_write(lsm6dsv16x_ctx_t *ctx, uint16_t address, uint8_t */ /** - * @brief Write buffer in a page.[set] + * @brief Read buffer in a page.[set] * * @param ctx read / write interface definitions * @param val Write buffer in a page. * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ln_pg_read(lsm6dsv16x_ctx_t *ctx, uint16_t address, uint8_t *buf, uint8_t len) +int32_t lsm6dsv16x_ln_pg_read(lsm6dsv16x_ctx_t *ctx, uint16_t address, uint8_t *buf, + uint8_t len) { lsm6dsv16x_page_address_t page_address; lsm6dsv16x_page_sel_t page_sel; @@ -1848,67 +2530,123 @@ int32_t lsm6dsv16x_ln_pg_read(lsm6dsv16x_ctx_t *ctx, uint16_t address, uint8_t * lsb = (uint8_t)address & 0xFFU; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_RW, (uint8_t *)&page_rw, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - page_rw.page_read = PROPERTY_ENABLE; - page_rw.page_write = PROPERTY_DISABLE; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_RW, (uint8_t *)&page_rw, 1); + /* set page write */ + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_RW, (uint8_t *)&page_rw, 1); + page_rw.page_read = PROPERTY_ENABLE; + page_rw.page_write = PROPERTY_DISABLE; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_RW, (uint8_t *)&page_rw, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); - } - if (ret == 0) { - page_sel.page_sel = msb; - page_sel.not_used0 = 1; // Default value - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); + + /* select page */ + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); + page_sel.page_sel = msb; + page_sel.not_used0 = 1; // Default value + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - page_address.page_addr = lsb; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_ADDRESS, (uint8_t *)&page_address, 1); + + /* set page addr */ + page_address.page_addr = lsb; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_ADDRESS, + (uint8_t *)&page_address, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - for (i = 0; ((i < len) && (ret == 0)); i++) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_RW, &buf[i], 1); - lsb++; - - /* Check if page wrap */ - if (((lsb & 0xFFU) == 0x00U) && (ret == 0)) { - msb++; - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); - - if (ret == 0) { - page_sel.page_sel = msb; - page_sel.not_used0 = 1; // Default value - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); - } + for (i = 0; ((i < len) && (ret == 0)); i++) { + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_VALUE, &buf[i], 1); + if (ret != 0) { + goto exit; + } + + lsb++; + + /* Check if page wrap */ + if (((lsb & 0xFFU) == 0x00U) && (ret == 0)) { + msb++; + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); + if (ret != 0) { + goto exit; + } + + page_sel.page_sel = msb; + page_sel.not_used0 = 1; // Default value + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); + if (ret != 0) { + goto exit; } } } - if (ret == 0) { - page_sel.page_sel = 0; - page_sel.not_used0 = 1;// Default value - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); + page_sel.page_sel = 0; + page_sel.not_used0 = 1;// Default value + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_SEL, (uint8_t *)&page_sel, 1); + if (ret != 0) { + goto exit; } + /* unset page write */ + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_RW, (uint8_t *)&page_rw, 1); + page_rw.page_read = PROPERTY_DISABLE; + page_rw.page_write = PROPERTY_DISABLE; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_RW, (uint8_t *)&page_rw, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + + return ret; +} + +/** + * @brief Enable debug mode for embedded functions [set] + * + * @param ctx read / write interface definitions + * @param val 0, 1 + * @retval interface status (MANDATORY: return 0 -> no Error) + * + */ +int32_t lsm6dsv16x_emb_function_dbg_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) +{ + lsm6dsv16x_ctrl10_t ctrl10; + int32_t ret; + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL10, (uint8_t *)&ctrl10, 1); + if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PAGE_RW, (uint8_t *)&page_rw, 1); - } - if (ret == 0) { - page_rw.page_read = PROPERTY_DISABLE; - page_rw.page_write = PROPERTY_DISABLE; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_PAGE_RW, (uint8_t *)&page_rw, 1); + ctrl10.emb_func_debug = val; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_CTRL10, (uint8_t *)&ctrl10, 1); } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + return ret; +} + +/** + * @brief Enable debug mode for embedded functions [get] + * + * @param ctx read / write interface definitions + * @param val 0, 1 + * @retval interface status (MANDATORY: return 0 -> no Error) + * + */ +int32_t lsm6dsv16x_emb_function_dbg_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) +{ + lsm6dsv16x_ctrl10_t ctrl10; + int32_t ret; + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL10, (uint8_t *)&ctrl10, 1); + if (ret != 0) { + return ret; } + *val = ctrl10.emb_func_debug; + return ret; } @@ -1933,7 +2671,8 @@ int32_t lsm6dsv16x_ln_pg_read(lsm6dsv16x_ctx_t *ctx, uint16_t address, uint8_t * * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_den_polarity_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_den_polarity_t val) +int32_t lsm6dsv16x_den_polarity_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_den_polarity_t val) { lsm6dsv16x_ctrl4_t ctrl4; int32_t ret; @@ -1956,12 +2695,17 @@ int32_t lsm6dsv16x_den_polarity_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_den_polari * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_den_polarity_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_den_polarity_t *val) +int32_t lsm6dsv16x_den_polarity_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_den_polarity_t *val) { lsm6dsv16x_ctrl4_t ctrl4; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL4, (uint8_t *)&ctrl4, 1); + if (ret != 0) { + return ret; + } + switch (ctrl4.int2_in_lh) { case LSM6DSV16X_DEN_ACT_LOW: *val = LSM6DSV16X_DEN_ACT_LOW; @@ -1975,6 +2719,7 @@ int32_t lsm6dsv16x_den_polarity_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_den_polari *val = LSM6DSV16X_DEN_ACT_LOW; break; } + return ret; } @@ -1992,36 +2737,38 @@ int32_t lsm6dsv16x_den_conf_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_den_conf_t val int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_DEN, (uint8_t *)&den, 1); - if (ret == 0) { - den.den_z = val.den_z; - den.den_y = val.den_y; - den.den_x = val.den_x; - - den.lvl2_en = (uint8_t)val.mode & 0x1U; - den.lvl1_en = ((uint8_t)val.mode & 0x2U) >> 1; - - if (val.stamp_in_gy_data == PROPERTY_ENABLE && val.stamp_in_xl_data == PROPERTY_ENABLE) { - den.den_xl_g = PROPERTY_DISABLE; - den.den_xl_en = PROPERTY_ENABLE; - } else if (val.stamp_in_gy_data == PROPERTY_ENABLE && val.stamp_in_xl_data == PROPERTY_DISABLE) { - den.den_xl_g = PROPERTY_DISABLE; - den.den_xl_en = PROPERTY_DISABLE; - } else if (val.stamp_in_gy_data == PROPERTY_DISABLE && val.stamp_in_xl_data == PROPERTY_ENABLE) { - den.den_xl_g = PROPERTY_ENABLE; - den.den_xl_en = PROPERTY_DISABLE; - } else { - den.den_xl_g = PROPERTY_DISABLE; - den.den_xl_en = PROPERTY_DISABLE; - den.den_z = PROPERTY_DISABLE; - den.den_y = PROPERTY_DISABLE; - den.den_x = PROPERTY_DISABLE; - den.lvl2_en = PROPERTY_DISABLE; - den.lvl1_en = PROPERTY_DISABLE; - } - - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_DEN, (uint8_t *)&den, 1); + if (ret != 0) { + return ret; + } + + den.den_z = val.den_z; + den.den_y = val.den_y; + den.den_x = val.den_x; + + den.lvl2_en = (uint8_t)val.mode & 0x1U; + den.lvl1_en = ((uint8_t)val.mode & 0x2U) >> 1; + + if (val.stamp_in_gy_data == PROPERTY_ENABLE && val.stamp_in_xl_data == PROPERTY_ENABLE) { + den.den_xl_g = PROPERTY_DISABLE; + den.den_xl_en = PROPERTY_ENABLE; + } else if (val.stamp_in_gy_data == PROPERTY_ENABLE && val.stamp_in_xl_data == PROPERTY_DISABLE) { + den.den_xl_g = PROPERTY_DISABLE; + den.den_xl_en = PROPERTY_DISABLE; + } else if (val.stamp_in_gy_data == PROPERTY_DISABLE && val.stamp_in_xl_data == PROPERTY_ENABLE) { + den.den_xl_g = PROPERTY_ENABLE; + den.den_xl_en = PROPERTY_DISABLE; + } else { + den.den_xl_g = PROPERTY_DISABLE; + den.den_xl_en = PROPERTY_DISABLE; + den.den_z = PROPERTY_DISABLE; + den.den_y = PROPERTY_DISABLE; + den.den_x = PROPERTY_DISABLE; + den.lvl2_en = PROPERTY_DISABLE; + den.lvl1_en = PROPERTY_DISABLE; } + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_DEN, (uint8_t *)&den, 1); + return ret; } @@ -2040,6 +2787,9 @@ int32_t lsm6dsv16x_den_conf_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_den_conf_t *va int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_DEN, (uint8_t *)&den, 1); + if (ret != 0) { + return ret; + } val->den_z = den.den_z; val->den_y = den.den_y; @@ -2066,8 +2816,8 @@ int32_t lsm6dsv16x_den_conf_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_den_conf_t *va val->mode = LEVEL_TRIGGER; break; - case LEVEL_LETCHED: - val->mode = LEVEL_LETCHED; + case LEVEL_LATCHED: + val->mode = LEVEL_LATCHED; break; default: @@ -2098,7 +2848,8 @@ int32_t lsm6dsv16x_den_conf_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_den_conf_t *va * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_eis_gy_full_scale_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_eis_gy_full_scale_t val) +int32_t lsm6dsv16x_eis_gy_full_scale_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_eis_gy_full_scale_t val) { lsm6dsv16x_ctrl_eis_t ctrl_eis; int32_t ret; @@ -2121,12 +2872,16 @@ int32_t lsm6dsv16x_eis_gy_full_scale_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_eis_g * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_eis_gy_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_eis_gy_full_scale_t *val) +int32_t lsm6dsv16x_eis_gy_full_scale_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_eis_gy_full_scale_t *val) { lsm6dsv16x_ctrl_eis_t ctrl_eis; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL_EIS, (uint8_t *)&ctrl_eis, 1); + if (ret != 0) { + return ret; + } switch (ctrl_eis.fs_g_eis) { case LSM6DSV16X_EIS_125dps: @@ -2206,7 +2961,8 @@ int32_t lsm6dsv16x_eis_gy_on_spi2_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_gy_eis_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_eis_data_rate_t val) +int32_t lsm6dsv16x_gy_eis_data_rate_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_gy_eis_data_rate_t val) { lsm6dsv16x_ctrl_eis_t ctrl_eis; int32_t ret; @@ -2229,12 +2985,16 @@ int32_t lsm6dsv16x_gy_eis_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_eis * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_gy_eis_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_eis_data_rate_t *val) +int32_t lsm6dsv16x_gy_eis_data_rate_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_gy_eis_data_rate_t *val) { lsm6dsv16x_ctrl_eis_t ctrl_eis; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL_EIS, (uint8_t *)&ctrl_eis, 1); + if (ret != 0) { + return ret; + } switch (ctrl_eis.odr_g_eis) { case LSM6DSV16X_EIS_ODR_OFF: @@ -2253,6 +3013,7 @@ int32_t lsm6dsv16x_gy_eis_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_eis *val = LSM6DSV16X_EIS_1920Hz; break; } + return ret; } @@ -2348,7 +3109,6 @@ int32_t lsm6dsv16x_fifo_xl_dual_fsm_batch_get(lsm6dsv16x_ctx_t *ctx, uint8_t *va ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FIFO_CTRL2, (uint8_t *)&fifo_ctrl2, 1); *val = fifo_ctrl2.xl_dualc_batch_from_fsm; - return ret; } @@ -2360,7 +3120,8 @@ int32_t lsm6dsv16x_fifo_xl_dual_fsm_batch_get(lsm6dsv16x_ctx_t *ctx, uint8_t *va * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_compress_algo_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_compress_algo_t val) +int32_t lsm6dsv16x_fifo_compress_algo_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_compress_algo_t val) { lsm6dsv16x_fifo_ctrl2_t fifo_ctrl2; int32_t ret; @@ -2382,12 +3143,17 @@ int32_t lsm6dsv16x_fifo_compress_algo_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_compress_algo_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_compress_algo_t *val) +int32_t lsm6dsv16x_fifo_compress_algo_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_compress_algo_t *val) { lsm6dsv16x_fifo_ctrl2_t fifo_ctrl2; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FIFO_CTRL2, (uint8_t *)&fifo_ctrl2, 1); + if (ret != 0) { + return ret; + } + switch (fifo_ctrl2.uncompr_rate) { case LSM6DSV16X_CMP_DISABLE: *val = LSM6DSV16X_CMP_DISABLE; @@ -2442,7 +3208,8 @@ int32_t lsm6dsv16x_fifo_virtual_sens_odr_chg_set(lsm6dsv16x_ctx_t *ctx, uint8_t * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_virtual_sens_odr_chg_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) +int32_t lsm6dsv16x_fifo_virtual_sens_odr_chg_get(lsm6dsv16x_ctx_t *ctx, + uint8_t *val) { lsm6dsv16x_fifo_ctrl2_t fifo_ctrl2; int32_t ret; @@ -2461,7 +3228,8 @@ int32_t lsm6dsv16x_fifo_virtual_sens_odr_chg_get(lsm6dsv16x_ctx_t *ctx, uint8_t * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_compress_algo_real_time_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) +int32_t lsm6dsv16x_fifo_compress_algo_real_time_set(lsm6dsv16x_ctx_t *ctx, + uint8_t val) { lsm6dsv16x_emb_func_en_b_t emb_func_en_b; lsm6dsv16x_fifo_ctrl2_t fifo_ctrl2; @@ -2469,25 +3237,22 @@ int32_t lsm6dsv16x_fifo_compress_algo_real_time_set(lsm6dsv16x_ctx_t *ctx, uint8 int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FIFO_CTRL2, (uint8_t *)&fifo_ctrl2, 1); - if (ret == 0) { - fifo_ctrl2.fifo_compr_rt_en = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FIFO_CTRL2, (uint8_t *)&fifo_ctrl2, 1); + fifo_ctrl2.fifo_compr_rt_en = val; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FIFO_CTRL2, (uint8_t *)&fifo_ctrl2, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_B, (uint8_t *)&emb_func_en_b, 1); - } - if (ret == 0) { - emb_func_en_b.fifo_compr_en = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_B, (uint8_t *)&emb_func_en_b, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); + if (ret != 0) { + return ret; } + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_B, (uint8_t *)&emb_func_en_b, 1); + emb_func_en_b.fifo_compr_en = val; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_B, (uint8_t *)&emb_func_en_b, 1); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + return ret; } @@ -2499,7 +3264,8 @@ int32_t lsm6dsv16x_fifo_compress_algo_real_time_set(lsm6dsv16x_ctx_t *ctx, uint8 * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_compress_algo_real_time_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) +int32_t lsm6dsv16x_fifo_compress_algo_real_time_get(lsm6dsv16x_ctx_t *ctx, + uint8_t *val) { lsm6dsv16x_fifo_ctrl2_t fifo_ctrl2; int32_t ret; @@ -2560,7 +3326,8 @@ int32_t lsm6dsv16x_fifo_stop_on_wtm_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_xl_batch_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_xl_batch_t val) +int32_t lsm6dsv16x_fifo_xl_batch_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_xl_batch_t val) { lsm6dsv16x_fifo_ctrl3_t fifo_ctrl3; int32_t ret; @@ -2582,12 +3349,17 @@ int32_t lsm6dsv16x_fifo_xl_batch_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_xl_b * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_xl_batch_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_xl_batch_t *val) +int32_t lsm6dsv16x_fifo_xl_batch_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_xl_batch_t *val) { lsm6dsv16x_fifo_ctrl3_t fifo_ctrl3; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FIFO_CTRL3, (uint8_t *)&fifo_ctrl3, 1); + if (ret != 0) { + return ret; + } + switch (fifo_ctrl3.bdr_xl) { case LSM6DSV16X_XL_NOT_BATCHED: *val = LSM6DSV16X_XL_NOT_BATCHED; @@ -2645,6 +3417,7 @@ int32_t lsm6dsv16x_fifo_xl_batch_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_xl_b *val = LSM6DSV16X_XL_NOT_BATCHED; break; } + return ret; } @@ -2656,7 +3429,8 @@ int32_t lsm6dsv16x_fifo_xl_batch_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_xl_b * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_gy_batch_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_gy_batch_t val) +int32_t lsm6dsv16x_fifo_gy_batch_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_gy_batch_t val) { lsm6dsv16x_fifo_ctrl3_t fifo_ctrl3; int32_t ret; @@ -2678,12 +3452,17 @@ int32_t lsm6dsv16x_fifo_gy_batch_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_gy_b * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_gy_batch_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_gy_batch_t *val) +int32_t lsm6dsv16x_fifo_gy_batch_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_gy_batch_t *val) { lsm6dsv16x_fifo_ctrl3_t fifo_ctrl3; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FIFO_CTRL3, (uint8_t *)&fifo_ctrl3, 1); + if (ret != 0) { + return ret; + } + switch (fifo_ctrl3.bdr_gy) { case LSM6DSV16X_GY_NOT_BATCHED: *val = LSM6DSV16X_GY_NOT_BATCHED; @@ -2749,7 +3528,7 @@ int32_t lsm6dsv16x_fifo_gy_batch_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_gy_b * @brief FIFO mode selection.[set] * * @param ctx read / write interface definitions - * @param val BYPASS_MODE, FIFO_MODE, STREAM_TO_FIFO_MODE, BYPASS_TO_STREAM_MODE, STREAM_MODE, BYPASS_TO_FIFO_MODE, + * @param val BYPASS_MODE, FIFO_MODE, STREAM_WTM_TO_FULL_MODE, STREAM_TO_FIFO_MODE, BYPASS_TO_STREAM_MODE, STREAM_MODE, BYPASS_TO_FIFO_MODE, * @retval interface status (MANDATORY: return 0 -> no Error) * */ @@ -2771,7 +3550,7 @@ int32_t lsm6dsv16x_fifo_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_mode_t v * @brief FIFO mode selection.[get] * * @param ctx read / write interface definitions - * @param val BYPASS_MODE, FIFO_MODE, STREAM_TO_FIFO_MODE, BYPASS_TO_STREAM_MODE, STREAM_MODE, BYPASS_TO_FIFO_MODE, + * @param val BYPASS_MODE, FIFO_MODE, STREAM_WTM_TO_FULL_MODE, STREAM_TO_FIFO_MODE, BYPASS_TO_STREAM_MODE, STREAM_MODE, BYPASS_TO_FIFO_MODE, * @retval interface status (MANDATORY: return 0 -> no Error) * */ @@ -2781,6 +3560,10 @@ int32_t lsm6dsv16x_fifo_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_mode_t * int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FIFO_CTRL4, (uint8_t *)&fifo_ctrl4, 1); + if (ret != 0) { + return ret; + } + switch (fifo_ctrl4.fifo_mode) { case LSM6DSV16X_BYPASS_MODE: *val = LSM6DSV16X_BYPASS_MODE; @@ -2866,7 +3649,8 @@ int32_t lsm6dsv16x_fifo_gy_eis_batch_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_temp_batch_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_temp_batch_t val) +int32_t lsm6dsv16x_fifo_temp_batch_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_temp_batch_t val) { lsm6dsv16x_fifo_ctrl4_t fifo_ctrl4; int32_t ret; @@ -2888,12 +3672,17 @@ int32_t lsm6dsv16x_fifo_temp_batch_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_te * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_temp_batch_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_temp_batch_t *val) +int32_t lsm6dsv16x_fifo_temp_batch_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_temp_batch_t *val) { lsm6dsv16x_fifo_ctrl4_t fifo_ctrl4; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FIFO_CTRL4, (uint8_t *)&fifo_ctrl4, 1); + if (ret != 0) { + return ret; + } + switch (fifo_ctrl4.odr_t_batch) { case LSM6DSV16X_TEMP_NOT_BATCHED: *val = LSM6DSV16X_TEMP_NOT_BATCHED; @@ -2926,7 +3715,8 @@ int32_t lsm6dsv16x_fifo_temp_batch_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_te * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_timestamp_batch_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_timestamp_batch_t val) +int32_t lsm6dsv16x_fifo_timestamp_batch_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_timestamp_batch_t val) { lsm6dsv16x_fifo_ctrl4_t fifo_ctrl4; int32_t ret; @@ -2948,12 +3738,17 @@ int32_t lsm6dsv16x_fifo_timestamp_batch_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fi * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_timestamp_batch_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_timestamp_batch_t *val) +int32_t lsm6dsv16x_fifo_timestamp_batch_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_timestamp_batch_t *val) { lsm6dsv16x_fifo_ctrl4_t fifo_ctrl4; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FIFO_CTRL4, (uint8_t *)&fifo_ctrl4, 1); + if (ret != 0) { + return ret; + } + switch (fifo_ctrl4.dec_ts_batch) { case LSM6DSV16X_TMSTMP_NOT_BATCHED: *val = LSM6DSV16X_TMSTMP_NOT_BATCHED; @@ -2975,6 +3770,7 @@ int32_t lsm6dsv16x_fifo_timestamp_batch_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fi *val = LSM6DSV16X_TMSTMP_NOT_BATCHED; break; } + return ret; } @@ -2986,7 +3782,8 @@ int32_t lsm6dsv16x_fifo_timestamp_batch_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fi * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_batch_counter_threshold_set(lsm6dsv16x_ctx_t *ctx, uint16_t val) +int32_t lsm6dsv16x_fifo_batch_counter_threshold_set(lsm6dsv16x_ctx_t *ctx, + uint16_t val) { uint8_t buff[2]; int32_t ret; @@ -3006,12 +3803,17 @@ int32_t lsm6dsv16x_fifo_batch_counter_threshold_set(lsm6dsv16x_ctx_t *ctx, uint1 * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_batch_counter_threshold_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val) +int32_t lsm6dsv16x_fifo_batch_counter_threshold_get(lsm6dsv16x_ctx_t *ctx, + uint16_t *val) { uint8_t buff[2]; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_COUNTER_BDR_REG1, &buff[0], 2); + if (ret != 0) { + return ret; + } + *val = buff[1]; *val = (*val * 256U) + buff[0]; @@ -3026,7 +3828,8 @@ int32_t lsm6dsv16x_fifo_batch_counter_threshold_get(lsm6dsv16x_ctx_t *ctx, uint1 * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_batch_cnt_event_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_batch_cnt_event_t val) +int32_t lsm6dsv16x_fifo_batch_cnt_event_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_batch_cnt_event_t val) { lsm6dsv16x_counter_bdr_reg1_t counter_bdr_reg1; int32_t ret; @@ -3048,12 +3851,17 @@ int32_t lsm6dsv16x_fifo_batch_cnt_event_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fi * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_batch_cnt_event_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_batch_cnt_event_t *val) +int32_t lsm6dsv16x_fifo_batch_cnt_event_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_batch_cnt_event_t *val) { lsm6dsv16x_counter_bdr_reg1_t counter_bdr_reg1; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_COUNTER_BDR_REG1, (uint8_t *)&counter_bdr_reg1, 1); + if (ret != 0) { + return ret; + } + switch (counter_bdr_reg1.trig_counter_bdr) { case LSM6DSV16X_XL_BATCH_EVENT: *val = LSM6DSV16X_XL_BATCH_EVENT; @@ -3071,44 +3879,63 @@ int32_t lsm6dsv16x_fifo_batch_cnt_event_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fi *val = LSM6DSV16X_XL_BATCH_EVENT; break; } + return ret; } -/** - * @brief Number of unread sensor data (TAG + 6 bytes) stored in FIFO.[get] - * - * @param ctx read / write interface definitions - * @param val Number of unread sensor data (TAG + 6 bytes) stored in FIFO. - * @retval interface status (MANDATORY: return 0 -> no Error) - * - */ -int32_t lsm6dsv16x_fifo_data_level_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val) +int32_t lsm6dsv16x_fifo_status_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_status_t *val) { uint8_t buff[2]; + lsm6dsv16x_fifo_status2_t status; int32_t ret; - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FIFO_STATUS1, &buff[0], 2); - *val = (uint16_t)buff[1] & 0x01U; - *val = (*val * 256U) + buff[0]; + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FIFO_STATUS1, (uint8_t *)&buff[0], 2); + if (ret != 0) { + return ret; + } + + bytecpy((uint8_t *)&status, &buff[1]); + + val->fifo_bdr = status.counter_bdr_ia; + val->fifo_ovr = status.fifo_ovr_ia; + val->fifo_full = status.fifo_full_ia; + val->fifo_th = status.fifo_wtm_ia; + + val->fifo_level = (uint16_t)buff[1] & 0x01U; + val->fifo_level = (val->fifo_level * 256U) + buff[0]; return ret; } + /** * @brief FIFO data output[get] * * @param ctx read / write interface definitions - * @param val FIFO_EMPTY, GY_NC_TAG, XL_NC_TAG, TIMESTAMP_TAG, TEMPERATURE_TAG, CFG_CHANGE_TAG, XL_NC_T_2_TAG, XL_NC_T_1_TAG, XL_2XC_TAG, XL_3XC_TAG, GY_NC_T_2_TAG, GY_NC_T_1_TAG, GY_2XC_TAG, GY_3XC_TAG, SENSORHUB_SLAVE0_TAG, SENSORHUB_SLAVE1_TAG, SENSORHUB_SLAVE2_TAG, SENSORHUB_SLAVE3_TAG, STEP_CPUNTER_TAG, SENSORHUB_NACK_TAG, MLC_RESULT_TAG, MLC_FILTER, MLC_FEATURE, XL_DUAL_CORE, AH_QVAR, + * @param val FIFO_EMPTY, GY_NC_TAG, XL_NC_TAG, TIMESTAMP_TAG, + TEMPERATURE_TAG, CFG_CHANGE_TAG, XL_NC_T_2_TAG, + XL_NC_T_1_TAG, XL_2XC_TAG, XL_3XC_TAG, GY_NC_T_2_TAG, + GY_NC_T_1_TAG, GY_2XC_TAG, GY_3XC_TAG, SENSORHUB_SLAVE0_TAG, + SENSORHUB_SLAVE1_TAG, SENSORHUB_SLAVE2_TAG, SENSORHUB_SLAVE3_TAG, + STEP_COUNTER_TAG, SFLP_GAME_ROTATION_VECTOR_TAG, SFLP_GYROSCOPE_BIAS_TAG, + SFLP_GRAVITY_VECTOR_TAG, SENSORHUB_NACK_TAG, MLC_RESULT_TAG, + MLC_FILTER, MLC_FEATURE, XL_DUAL_CORE, GY_ENHANCED_EIS, * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_out_raw_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_out_raw_t *val) +int32_t lsm6dsv16x_fifo_out_raw_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_out_raw_t *val) { lsm6dsv16x_fifo_data_out_tag_t fifo_data_out_tag; uint8_t buff[7]; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FIFO_DATA_OUT_TAG, buff, 7); + if (ret != 0) { + return ret; + } + bytecpy((uint8_t *)&fifo_data_out_tag, &buff[0]); switch (fifo_data_out_tag.tag_sensor) { @@ -3184,8 +4011,20 @@ int32_t lsm6dsv16x_fifo_out_raw_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_out_r val->tag = LSM6DSV16X_SENSORHUB_SLAVE3_TAG; break; - case LSM6DSV16X_STEP_CPUNTER_TAG: - val->tag = LSM6DSV16X_STEP_CPUNTER_TAG; + case LSM6DSV16X_STEP_COUNTER_TAG: + val->tag = LSM6DSV16X_STEP_COUNTER_TAG; + break; + + case LSM6DSV16X_SFLP_GAME_ROTATION_VECTOR_TAG: + val->tag = LSM6DSV16X_SFLP_GAME_ROTATION_VECTOR_TAG; + break; + + case LSM6DSV16X_SFLP_GYROSCOPE_BIAS_TAG: + val->tag = LSM6DSV16X_SFLP_GYROSCOPE_BIAS_TAG; + break; + + case LSM6DSV16X_SFLP_GRAVITY_VECTOR_TAG: + val->tag = LSM6DSV16X_SFLP_GRAVITY_VECTOR_TAG; break; case LSM6DSV16X_SENSORHUB_NACK_TAG: @@ -3208,8 +4047,8 @@ int32_t lsm6dsv16x_fifo_out_raw_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_out_r val->tag = LSM6DSV16X_XL_DUAL_CORE; break; - case LSM6DSV16X_AH_QVAR: - val->tag = LSM6DSV16X_AH_QVAR; + case LSM6DSV16X_GY_ENHANCED_EIS: + val->tag = LSM6DSV16X_GY_ENHANCED_EIS; break; default: @@ -3243,17 +4082,15 @@ int32_t lsm6dsv16x_fifo_stpcnt_batch_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_A, (uint8_t *)&emb_func_fifo_en_a, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - emb_func_fifo_en_a.step_counter_fifo_en = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_A, (uint8_t *)&emb_func_fifo_en_a, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_A, (uint8_t *)&emb_func_fifo_en_a, 1); + emb_func_fifo_en_a.step_counter_fifo_en = val; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_A, (uint8_t *)&emb_func_fifo_en_a, 1); + + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -3272,15 +4109,14 @@ int32_t lsm6dsv16x_fifo_stpcnt_batch_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_A, (uint8_t *)&emb_func_fifo_en_a, 1); + if (ret != 0) { + return ret; } + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_A, (uint8_t *)&emb_func_fifo_en_a, 1); *val = emb_func_fifo_en_a.step_counter_fifo_en; - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -3299,17 +4135,15 @@ int32_t lsm6dsv16x_fifo_mlc_batch_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_A, (uint8_t *)&emb_func_fifo_en_a, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - emb_func_fifo_en_a.mlc_fifo_en = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_A, (uint8_t *)&emb_func_fifo_en_a, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_A, (uint8_t *)&emb_func_fifo_en_a, 1); + emb_func_fifo_en_a.mlc_fifo_en = val; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_A, (uint8_t *)&emb_func_fifo_en_a, 1); + + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -3328,15 +4162,14 @@ int32_t lsm6dsv16x_fifo_mlc_batch_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_A, (uint8_t *)&emb_func_fifo_en_a, 1); + if (ret != 0) { + return ret; } + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_A, (uint8_t *)&emb_func_fifo_en_a, 1); *val = emb_func_fifo_en_a.mlc_fifo_en; - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -3355,17 +4188,15 @@ int32_t lsm6dsv16x_fifo_mlc_filt_batch_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_B, (uint8_t *)&emb_func_fifo_en_b, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - emb_func_fifo_en_b.mlc_filter_feature_fifo_en = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_B, (uint8_t *)&emb_func_fifo_en_b, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_B, (uint8_t *)&emb_func_fifo_en_b, 1); + emb_func_fifo_en_b.mlc_filter_feature_fifo_en = val; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_B, (uint8_t *)&emb_func_fifo_en_b, 1); + + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -3384,293 +4215,184 @@ int32_t lsm6dsv16x_fifo_mlc_filt_batch_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_B, (uint8_t *)&emb_func_fifo_en_b, 1); + if (ret != 0) { + return ret; } + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_B, (uint8_t *)&emb_func_fifo_en_b, 1); *val = emb_func_fifo_en_b.mlc_filter_feature_fifo_en; - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } /** - * @brief Enable FIFO data batching of first slave.[set] + * @brief Enable FIFO data batching of slave idx.[set] * * @param ctx read / write interface definitions - * @param val Enable FIFO data batching of first slave. + * @param val Enable FIFO data batching of slave idx. * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_batch_sh_slave_0_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) +int32_t lsm6dsv16x_fifo_sh_batch_slave_set(lsm6dsv16x_ctx_t *ctx, uint8_t idx, uint8_t val) { - lsm6dsv16x_slv0_config_t slv0_config; + lsm6dsv16x_slv0_config_t slv_config; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV0_CONFIG, (uint8_t *)&slv0_config, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - slv0_config.batch_ext_sens_0_en = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV0_CONFIG, (uint8_t *)&slv0_config, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV0_CONFIG + idx * 3U, (uint8_t *)&slv_config, 1); + slv_config.batch_ext_sens_0_en = val; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV0_CONFIG + idx * 3U, (uint8_t *)&slv_config, 1); + + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } /** - * @brief Enable FIFO data batching of first slave.[get] + * @brief Enable FIFO data batching of slave idx.[get] * * @param ctx read / write interface definitions - * @param val Enable FIFO data batching of first slave. + * @param val Enable FIFO data batching of slave idx. * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_batch_sh_slave_0_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) +int32_t lsm6dsv16x_fifo_sh_batch_slave_get(lsm6dsv16x_ctx_t *ctx, uint8_t idx, uint8_t *val) { - lsm6dsv16x_slv0_config_t slv0_config; + lsm6dsv16x_slv0_config_t slv_config; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV0_CONFIG, (uint8_t *)&slv0_config, 1); + if (ret != 0) { + return ret; } - *val = slv0_config.batch_ext_sens_0_en; + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV0_CONFIG + idx * 3U, (uint8_t *)&slv_config, 1); + *val = slv_config.batch_ext_sens_0_en; - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } /** - * @brief Enable FIFO data batching of second slave.[set] + * @brief Batching in FIFO buffer of SFLP.[set] * * @param ctx read / write interface definitions - * @param val Enable FIFO data batching of second slave. + * @param val Batching in FIFO buffer of SFLP values. * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_batch_sh_slave_1_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) +int32_t lsm6dsv16x_fifo_sflp_batch_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_sflp_raw_t val) { - lsm6dsv16x_slv1_config_t slv1_config; + lsm6dsv16x_emb_func_fifo_en_a_t emb_func_fifo_en_a; int32_t ret; - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); + ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV1_CONFIG, (uint8_t *)&slv1_config, 1); + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_A, (uint8_t *)&emb_func_fifo_en_a, 1); + emb_func_fifo_en_a.sflp_game_fifo_en = val.game_rotation; + emb_func_fifo_en_a.sflp_gravity_fifo_en = val.gravity; + emb_func_fifo_en_a.sflp_gbias_fifo_en = val.gbias; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_A, + (uint8_t *)&emb_func_fifo_en_a, 1); } - if (ret == 0) { - slv1_config.batch_ext_sens_1_en = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV1_CONFIG, (uint8_t *)&slv1_config, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } /** - * @brief Enable FIFO data batching of second slave.[get] + * @brief Batching in FIFO buffer of SFLP.[get] * * @param ctx read / write interface definitions - * @param val Enable FIFO data batching of second slave. + * @param val Batching in FIFO buffer of SFLP values. * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_batch_sh_slave_1_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) +int32_t lsm6dsv16x_fifo_sflp_batch_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_sflp_raw_t *val) { - lsm6dsv16x_slv1_config_t slv1_config; + lsm6dsv16x_emb_func_fifo_en_a_t emb_func_fifo_en_a; int32_t ret; - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); + ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV1_CONFIG, (uint8_t *)&slv1_config, 1); - } - - *val = slv1_config.batch_ext_sens_1_en; + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_FIFO_EN_A, (uint8_t *)&emb_func_fifo_en_a, 1); - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + val->game_rotation = emb_func_fifo_en_a.sflp_game_fifo_en; + val->gravity = emb_func_fifo_en_a.sflp_gravity_fifo_en; + val->gbias = emb_func_fifo_en_a.sflp_gbias_fifo_en; } + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + return ret; } /** - * @brief Enable FIFO data batching of third slave.[set] + * @} + * + */ + +/** + * @defgroup Filters + * @brief This section group all the functions concerning the + * filters configuration + * @{ + * + */ + +/** + * @brief Protocol anti-spike filters.[set] * * @param ctx read / write interface definitions - * @param val Enable FIFO data batching of third slave. + * @param val AUTO, ALWAYS_ACTIVE, * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_batch_sh_slave_2_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) +int32_t lsm6dsv16x_filt_anti_spike_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_anti_spike_t val) { - lsm6dsv16x_slv2_config_t slv2_config; + lsm6dsv16x_if_cfg_t if_cfg; int32_t ret; - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV2_CONFIG, (uint8_t *)&slv2_config, 1); - } + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_IF_CFG, (uint8_t *)&if_cfg, 1); if (ret == 0) { - slv2_config.batch_ext_sens_2_en = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV2_CONFIG, (uint8_t *)&slv2_config, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + if_cfg.asf_ctrl = (uint8_t)val & 0x01U; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_IF_CFG, (uint8_t *)&if_cfg, 1); } return ret; } /** - * @brief Enable FIFO data batching of third slave.[get] + * @brief Protocol anti-spike filters.[get] * * @param ctx read / write interface definitions - * @param val Enable FIFO data batching of third slave. + * @param val AUTO, ALWAYS_ACTIVE, * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fifo_batch_sh_slave_2_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) +int32_t lsm6dsv16x_filt_anti_spike_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_anti_spike_t *val) { - lsm6dsv16x_slv2_config_t slv2_config; + lsm6dsv16x_if_cfg_t if_cfg; int32_t ret; - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV2_CONFIG, (uint8_t *)&slv2_config, 1); + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_IF_CFG, (uint8_t *)&if_cfg, 1); + if (ret != 0) { + return ret; } - *val = slv2_config.batch_ext_sens_2_en; - - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } - - return ret; -} - -/** - * @brief Enable FIFO data batching of fourth slave.[set] - * - * @param ctx read / write interface definitions - * @param val Enable FIFO data batching of fourth slave. - * @retval interface status (MANDATORY: return 0 -> no Error) - * - */ -int32_t lsm6dsv16x_fifo_batch_sh_slave_3_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) -{ - lsm6dsv16x_slv3_config_t slv3_config; - int32_t ret; - - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV3_CONFIG, (uint8_t *)&slv3_config, 1); - } - - if (ret == 0) { - slv3_config.batch_ext_sens_3_en = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV3_CONFIG, (uint8_t *)&slv3_config, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } - - return ret; -} - -/** - * @brief Enable FIFO data batching of fourth slave.[get] - * - * @param ctx read / write interface definitions - * @param val Enable FIFO data batching of fourth slave. - * @retval interface status (MANDATORY: return 0 -> no Error) - * - */ -int32_t lsm6dsv16x_fifo_batch_sh_slave_3_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) -{ - lsm6dsv16x_slv3_config_t slv3_config; - int32_t ret; - - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV3_CONFIG, (uint8_t *)&slv3_config, 1); - } - - *val = slv3_config.batch_ext_sens_3_en; - - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } - - return ret; -} - -/** - * @} - * - */ - -/** - * @defgroup Filters - * @brief This section group all the functions concerning the - * filters configuration - * @{ - * - */ - -/** - * @brief Protocol anti-spike filters.[set] - * - * @param ctx read / write interface definitions - * @param val AUTO, ALWAYS_ACTIVE, - * @retval interface status (MANDATORY: return 0 -> no Error) - * - */ -int32_t lsm6dsv16x_filt_anti_spike_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_anti_spike_t val) -{ - lsm6dsv16x_if_cfg_t if_cfg; - int32_t ret; - - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_IF_CFG, (uint8_t *)&if_cfg, 1); - - if (ret == 0) { - if_cfg.asf_ctrl = (uint8_t)val & 0x01U; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_IF_CFG, (uint8_t *)&if_cfg, 1); - } - - return ret; -} - -/** - * @brief Protocol anti-spike filters.[get] - * - * @param ctx read / write interface definitions - * @param val AUTO, ALWAYS_ACTIVE, - * @retval interface status (MANDATORY: return 0 -> no Error) - * - */ -int32_t lsm6dsv16x_filt_anti_spike_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_anti_spike_t *val) -{ - lsm6dsv16x_if_cfg_t if_cfg; - int32_t ret; - - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_IF_CFG, (uint8_t *)&if_cfg, 1); switch (if_cfg.asf_ctrl) { case LSM6DSV16X_AUTO: *val = LSM6DSV16X_AUTO; @@ -3684,6 +4406,7 @@ int32_t lsm6dsv16x_filt_anti_spike_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_an *val = LSM6DSV16X_AUTO; break; } + return ret; } @@ -3695,7 +4418,8 @@ int32_t lsm6dsv16x_filt_anti_spike_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_an * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_settling_mask_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_settling_mask_t val) +int32_t lsm6dsv16x_filt_settling_mask_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_settling_mask_t val) { lsm6dsv16x_emb_func_cfg_t emb_func_cfg; lsm6dsv16x_ui_int_ois_t ui_int_ois; @@ -3703,31 +4427,23 @@ int32_t lsm6dsv16x_filt_settling_mask_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL4, (uint8_t *)&ctrl4, 1); - - if (ret == 0) { - ctrl4.drdy_mask = val.drdy; - - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_CTRL4, (uint8_t *)&ctrl4, 1); - } - - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_CFG, (uint8_t *)&emb_func_cfg, 1); - } - - if (ret == 0) { - emb_func_cfg.emb_func_irq_mask_xl_settl = val.irq_xl; - emb_func_cfg.emb_func_irq_mask_g_settl = val.irq_g; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_CFG, (uint8_t *)&emb_func_cfg, 1); + ctrl4.drdy_mask = val.drdy; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_CTRL4, (uint8_t *)&ctrl4, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_UI_INT_OIS, (uint8_t *)&ui_int_ois, 1); + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_CFG, (uint8_t *)&emb_func_cfg, 1); + emb_func_cfg.emb_func_irq_mask_xl_settl = val.irq_xl; + emb_func_cfg.emb_func_irq_mask_g_settl = val.irq_g; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_CFG, (uint8_t *)&emb_func_cfg, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - ui_int_ois.drdy_mask_ois = val.ois_drdy; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_UI_INT_OIS, (uint8_t *)&ui_int_ois, 1); - } + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_UI_INT_OIS, (uint8_t *)&ui_int_ois, 1); + ui_int_ois.drdy_mask_ois = val.ois_drdy; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_UI_INT_OIS, (uint8_t *)&ui_int_ois, 1); return ret; } @@ -3740,7 +4456,8 @@ int32_t lsm6dsv16x_filt_settling_mask_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_settling_mask_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_settling_mask_t *val) +int32_t lsm6dsv16x_filt_settling_mask_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_settling_mask_t *val) { lsm6dsv16x_emb_func_cfg_t emb_func_cfg; lsm6dsv16x_ui_int_ois_t ui_int_ois; @@ -3748,12 +4465,8 @@ int32_t lsm6dsv16x_filt_settling_mask_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL4, (uint8_t *)&ctrl4, 1); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_CFG, (uint8_t *)&emb_func_cfg, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_UI_INT_OIS, (uint8_t *)&ui_int_ois, 1); - } + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_CFG, (uint8_t *)&emb_func_cfg, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_UI_INT_OIS, (uint8_t *)&ui_int_ois, 1); val->irq_xl = emb_func_cfg.emb_func_irq_mask_xl_settl; val->irq_g = emb_func_cfg.emb_func_irq_mask_g_settl; @@ -3770,7 +4483,8 @@ int32_t lsm6dsv16x_filt_settling_mask_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_ois_settling_mask_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_ois_settling_mask_t val) +int32_t lsm6dsv16x_filt_ois_settling_mask_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_ois_settling_mask_t val) { lsm6dsv16x_spi2_int_ois_t spi2_int_ois; int32_t ret; @@ -3793,7 +4507,8 @@ int32_t lsm6dsv16x_filt_ois_settling_mask_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_ois_settling_mask_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_ois_settling_mask_t *val) +int32_t lsm6dsv16x_filt_ois_settling_mask_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_ois_settling_mask_t *val) { lsm6dsv16x_spi2_int_ois_t spi2_int_ois; @@ -3813,7 +4528,8 @@ int32_t lsm6dsv16x_filt_ois_settling_mask_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_gy_lp1_bandwidth_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_gy_lp1_bandwidth_t val) +int32_t lsm6dsv16x_filt_gy_lp1_bandwidth_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_gy_lp1_bandwidth_t val) { lsm6dsv16x_ctrl6_t ctrl6; int32_t ret; @@ -3835,12 +4551,17 @@ int32_t lsm6dsv16x_filt_gy_lp1_bandwidth_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_f * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_gy_lp1_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_gy_lp1_bandwidth_t *val) +int32_t lsm6dsv16x_filt_gy_lp1_bandwidth_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_gy_lp1_bandwidth_t *val) { lsm6dsv16x_ctrl6_t ctrl6; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL6, (uint8_t *)&ctrl6, 1); + if (ret != 0) { + return ret; + } + switch (ctrl6.lpf1_g_bw) { case LSM6DSV16X_GY_ULTRA_LIGHT: *val = LSM6DSV16X_GY_ULTRA_LIGHT; @@ -3878,6 +4599,7 @@ int32_t lsm6dsv16x_filt_gy_lp1_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_f *val = LSM6DSV16X_GY_ULTRA_LIGHT; break; } + return ret; } @@ -3931,7 +4653,8 @@ int32_t lsm6dsv16x_filt_gy_lp1_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_xl_lp2_bandwidth_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_xl_lp2_bandwidth_t val) +int32_t lsm6dsv16x_filt_xl_lp2_bandwidth_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_xl_lp2_bandwidth_t val) { lsm6dsv16x_ctrl8_t ctrl8; int32_t ret; @@ -3953,12 +4676,17 @@ int32_t lsm6dsv16x_filt_xl_lp2_bandwidth_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_f * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_xl_lp2_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_xl_lp2_bandwidth_t *val) +int32_t lsm6dsv16x_filt_xl_lp2_bandwidth_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_xl_lp2_bandwidth_t *val) { lsm6dsv16x_ctrl8_t ctrl8; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL8, (uint8_t *)&ctrl8, 1); + if (ret != 0) { + return ret; + } + switch (ctrl8.hp_lpf2_xl_bw) { case LSM6DSV16X_XL_ULTRA_LIGHT: *val = LSM6DSV16X_XL_ULTRA_LIGHT; @@ -3996,6 +4724,7 @@ int32_t lsm6dsv16x_filt_xl_lp2_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_f *val = LSM6DSV16X_XL_ULTRA_LIGHT; break; } + return ret; } @@ -4130,7 +4859,8 @@ int32_t lsm6dsv16x_filt_xl_fast_settling_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_xl_hp_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_xl_hp_mode_t val) +int32_t lsm6dsv16x_filt_xl_hp_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_xl_hp_mode_t val) { lsm6dsv16x_ctrl9_t ctrl9; int32_t ret; @@ -4152,12 +4882,17 @@ int32_t lsm6dsv16x_filt_xl_hp_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_xl * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_xl_hp_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_xl_hp_mode_t *val) +int32_t lsm6dsv16x_filt_xl_hp_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_xl_hp_mode_t *val) { lsm6dsv16x_ctrl9_t ctrl9; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL9, (uint8_t *)&ctrl9, 1); + if (ret != 0) { + return ret; + } + switch (ctrl9.hp_ref_mode_xl) { case LSM6DSV16X_HP_MD_NORMAL: *val = LSM6DSV16X_HP_MD_NORMAL; @@ -4171,6 +4906,7 @@ int32_t lsm6dsv16x_filt_xl_hp_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_xl *val = LSM6DSV16X_HP_MD_NORMAL; break; } + return ret; } @@ -4182,26 +4918,28 @@ int32_t lsm6dsv16x_filt_xl_hp_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_xl * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_wkup_act_feed_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_wkup_act_feed_t val) +int32_t lsm6dsv16x_filt_wkup_act_feed_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_wkup_act_feed_t val) { lsm6dsv16x_wake_up_ths_t wake_up_ths; lsm6dsv16x_tap_cfg0_t tap_cfg0; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_WAKE_UP_THS, (uint8_t *)&wake_up_ths, 1); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG0, (uint8_t *)&tap_cfg0, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG0, (uint8_t *)&tap_cfg0, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - tap_cfg0.slope_fds = (uint8_t)val & 0x01U; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_TAP_CFG0, (uint8_t *)&tap_cfg0, 1); - } - if (ret == 0) { - wake_up_ths.usr_off_on_wu = ((uint8_t)val & 0x02U) >> 1; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_WAKE_UP_THS, (uint8_t *)&wake_up_ths, 1); + tap_cfg0.slope_fds = (uint8_t)val & 0x01U; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_TAP_CFG0, (uint8_t *)&tap_cfg0, 1); + if (ret != 0) { + return ret; } + wake_up_ths.usr_off_on_wu = ((uint8_t)val & 0x02U) >> 1; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_WAKE_UP_THS, (uint8_t *)&wake_up_ths, 1); + return ret; } @@ -4213,15 +4951,17 @@ int32_t lsm6dsv16x_filt_wkup_act_feed_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_wkup_act_feed_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_wkup_act_feed_t *val) +int32_t lsm6dsv16x_filt_wkup_act_feed_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_wkup_act_feed_t *val) { lsm6dsv16x_wake_up_ths_t wake_up_ths; lsm6dsv16x_tap_cfg0_t tap_cfg0; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_WAKE_UP_THS, (uint8_t *)&wake_up_ths, 1); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG0, (uint8_t *)&tap_cfg0, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG0, (uint8_t *)&tap_cfg0, 1); + if (ret != 0) { + return ret; } switch ((wake_up_ths.usr_off_on_wu << 1) + tap_cfg0.slope_fds) { @@ -4241,6 +4981,49 @@ int32_t lsm6dsv16x_filt_wkup_act_feed_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt *val = LSM6DSV16X_WK_FEED_SLOPE; break; } + + return ret; +} + +/** + * @brief Mask hw function triggers when xl is settling.[set] + * + * @param ctx read / write interface definitions + * @param val 0 or 1, + * @retval interface status (MANDATORY: return 0 -> no Error) + * + */ +int32_t lsm6dsv16x_mask_trigger_xl_settl_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) +{ + lsm6dsv16x_tap_cfg0_t tap_cfg0; + int32_t ret; + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG0, (uint8_t *)&tap_cfg0, 1); + + if (ret == 0) { + tap_cfg0.hw_func_mask_xl_settl = val & 0x01U; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_TAP_CFG0, (uint8_t *)&tap_cfg0, 1); + } + + return ret; +} + +/** + * @brief Mask hw function triggers when xl is settling.[get] + * + * @param ctx read / write interface definitions + * @param val 0 or 1, + * @retval interface status (MANDATORY: return 0 -> no Error) + * + */ +int32_t lsm6dsv16x_mask_trigger_xl_settl_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) +{ + lsm6dsv16x_tap_cfg0_t tap_cfg0; + int32_t ret; + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG0, (uint8_t *)&tap_cfg0, 1); + *val = tap_cfg0.hw_func_mask_xl_settl; + return ret; } @@ -4252,7 +5035,8 @@ int32_t lsm6dsv16x_filt_wkup_act_feed_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_sixd_feed_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_sixd_feed_t val) +int32_t lsm6dsv16x_filt_sixd_feed_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_sixd_feed_t val) { lsm6dsv16x_tap_cfg0_t tap_cfg0; int32_t ret; @@ -4275,12 +5059,16 @@ int32_t lsm6dsv16x_filt_sixd_feed_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_six * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_sixd_feed_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_sixd_feed_t *val) +int32_t lsm6dsv16x_filt_sixd_feed_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_sixd_feed_t *val) { lsm6dsv16x_tap_cfg0_t tap_cfg0; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG0, (uint8_t *)&tap_cfg0, 1); + if (ret != 0) { + return ret; + } switch (tap_cfg0.low_pass_on_6d) { case LSM6DSV16X_SIXD_FEED_ODR_DIV_2: @@ -4295,6 +5083,7 @@ int32_t lsm6dsv16x_filt_sixd_feed_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_six *val = LSM6DSV16X_SIXD_FEED_ODR_DIV_2; break; } + return ret; } @@ -4306,7 +5095,8 @@ int32_t lsm6dsv16x_filt_sixd_feed_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_six * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_gy_eis_lp_bandwidth_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_gy_eis_lp_bandwidth_t val) +int32_t lsm6dsv16x_filt_gy_eis_lp_bandwidth_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_gy_eis_lp_bandwidth_t val) { lsm6dsv16x_ctrl_eis_t ctrl_eis; int32_t ret; @@ -4329,12 +5119,16 @@ int32_t lsm6dsv16x_filt_gy_eis_lp_bandwidth_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16 * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_gy_eis_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_gy_eis_lp_bandwidth_t *val) +int32_t lsm6dsv16x_filt_gy_eis_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_gy_eis_lp_bandwidth_t *val) { lsm6dsv16x_ctrl_eis_t ctrl_eis; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL_EIS, (uint8_t *)&ctrl_eis, 1); + if (ret != 0) { + return ret; + } switch (ctrl_eis.lpf_g_eis_bw) { case LSM6DSV16X_EIS_LP_NORMAL: @@ -4349,6 +5143,7 @@ int32_t lsm6dsv16x_filt_gy_eis_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16 *val = LSM6DSV16X_EIS_LP_NORMAL; break; } + return ret; } @@ -4360,7 +5155,8 @@ int32_t lsm6dsv16x_filt_gy_eis_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16 * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_gy_ois_lp_bandwidth_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_gy_ois_lp_bandwidth_t val) +int32_t lsm6dsv16x_filt_gy_ois_lp_bandwidth_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_gy_ois_lp_bandwidth_t val) { lsm6dsv16x_ui_ctrl2_ois_t ui_ctrl2_ois; int32_t ret; @@ -4383,13 +5179,17 @@ int32_t lsm6dsv16x_filt_gy_ois_lp_bandwidth_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16 * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_gy_ois_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_gy_ois_lp_bandwidth_t *val) +int32_t lsm6dsv16x_filt_gy_ois_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_gy_ois_lp_bandwidth_t *val) { lsm6dsv16x_ui_ctrl2_ois_t ui_ctrl2_ois; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_UI_CTRL2_OIS, (uint8_t *)&ui_ctrl2_ois, 1); + if (ret != 0) { + return ret; + } switch (ui_ctrl2_ois.lpf1_g_ois_bw) { case LSM6DSV16X_OIS_GY_LP_NORMAL: @@ -4412,6 +5212,7 @@ int32_t lsm6dsv16x_filt_gy_ois_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16 *val = LSM6DSV16X_OIS_GY_LP_NORMAL; break; } + return ret; } @@ -4423,7 +5224,8 @@ int32_t lsm6dsv16x_filt_gy_ois_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16 * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_xl_ois_lp_bandwidth_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_xl_ois_lp_bandwidth_t val) +int32_t lsm6dsv16x_filt_xl_ois_lp_bandwidth_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_xl_ois_lp_bandwidth_t val) { lsm6dsv16x_ui_ctrl3_ois_t ui_ctrl3_ois; int32_t ret; @@ -4446,12 +5248,16 @@ int32_t lsm6dsv16x_filt_xl_ois_lp_bandwidth_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16 * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_filt_xl_ois_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_xl_ois_lp_bandwidth_t *val) +int32_t lsm6dsv16x_filt_xl_ois_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_xl_ois_lp_bandwidth_t *val) { lsm6dsv16x_ui_ctrl3_ois_t ui_ctrl3_ois; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_UI_CTRL3_OIS, (uint8_t *)&ui_ctrl3_ois, 1); + if (ret != 0) { + return ret; + } switch (ui_ctrl3_ois.lpf_xl_ois_bw) { case LSM6DSV16X_OIS_XL_LP_ULTRA_LIGHT: @@ -4490,6 +5296,7 @@ int32_t lsm6dsv16x_filt_xl_ois_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16 *val = LSM6DSV16X_OIS_XL_LP_ULTRA_LIGHT; break; } + return ret; } @@ -4514,7 +5321,8 @@ int32_t lsm6dsv16x_filt_xl_ois_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16 * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fsm_permission_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_permission_t val) +int32_t lsm6dsv16x_fsm_permission_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_permission_t val) { lsm6dsv16x_func_cfg_access_t func_cfg_access; int32_t ret; @@ -4537,12 +5345,16 @@ int32_t lsm6dsv16x_fsm_permission_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_perm * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fsm_permission_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_permission_t *val) +int32_t lsm6dsv16x_fsm_permission_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_permission_t *val) { lsm6dsv16x_func_cfg_access_t func_cfg_access; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FUNC_CFG_ACCESS, (uint8_t *)&func_cfg_access, 1); + if (ret != 0) { + return ret; + } switch (func_cfg_access.fsm_wr_ctrl_en) { case LSM6DSV16X_PROTECT_CTRL_REGS: @@ -4557,6 +5369,7 @@ int32_t lsm6dsv16x_fsm_permission_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_perm *val = LSM6DSV16X_PROTECT_CTRL_REGS; break; } + return ret; } @@ -4595,35 +5408,37 @@ int32_t lsm6dsv16x_fsm_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_mode_t val int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_B, (uint8_t *)&emb_func_en_b, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FSM_ENABLE, (uint8_t *)&fsm_enable, 1); + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_B, (uint8_t *)&emb_func_en_b, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FSM_ENABLE, (uint8_t *)&fsm_enable, 1); + if (ret != 0) { + goto exit; } + if ((val.fsm1_en | val.fsm2_en | val.fsm1_en | val.fsm1_en | val.fsm1_en | val.fsm2_en | val.fsm1_en | val.fsm1_en) == PROPERTY_ENABLE) { emb_func_en_b.fsm_en = PROPERTY_ENABLE; } else { emb_func_en_b.fsm_en = PROPERTY_DISABLE; } - if (ret == 0) { - fsm_enable.fsm1_en = val.fsm1_en; - fsm_enable.fsm2_en = val.fsm2_en; - fsm_enable.fsm3_en = val.fsm3_en; - fsm_enable.fsm4_en = val.fsm4_en; - fsm_enable.fsm5_en = val.fsm5_en; - fsm_enable.fsm6_en = val.fsm6_en; - fsm_enable.fsm7_en = val.fsm7_en; - fsm_enable.fsm8_en = val.fsm8_en; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FSM_ENABLE, (uint8_t *)&fsm_enable, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_B, (uint8_t *)&emb_func_en_b, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + + fsm_enable.fsm1_en = val.fsm1_en; + fsm_enable.fsm2_en = val.fsm2_en; + fsm_enable.fsm3_en = val.fsm3_en; + fsm_enable.fsm4_en = val.fsm4_en; + fsm_enable.fsm5_en = val.fsm5_en; + fsm_enable.fsm6_en = val.fsm6_en; + fsm_enable.fsm7_en = val.fsm7_en; + fsm_enable.fsm8_en = val.fsm8_en; + + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FSM_ENABLE, (uint8_t *)&fsm_enable, 1); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_B, (uint8_t *)&emb_func_en_b, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -4642,11 +5457,10 @@ int32_t lsm6dsv16x_fsm_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_mode_t *va int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FSM_ENABLE, (uint8_t *)&fsm_enable, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FSM_ENABLE, (uint8_t *)&fsm_enable, 1); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + if (ret != 0) { + return ret; } val->fsm1_en = fsm_enable.fsm1_en; @@ -4677,10 +5491,9 @@ int32_t lsm6dsv16x_fsm_long_cnt_set(lsm6dsv16x_ctx_t *ctx, uint16_t val) buff[1] = (uint8_t)(val / 256U); buff[0] = (uint8_t)(val - (buff[1] * 256U)); - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FSM_LONG_COUNTER_L, (uint8_t *)&buff[0], 2); - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FSM_LONG_COUNTER_L, (uint8_t *)&buff[0], 2); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -4699,11 +5512,10 @@ int32_t lsm6dsv16x_fsm_long_cnt_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FSM_LONG_COUNTER_L, &buff[0], 2); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FSM_LONG_COUNTER_L, &buff[0], 2); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + if (ret != 0) { + return ret; } *val = buff[1]; @@ -4725,12 +5537,8 @@ int32_t lsm6dsv16x_fsm_out_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_out_t *val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FSM_OUTS1, (uint8_t *)val, 8); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FSM_OUTS1, (uint8_t *)val, 8); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -4743,23 +5551,23 @@ int32_t lsm6dsv16x_fsm_out_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_out_t *val) * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fsm_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_data_rate_t val) +int32_t lsm6dsv16x_fsm_data_rate_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_data_rate_t val) { lsm6dsv16x_fsm_odr_t fsm_odr; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FSM_ODR, (uint8_t *)&fsm_odr, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FSM_ODR, (uint8_t *)&fsm_odr, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - fsm_odr.fsm_odr = (uint8_t)val & 0x07U; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FSM_ODR, (uint8_t *)&fsm_odr, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + fsm_odr.fsm_odr = (uint8_t)val & 0x07U; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FSM_ODR, (uint8_t *)&fsm_odr, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -4772,20 +5580,19 @@ int32_t lsm6dsv16x_fsm_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_data_ * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fsm_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_data_rate_t *val) +int32_t lsm6dsv16x_fsm_data_rate_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_data_rate_t *val) { lsm6dsv16x_fsm_odr_t fsm_odr; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FSM_ODR, (uint8_t *)&fsm_odr, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FSM_ODR, (uint8_t *)&fsm_odr, 1); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + if (ret != 0) { + return ret; } - switch (fsm_odr.fsm_odr) { case LSM6DSV16X_FSM_15Hz: *val = LSM6DSV16X_FSM_15Hz; @@ -4819,6 +5626,304 @@ int32_t lsm6dsv16x_fsm_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_data_ *val = LSM6DSV16X_FSM_15Hz; break; } + + return ret; +} + +/* + * Original conversion routines taken from: https://github.com/numpy/numpy + * + * uint16_t npy_floatbits_to_halfbits(uint32_t f); + * uint16_t npy_float_to_half(float_t f); + * + * Released under BSD-3-Clause License + */ +static uint16_t npy_floatbits_to_halfbits(uint32_t f) +{ + uint32_t f_exp, f_sig; + uint16_t h_sgn, h_exp, h_sig; + + h_sgn = (uint16_t)((f & 0x80000000u) >> 16); + f_exp = (f & 0x7f800000u); + + /* Exponent overflow/NaN converts to signed inf/NaN */ + if (f_exp >= 0x47800000u) { + if (f_exp == 0x7f800000u) { + /* Inf or NaN */ + f_sig = (f & 0x007fffffu); + if (f_sig != 0U) { + /* NaN - propagate the flag in the significand... */ + uint16_t ret = (uint16_t)(0x7c00u + (f_sig >> 13)); + /* ...but make sure it stays a NaN */ + if (ret == 0x7c00u) { + ret++; + } + return h_sgn + ret; + } else { + /* signed inf */ + return (uint16_t)(h_sgn + 0x7c00u); + } + } else { + /* overflow to signed inf */ +#if NPY_HALF_GENERATE_OVERFLOW + npy_set_floatstatus_overflow(); +#endif + return (uint16_t)(h_sgn + 0x7c00u); + } + } + + /* Exponent underflow converts to a subnormal half or signed zero */ + if (f_exp <= 0x38000000u) { + /* + * Signed zeros, subnormal floats, and floats with small + * exponents all convert to signed zero half-floats. + */ + if (f_exp < 0x33000000u) { +#if NPY_HALF_GENERATE_UNDERFLOW + /* If f != 0, it underflowed to 0 */ + if ((f & 0x7fffffff) != 0) { + npy_set_floatstatus_underflow(); + } +#endif + return h_sgn; + } + /* Make the subnormal significand */ + f_exp >>= 23; + f_sig = (0x00800000u + (f & 0x007fffffu)); +#if NPY_HALF_GENERATE_UNDERFLOW + /* If it's not exactly represented, it underflowed */ + if ((f_sig & (((uint32_t)1 << (126 - f_exp)) - 1)) != 0) { + npy_set_floatstatus_underflow(); + } +#endif + /* + * Usually the significand is shifted by 13. For subnormals an + * additional shift needs to occur. This shift is one for the largest + * exponent giving a subnormal `f_exp = 0x38000000 >> 23 = 112`, which + * offsets the new first bit. At most the shift can be 1+10 bits. + */ + f_sig >>= (113U - f_exp); + /* Handle rounding by adding 1 to the bit beyond half precision */ +#if NPY_HALF_ROUND_TIES_TO_EVEN + /* + * If the last bit in the half significand is 0 (already even), and + * the remaining bit pattern is 1000...0, then we do not add one + * to the bit after the half significand. However, the (113 - f_exp) + * shift can lose up to 11 bits, so the || checks them in the original. + * In all other cases, we can just add one. + */ + if (((f_sig & 0x00003fffu) != 0x00001000u) || (f & 0x000007ffu)) { + f_sig += 0x00001000u; + } +#else + f_sig += 0x00001000u; +#endif + h_sig = (uint16_t)(f_sig >> 13); + /* + * If the rounding causes a bit to spill into h_exp, it will + * increment h_exp from zero to one and h_sig will be zero. + * This is the correct result. + */ + return (uint16_t)(h_sgn + h_sig); + } + + /* Regular case with no overflow or underflow */ + h_exp = (uint16_t)((f_exp - 0x38000000u) >> 13); + /* Handle rounding by adding 1 to the bit beyond half precision */ + f_sig = (f & 0x007fffffu); +#if NPY_HALF_ROUND_TIES_TO_EVEN + /* + * If the last bit in the half significand is 0 (already even), and + * the remaining bit pattern is 1000...0, then we do not add one + * to the bit after the half significand. In all other cases, we do. + */ + if ((f_sig & 0x00003fffu) != 0x00001000u) { + f_sig += 0x00001000u; + } +#else + f_sig += 0x00001000u; +#endif + h_sig = (uint16_t)(f_sig >> 13); + /* + * If the rounding causes a bit to spill into h_exp, it will + * increment h_exp by one and h_sig will be zero. This is the + * correct result. h_exp may increment to 15, at greatest, in + * which case the result overflows to a signed inf. + */ +#if NPY_HALF_GENERATE_OVERFLOW + h_sig += h_exp; + if (h_sig == 0x7c00u) { + npy_set_floatstatus_overflow(); + } + return h_sgn + h_sig; +#else + return h_sgn + h_exp + h_sig; +#endif +} + +static uint16_t npy_float_to_half(float_t f) +{ + union { + float_t f; + uint32_t fbits; + } conv; + conv.f = f; + return npy_floatbits_to_halfbits(conv.fbits); +} + +/** + * @brief SFLP GBIAS value. The register value is expressed as half-precision + * floating-point format: SEEEEEFFFFFFFFFF (S: 1 sign bit; E: 5 exponent + * bits; F: 10 fraction bits).[set] + * + * @param ctx read / write interface definitions + * @param val GBIAS x/y/z val. + * @retval interface status (MANDATORY: return 0 -> no Error) + * + */ +int32_t lsm6dsv16x_sflp_game_gbias_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sflp_gbias_t *val) +{ + lsm6dsv16x_sflp_data_rate_t sflp_odr; + lsm6dsv16x_emb_func_exec_status_t emb_func_sts; + lsm6dsv16x_data_ready_t drdy; + lsm6dsv16x_xl_full_scale_t xl_fs; + lsm6dsv16x_ctrl10_t ctrl10; + uint8_t master_config; + uint8_t emb_func_en_saved[2]; + uint8_t conf_saved[2]; + uint8_t reg_zero[2] = {0x0, 0x0}; + uint16_t gbias_hf[3]; + float_t k = 0.005f; + int16_t xl_data[3]; + int32_t data_tmp; + uint8_t *data_ptr = (uint8_t *)&data_tmp; + uint8_t i, j; + int32_t ret; + + ret = lsm6dsv16x_sflp_data_rate_get(ctx, &sflp_odr); + if (ret != 0) { + return ret; + } + + /* Calculate k factor */ + switch (sflp_odr) { + default: + case LSM6DSV16X_SFLP_15Hz: + k = 0.04f; + break; + case LSM6DSV16X_SFLP_30Hz: + k = 0.02f; + break; + case LSM6DSV16X_SFLP_60Hz: + k = 0.01f; + break; + case LSM6DSV16X_SFLP_120Hz: + k = 0.005f; + break; + case LSM6DSV16X_SFLP_240Hz: + k = 0.0025f; + break; + case LSM6DSV16X_SFLP_480Hz: + k = 0.00125f; + break; + } + + /* compute gbias as half precision float in order to be put in embedded advanced feature register */ + gbias_hf[0] = npy_float_to_half(val->gbias_x * (3.14159265358979323846f / 180.0f) / k); + gbias_hf[1] = npy_float_to_half(val->gbias_y * (3.14159265358979323846f / 180.0f) / k); + gbias_hf[2] = npy_float_to_half(val->gbias_z * (3.14159265358979323846f / 180.0f) / k); + + /* Save sensor configuration and set high-performance mode (if the sensor is in power-down mode, turn it on) */ + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL1, conf_saved, 2); + ret += lsm6dsv16x_xl_mode_set(ctx, LSM6DSV16X_XL_HIGH_PERFORMANCE_MD); + ret += lsm6dsv16x_gy_mode_set(ctx, LSM6DSV16X_GY_HIGH_PERFORMANCE_MD); + if (((uint8_t)conf_saved[0] & 0x0FU) == (uint8_t)LSM6DSV16X_ODR_OFF) { + ret += lsm6dsv16x_xl_data_rate_set(ctx, LSM6DSV16X_ODR_AT_120Hz); + } + + /* Make sure to turn the sensor-hub master off */ + ret += lsm6dsv16x_sh_master_get(ctx, &master_config); + ret += lsm6dsv16x_sh_master_set(ctx, 0); + + /* disable algos */ + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, emb_func_en_saved, 2); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, reg_zero, 2); + do { + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EXEC_STATUS, + (uint8_t *)&emb_func_sts, 1); + } while (emb_func_sts.emb_func_endop != 1U); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + + // enable gbias setting + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL10, (uint8_t *)&ctrl10, 1); + ctrl10.emb_func_debug = 1; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_CTRL10, (uint8_t *)&ctrl10, 1); + + /* enable algos */ + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); + emb_func_en_saved[0] |= 0x02U; /* force SFLP GAME en */ + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, emb_func_en_saved, + 2); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + + ret += lsm6dsv16x_xl_full_scale_get(ctx, &xl_fs); + + /* Read XL data */ + do { + ret += lsm6dsv16x_flag_data_ready_get(ctx, &drdy); + } while (drdy.drdy_xl != 1U); + ret += lsm6dsv16x_acceleration_raw_get(ctx, xl_data); + + /* force sflp initialization */ + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); + for (i = 0; i < 3U; i++) { + j = 0; + data_tmp = (int32_t)xl_data[i]; + data_tmp <<= xl_fs; // shift based on current fs + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SENSOR_HUB_1 + 3U * i, + &data_ptr[j++], 1); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SENSOR_HUB_2 + 3U * i, + &data_ptr[j++], 1); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SENSOR_HUB_3 + 3U * i, &data_ptr[j], + 1); + } + for (i = 0; i < 3U; i++) { + j = 0; + data_tmp = 0; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SENSOR_HUB_10 + 3U * i, + &data_ptr[j++], 1); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SENSOR_HUB_11 + 3U * i, + &data_ptr[j++], 1); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SENSOR_HUB_12 + 3U * i, &data_ptr[j], + 1); + } + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + + // wait end_op (and at least 30 us) + ctx->mdelay(1); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); + do { + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EXEC_STATUS, + (uint8_t *)&emb_func_sts, 1); + } while (emb_func_sts.emb_func_endop != 1U); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + + /* write gbias in embedded advanced features registers */ + ret += lsm6dsv16x_ln_pg_write(ctx, LSM6DSV16X_SFLP_GAME_GBIASX_L, + (uint8_t *)gbias_hf, 6); + + /* reload previous sensor configuration */ + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_CTRL1, conf_saved, 2); + + // disable gbias setting + ctrl10.emb_func_debug = 0; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_CTRL10, (uint8_t *)&ctrl10, 1); + + /* reload previous master configuration */ + ret += lsm6dsv16x_sh_master_set(ctx, master_config); + return ret; } @@ -4850,12 +5955,17 @@ int32_t lsm6dsv16x_fsm_ext_sens_sensitivity_set(lsm6dsv16x_ctx_t *ctx, uint16_t * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fsm_ext_sens_sensitivity_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val) +int32_t lsm6dsv16x_fsm_ext_sens_sensitivity_get(lsm6dsv16x_ctx_t *ctx, + uint16_t *val) { uint8_t buff[2]; int32_t ret; ret = lsm6dsv16x_ln_pg_read(ctx, LSM6DSV16X_FSM_EXT_SENSITIVITY_L, &buff[0], 2); + if (ret != 0) { + return ret; + } + *val = buff[1]; *val = (*val * 256U) + buff[0]; @@ -4870,7 +5980,8 @@ int32_t lsm6dsv16x_fsm_ext_sens_sensitivity_get(lsm6dsv16x_ctx_t *ctx, uint16_t * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fsm_ext_sens_offset_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_fsm_ext_sens_offset_t val) +int32_t lsm6dsv16x_fsm_ext_sens_offset_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_fsm_ext_sens_offset_t val) { uint8_t buff[6]; int32_t ret; @@ -4894,12 +6005,16 @@ int32_t lsm6dsv16x_fsm_ext_sens_offset_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_ * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fsm_ext_sens_offset_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_fsm_ext_sens_offset_t *val) +int32_t lsm6dsv16x_fsm_ext_sens_offset_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_fsm_ext_sens_offset_t *val) { uint8_t buff[6]; int32_t ret; ret = lsm6dsv16x_ln_pg_read(ctx, LSM6DSV16X_FSM_EXT_OFFX_L, &buff[0], 6); + if (ret != 0) { + return ret; + } val->x = buff[1]; val->x = (val->x * 256U) + buff[0]; @@ -4919,7 +6034,8 @@ int32_t lsm6dsv16x_fsm_ext_sens_offset_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_ * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fsm_ext_sens_matrix_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_fsm_ext_sens_matrix_t val) +int32_t lsm6dsv16x_fsm_ext_sens_matrix_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_fsm_ext_sens_matrix_t val) { uint8_t buff[12]; int32_t ret; @@ -4949,12 +6065,16 @@ int32_t lsm6dsv16x_fsm_ext_sens_matrix_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_ * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fsm_ext_sens_matrix_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_fsm_ext_sens_matrix_t *val) +int32_t lsm6dsv16x_fsm_ext_sens_matrix_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_fsm_ext_sens_matrix_t *val) { uint8_t buff[12]; int32_t ret; ret = lsm6dsv16x_ln_pg_read(ctx, LSM6DSV16X_FSM_EXT_MATRIX_XX_L, &buff[0], 12); + if (ret != 0) { + return ret; + } val->xx = buff[1]; val->xx = (val->xx * 256U) + buff[0]; @@ -4980,16 +6100,15 @@ int32_t lsm6dsv16x_fsm_ext_sens_matrix_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_ * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fsm_ext_sens_z_orient_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_ext_sens_z_orient_t val) +int32_t lsm6dsv16x_fsm_ext_sens_z_orient_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_ext_sens_z_orient_t val) { lsm6dsv16x_ext_cfg_a_t ext_cfg_a; int32_t ret; ret = lsm6dsv16x_ln_pg_read(ctx, LSM6DSV16X_EXT_CFG_A, (uint8_t *)&ext_cfg_a, 1); - if (ret == 0) { - ext_cfg_a.ext_z_axis = (uint8_t)val & 0x07U; - ret = lsm6dsv16x_ln_pg_write(ctx, LSM6DSV16X_EXT_CFG_A, (uint8_t *)&ext_cfg_a, 1); - } + ext_cfg_a.ext_z_axis = (uint8_t)val & 0x07U; + ret += lsm6dsv16x_ln_pg_write(ctx, LSM6DSV16X_EXT_CFG_A, (uint8_t *)&ext_cfg_a, 1); return ret; } @@ -5002,12 +6121,17 @@ int32_t lsm6dsv16x_fsm_ext_sens_z_orient_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_f * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fsm_ext_sens_z_orient_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_ext_sens_z_orient_t *val) +int32_t lsm6dsv16x_fsm_ext_sens_z_orient_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_ext_sens_z_orient_t *val) { lsm6dsv16x_ext_cfg_a_t ext_cfg_a; int32_t ret; ret = lsm6dsv16x_ln_pg_read(ctx, LSM6DSV16X_EXT_CFG_A, (uint8_t *)&ext_cfg_a, 1); + if (ret != 0) { + return ret; + } + switch (ext_cfg_a.ext_z_axis) { case LSM6DSV16X_Z_EQ_Y: *val = LSM6DSV16X_Z_EQ_Y; @@ -5037,6 +6161,7 @@ int32_t lsm6dsv16x_fsm_ext_sens_z_orient_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_f *val = LSM6DSV16X_Z_EQ_Y; break; } + return ret; } @@ -5048,7 +6173,8 @@ int32_t lsm6dsv16x_fsm_ext_sens_z_orient_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_f * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fsm_ext_sens_y_orient_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_ext_sens_y_orient_t val) +int32_t lsm6dsv16x_fsm_ext_sens_y_orient_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_ext_sens_y_orient_t val) { lsm6dsv16x_ext_cfg_a_t ext_cfg_a; int32_t ret; @@ -5070,12 +6196,17 @@ int32_t lsm6dsv16x_fsm_ext_sens_y_orient_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_f * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fsm_ext_sens_y_orient_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_ext_sens_y_orient_t *val) +int32_t lsm6dsv16x_fsm_ext_sens_y_orient_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_ext_sens_y_orient_t *val) { lsm6dsv16x_ext_cfg_a_t ext_cfg_a; int32_t ret; ret = lsm6dsv16x_ln_pg_read(ctx, LSM6DSV16X_EXT_CFG_A, (uint8_t *)&ext_cfg_a, 1); + if (ret != 0) { + return ret; + } + switch (ext_cfg_a.ext_y_axis) { case LSM6DSV16X_Y_EQ_Y: *val = LSM6DSV16X_Y_EQ_Y; @@ -5105,6 +6236,7 @@ int32_t lsm6dsv16x_fsm_ext_sens_y_orient_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_f *val = LSM6DSV16X_Y_EQ_Y; break; } + return ret; } @@ -5116,7 +6248,8 @@ int32_t lsm6dsv16x_fsm_ext_sens_y_orient_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_f * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fsm_ext_sens_x_orient_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_ext_sens_x_orient_t val) +int32_t lsm6dsv16x_fsm_ext_sens_x_orient_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_ext_sens_x_orient_t val) { lsm6dsv16x_ext_cfg_b_t ext_cfg_b; int32_t ret; @@ -5138,12 +6271,17 @@ int32_t lsm6dsv16x_fsm_ext_sens_x_orient_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_f * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_fsm_ext_sens_x_orient_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_ext_sens_x_orient_t *val) +int32_t lsm6dsv16x_fsm_ext_sens_x_orient_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_ext_sens_x_orient_t *val) { lsm6dsv16x_ext_cfg_b_t ext_cfg_b; int32_t ret; ret = lsm6dsv16x_ln_pg_read(ctx, LSM6DSV16X_EXT_CFG_B, (uint8_t *)&ext_cfg_b, 1); + if (ret != 0) { + return ret; + } + switch (ext_cfg_b.ext_x_axis) { case LSM6DSV16X_X_EQ_Y: *val = LSM6DSV16X_X_EQ_Y; @@ -5173,6 +6311,7 @@ int32_t lsm6dsv16x_fsm_ext_sens_x_orient_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_f *val = LSM6DSV16X_X_EQ_Y; break; } + return ret; } @@ -5210,6 +6349,10 @@ int32_t lsm6dsv16x_fsm_long_cnt_timeout_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val int32_t ret; ret = lsm6dsv16x_ln_pg_read(ctx, LSM6DSV16X_EMB_ADV_PG_1 + LSM6DSV16X_FSM_LC_TIMEOUT_L, &buff[0], 2); + if (ret != 0) { + return ret; + } + *val = buff[1]; *val = (*val * 256U) + buff[0]; @@ -5291,6 +6434,10 @@ int32_t lsm6dsv16x_fsm_start_address_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val) int32_t ret; ret = lsm6dsv16x_ln_pg_read(ctx, LSM6DSV16X_EMB_ADV_PG_1 + LSM6DSV16X_FSM_START_ADD_L, &buff[0], 2); + if (ret != 0) { + return ret; + } + *val = buff[1]; *val = (*val * 256U) + buff[0]; @@ -5325,18 +6472,15 @@ int32_t lsm6dsv16x_ff_time_windows_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_WAKE_UP_DUR, (uint8_t *)&wake_up_dur, 1); - if (ret == 0) { - wake_up_dur.ff_dur = ((uint8_t)val & 0x20U) >> 5; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_WAKE_UP_DUR, (uint8_t *)&wake_up_dur, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FREE_FALL, (uint8_t *)&free_fall, 1); + wake_up_dur.ff_dur = ((uint8_t)val & 0x20U) >> 5; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_WAKE_UP_DUR, (uint8_t *)&wake_up_dur, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - free_fall.ff_dur = (uint8_t)val & 0x1FU; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FREE_FALL, (uint8_t *)&free_fall, 1); - } + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FREE_FALL, (uint8_t *)&free_fall, 1); + free_fall.ff_dur = (uint8_t)val & 0x1FU; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_FREE_FALL, (uint8_t *)&free_fall, 1); return ret; } @@ -5356,9 +6500,7 @@ int32_t lsm6dsv16x_ff_time_windows_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_WAKE_UP_DUR, (uint8_t *)&wake_up_dur, 1); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FREE_FALL, (uint8_t *)&free_fall, 1); - } + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FREE_FALL, (uint8_t *)&free_fall, 1); *val = (wake_up_dur.ff_dur << 5) + free_fall.ff_dur; @@ -5373,7 +6515,8 @@ int32_t lsm6dsv16x_ff_time_windows_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ff_thresholds_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ff_thresholds_t val) +int32_t lsm6dsv16x_ff_thresholds_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ff_thresholds_t val) { lsm6dsv16x_free_fall_t free_fall; int32_t ret; @@ -5395,12 +6538,17 @@ int32_t lsm6dsv16x_ff_thresholds_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ff_thresh * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ff_thresholds_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ff_thresholds_t *val) +int32_t lsm6dsv16x_ff_thresholds_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ff_thresholds_t *val) { lsm6dsv16x_free_fall_t free_fall; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FREE_FALL, (uint8_t *)&free_fall, 1); + if (ret != 0) { + return ret; + } + switch (free_fall.ff_ths) { case LSM6DSV16X_156_mg: *val = LSM6DSV16X_156_mg; @@ -5438,6 +6586,7 @@ int32_t lsm6dsv16x_ff_thresholds_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ff_thresh *val = LSM6DSV16X_156_mg; break; } + return ret; } @@ -5458,36 +6607,46 @@ int32_t lsm6dsv16x_ff_thresholds_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ff_thresh * @brief It enables Machine Learning Core feature (MLC). When the Machine Learning Core is enabled the Finite State Machine (FSM) programs are executed before executing the MLC algorithms.[set] * * @param ctx read / write interface definitions - * @param val DISABLE, MLC_BEFORE_FSM, MLC_AFTER_FSM, + * @param val MLC_OFF, MLC_ON, MLC_BEFORE_FSM, * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_mlc_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_mode_t val) +int32_t lsm6dsv16x_mlc_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_mode_t val) { - lsm6dsv16x_emb_func_en_b_t emb_func_en_b; - lsm6dsv16x_emb_func_en_a_t emb_func_en_a; + lsm6dsv16x_emb_func_en_b_t emb_en_b; + lsm6dsv16x_emb_func_en_a_t emb_en_a; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_en_a, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_B, (uint8_t *)&emb_en_b, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_B, (uint8_t *)&emb_func_en_b, 1); - } - emb_func_en_a.mlc_before_fsm_en = (uint8_t)val & 0x01U; - emb_func_en_b.mlc_en = ((uint8_t)val & 0x02U) >> 1; - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_B, (uint8_t *)&emb_func_en_b, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + switch (val) { + case LSM6DSV16X_MLC_OFF: + emb_en_a.mlc_before_fsm_en = 0; + emb_en_b.mlc_en = 0; + break; + case LSM6DSV16X_MLC_ON: + emb_en_a.mlc_before_fsm_en = 0; + emb_en_b.mlc_en = 1; + break; + case LSM6DSV16X_MLC_ON_BEFORE_FSM: + emb_en_a.mlc_before_fsm_en = 1; + emb_en_b.mlc_en = 0; + break; + default: + break; } + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_en_a, 1); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_B, (uint8_t *)&emb_en_b, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + return ret; } @@ -5495,44 +6654,36 @@ int32_t lsm6dsv16x_mlc_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_mode_t val * @brief It enables Machine Learning Core feature (MLC). When the Machine Learning Core is enabled the Finite State Machine (FSM) programs are executed before executing the MLC algorithms.[get] * * @param ctx read / write interface definitions - * @param val DISABLE, MLC_BEFORE_FSM, MLC_AFTER_FSM, + * @param val MLC_OFF, MLC_ON, MLC_BEFORE_FSM, * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_mlc_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_mode_t *val) +int32_t lsm6dsv16x_mlc_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_mode_t *val) { - lsm6dsv16x_emb_func_en_a_t emb_func_en_a; - lsm6dsv16x_emb_func_en_b_t emb_func_en_b; + lsm6dsv16x_emb_func_en_b_t emb_en_b; + lsm6dsv16x_emb_func_en_a_t emb_en_a; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_B, (uint8_t *)&emb_func_en_b, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_en_a, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_B, (uint8_t *)&emb_en_b, 1); + if (ret != 0) { + goto exit; + } + + if (emb_en_a.mlc_before_fsm_en == 0U && emb_en_b.mlc_en == 0U) { + *val = LSM6DSV16X_MLC_OFF; + } else if (emb_en_a.mlc_before_fsm_en == 0U && emb_en_b.mlc_en == 1U) { + *val = LSM6DSV16X_MLC_ON; + } else if (emb_en_a.mlc_before_fsm_en == 1U) { + *val = LSM6DSV16X_MLC_ON_BEFORE_FSM; + } else { + /* Do nothing */ } - switch ((emb_func_en_b.mlc_en << 1) + emb_func_en_a.mlc_before_fsm_en) { - case LSM6DSV16X_DISABLE: - *val = LSM6DSV16X_DISABLE; - break; - - case LSM6DSV16X_MLC_BEFORE_FSM: - *val = LSM6DSV16X_MLC_BEFORE_FSM; - break; +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - case LSM6DSV16X_MLC_AFTER_FSM: - *val = LSM6DSV16X_MLC_AFTER_FSM; - break; - - default: - *val = LSM6DSV16X_DISABLE; - break; - } return ret; } @@ -5544,23 +6695,23 @@ int32_t lsm6dsv16x_mlc_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_mode_t *va * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_mlc_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_data_rate_t val) +int32_t lsm6dsv16x_mlc_data_rate_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_mlc_data_rate_t val) { lsm6dsv16x_mlc_odr_t mlc_odr; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MLC_ODR, (uint8_t *)&mlc_odr, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MLC_ODR, (uint8_t *)&mlc_odr, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - mlc_odr.mlc_odr = (uint8_t)val & 0x07U; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_MLC_ODR, (uint8_t *)&mlc_odr, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + mlc_odr.mlc_odr = (uint8_t)val & 0x07U; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_MLC_ODR, (uint8_t *)&mlc_odr, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -5573,17 +6724,17 @@ int32_t lsm6dsv16x_mlc_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_data_ * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_mlc_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_data_rate_t *val) +int32_t lsm6dsv16x_mlc_data_rate_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_mlc_data_rate_t *val) { lsm6dsv16x_mlc_odr_t mlc_odr; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MLC_ODR, (uint8_t *)&mlc_odr, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MLC_ODR, (uint8_t *)&mlc_odr, 1); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + if (ret != 0) { + return ret; } switch (mlc_odr.mlc_odr) { @@ -5619,6 +6770,7 @@ int32_t lsm6dsv16x_mlc_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_data_ *val = LSM6DSV16X_MLC_15Hz; break; } + return ret; } @@ -5638,9 +6790,8 @@ int32_t lsm6dsv16x_mlc_out_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_out_t *val) if (ret == 0) { ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MLC1_SRC, (uint8_t *)val, 4); } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + return ret; } @@ -5673,12 +6824,17 @@ int32_t lsm6dsv16x_mlc_ext_sens_sensitivity_set(lsm6dsv16x_ctx_t *ctx, uint16_t * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_mlc_ext_sens_sensitivity_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val) +int32_t lsm6dsv16x_mlc_ext_sens_sensitivity_get(lsm6dsv16x_ctx_t *ctx, + uint16_t *val) { uint8_t buff[2]; int32_t ret; ret = lsm6dsv16x_ln_pg_read(ctx, LSM6DSV16X_EMB_ADV_PG_1 + LSM6DSV16X_MLC_EXT_SENSITIVITY_L, &buff[0], 2); + if (ret != 0) { + return ret; + } + *val = buff[1]; *val = (*val * 256U) + buff[0]; @@ -5706,7 +6862,8 @@ int32_t lsm6dsv16x_mlc_ext_sens_sensitivity_get(lsm6dsv16x_ctx_t *ctx, uint16_t * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ois_ctrl_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_ctrl_mode_t val) +int32_t lsm6dsv16x_ois_ctrl_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_ctrl_mode_t val) { lsm6dsv16x_func_cfg_access_t func_cfg_access; int32_t ret; @@ -5728,12 +6885,17 @@ int32_t lsm6dsv16x_ois_ctrl_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_ctrl_ * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ois_ctrl_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_ctrl_mode_t *val) +int32_t lsm6dsv16x_ois_ctrl_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_ctrl_mode_t *val) { lsm6dsv16x_func_cfg_access_t func_cfg_access; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FUNC_CFG_ACCESS, (uint8_t *)&func_cfg_access, 1); + if (ret != 0) { + return ret; + } + switch (func_cfg_access.ois_ctrl_from_ui) { case LSM6DSV16X_OIS_CTRL_FROM_OIS: *val = LSM6DSV16X_OIS_CTRL_FROM_OIS; @@ -5747,6 +6909,7 @@ int32_t lsm6dsv16x_ois_ctrl_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_ctrl_ *val = LSM6DSV16X_OIS_CTRL_FROM_OIS; break; } + return ret; } @@ -5840,7 +7003,8 @@ int32_t lsm6dsv16x_ois_interface_pull_up_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ois_handshake_from_ui_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_handshake_t val) +int32_t lsm6dsv16x_ois_handshake_from_ui_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_handshake_t val) { lsm6dsv16x_ui_handshake_ctrl_t ui_handshake_ctrl; int32_t ret; @@ -5863,12 +7027,17 @@ int32_t lsm6dsv16x_ois_handshake_from_ui_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_o * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ois_handshake_from_ui_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_handshake_t *val) +int32_t lsm6dsv16x_ois_handshake_from_ui_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_handshake_t *val) { lsm6dsv16x_ui_handshake_ctrl_t ui_handshake_ctrl; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_UI_HANDSHAKE_CTRL, (uint8_t *)&ui_handshake_ctrl, 1); + if (ret != 0) { + return ret; + } + val->ack = ui_handshake_ctrl.ui_shared_ack; val->req = ui_handshake_ctrl.ui_shared_req; @@ -5883,7 +7052,8 @@ int32_t lsm6dsv16x_ois_handshake_from_ui_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_o * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ois_handshake_from_ois_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_handshake_t val) +int32_t lsm6dsv16x_ois_handshake_from_ois_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_handshake_t val) { lsm6dsv16x_spi2_handshake_ctrl_t spi2_handshake_ctrl; int32_t ret; @@ -5906,12 +7076,17 @@ int32_t lsm6dsv16x_ois_handshake_from_ois_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ois_handshake_from_ois_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_handshake_t *val) +int32_t lsm6dsv16x_ois_handshake_from_ois_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_handshake_t *val) { lsm6dsv16x_spi2_handshake_ctrl_t spi2_handshake_ctrl; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SPI2_HANDSHAKE_CTRL, (uint8_t *)&spi2_handshake_ctrl, 1); + if (ret != 0) { + return ret; + } + val->ack = spi2_handshake_ctrl.spi2_shared_ack; val->req = spi2_handshake_ctrl.spi2_shared_req; @@ -6030,6 +7205,10 @@ int32_t lsm6dsv16x_ois_chain_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_chain_t * int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_UI_CTRL1_OIS, (uint8_t *)&ui_ctrl1_ois, 1); + if (ret != 0) { + return ret; + } + val->gy = ui_ctrl1_ois.ois_g_en; val->xl = ui_ctrl1_ois.ois_xl_en; @@ -6044,7 +7223,8 @@ int32_t lsm6dsv16x_ois_chain_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_chain_t * * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ois_gy_full_scale_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_gy_full_scale_t val) +int32_t lsm6dsv16x_ois_gy_full_scale_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_gy_full_scale_t val) { lsm6dsv16x_ui_ctrl2_ois_t ui_ctrl2_ois; int32_t ret; @@ -6066,12 +7246,17 @@ int32_t lsm6dsv16x_ois_gy_full_scale_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_g * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ois_gy_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_gy_full_scale_t *val) +int32_t lsm6dsv16x_ois_gy_full_scale_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_gy_full_scale_t *val) { lsm6dsv16x_ui_ctrl2_ois_t ui_ctrl2_ois; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_UI_CTRL2_OIS, (uint8_t *)&ui_ctrl2_ois, 1); + if (ret != 0) { + return ret; + } + switch (ui_ctrl2_ois.fs_g_ois) { case LSM6DSV16X_OIS_125dps: *val = LSM6DSV16X_OIS_125dps; @@ -6097,6 +7282,7 @@ int32_t lsm6dsv16x_ois_gy_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_g *val = LSM6DSV16X_OIS_125dps; break; } + return ret; } @@ -6108,7 +7294,8 @@ int32_t lsm6dsv16x_ois_gy_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_g * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ois_xl_full_scale_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_xl_full_scale_t val) +int32_t lsm6dsv16x_ois_xl_full_scale_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_xl_full_scale_t val) { lsm6dsv16x_ui_ctrl3_ois_t ui_ctrl3_ois; int32_t ret; @@ -6130,12 +7317,17 @@ int32_t lsm6dsv16x_ois_xl_full_scale_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_x * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ois_xl_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_xl_full_scale_t *val) +int32_t lsm6dsv16x_ois_xl_full_scale_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_xl_full_scale_t *val) { lsm6dsv16x_ui_ctrl3_ois_t ui_ctrl3_ois; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_UI_CTRL3_OIS, (uint8_t *)&ui_ctrl3_ois, 1); + if (ret != 0) { + return ret; + } + switch (ui_ctrl3_ois.fs_xl_ois) { case LSM6DSV16X_OIS_2g: *val = LSM6DSV16X_OIS_2g; @@ -6157,6 +7349,7 @@ int32_t lsm6dsv16x_ois_xl_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_x *val = LSM6DSV16X_OIS_2g; break; } + return ret; } @@ -6181,7 +7374,8 @@ int32_t lsm6dsv16x_ois_xl_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_x * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_6d_threshold_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_6d_threshold_t val) +int32_t lsm6dsv16x_6d_threshold_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_6d_threshold_t val) { lsm6dsv16x_tap_ths_6d_t tap_ths_6d; int32_t ret; @@ -6203,12 +7397,17 @@ int32_t lsm6dsv16x_6d_threshold_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_6d_thresho * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_6d_threshold_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_6d_threshold_t *val) +int32_t lsm6dsv16x_6d_threshold_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_6d_threshold_t *val) { lsm6dsv16x_tap_ths_6d_t tap_ths_6d; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_THS_6D, (uint8_t *)&tap_ths_6d, 1); + if (ret != 0) { + return ret; + } + switch (tap_ths_6d.sixd_ths) { case LSM6DSV16X_DEG_80: *val = LSM6DSV16X_DEG_80; @@ -6230,6 +7429,7 @@ int32_t lsm6dsv16x_6d_threshold_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_6d_thresho *val = LSM6DSV16X_DEG_80; break; } + return ret; } @@ -6295,7 +7495,8 @@ int32_t lsm6dsv16x_4d_mode_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ah_qvar_zin_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ah_qvar_zin_t val) +int32_t lsm6dsv16x_ah_qvar_zin_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ah_qvar_zin_t val) { lsm6dsv16x_ctrl7_t ctrl7; int32_t ret; @@ -6317,12 +7518,17 @@ int32_t lsm6dsv16x_ah_qvar_zin_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ah_qvar_zin * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ah_qvar_zin_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ah_qvar_zin_t *val) +int32_t lsm6dsv16x_ah_qvar_zin_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ah_qvar_zin_t *val) { lsm6dsv16x_ctrl7_t ctrl7; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL7, (uint8_t *)&ctrl7, 1); + if (ret != 0) { + return ret; + } + switch (ctrl7.ah_qvar_c_zin) { case LSM6DSV16X_2400MOhm: *val = LSM6DSV16X_2400MOhm; @@ -6344,6 +7550,7 @@ int32_t lsm6dsv16x_ah_qvar_zin_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ah_qvar_zin *val = LSM6DSV16X_2400MOhm; break; } + return ret; } @@ -6355,7 +7562,8 @@ int32_t lsm6dsv16x_ah_qvar_zin_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ah_qvar_zin * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ah_qvar_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ah_qvar_mode_t val) +int32_t lsm6dsv16x_ah_qvar_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ah_qvar_mode_t val) { lsm6dsv16x_ctrl7_t ctrl7; int32_t ret; @@ -6377,7 +7585,8 @@ int32_t lsm6dsv16x_ah_qvar_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ah_qvar_mo * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ah_qvar_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ah_qvar_mode_t *val) +int32_t lsm6dsv16x_ah_qvar_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ah_qvar_mode_t *val) { lsm6dsv16x_ctrl7_t ctrl7; int32_t ret; @@ -6409,7 +7618,8 @@ int32_t lsm6dsv16x_ah_qvar_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ah_qvar_mo * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_i3c_reset_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_i3c_reset_mode_t val) +int32_t lsm6dsv16x_i3c_reset_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_i3c_reset_mode_t val) { lsm6dsv16x_pin_ctrl_t pin_ctrl; int32_t ret; @@ -6431,12 +7641,17 @@ int32_t lsm6dsv16x_i3c_reset_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_i3c_rese * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_i3c_reset_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_i3c_reset_mode_t *val) +int32_t lsm6dsv16x_i3c_reset_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_i3c_reset_mode_t *val) { lsm6dsv16x_pin_ctrl_t pin_ctrl; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_PIN_CTRL, (uint8_t *)&pin_ctrl, 1); + if (ret != 0) { + return ret; + } + switch (pin_ctrl.ibhr_por_en) { case LSM6DSV16X_SW_RST_DYN_ADDRESS_RST: *val = LSM6DSV16X_SW_RST_DYN_ADDRESS_RST; @@ -6450,6 +7665,7 @@ int32_t lsm6dsv16x_i3c_reset_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_i3c_rese *val = LSM6DSV16X_SW_RST_DYN_ADDRESS_RST; break; } + return ret; } @@ -6461,7 +7677,8 @@ int32_t lsm6dsv16x_i3c_reset_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_i3c_rese * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_i3c_ibi_time_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_i3c_ibi_time_t val) +int32_t lsm6dsv16x_i3c_ibi_time_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_i3c_ibi_time_t val) { lsm6dsv16x_ctrl5_t ctrl5; int32_t ret; @@ -6483,12 +7700,17 @@ int32_t lsm6dsv16x_i3c_ibi_time_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_i3c_ibi_ti * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_i3c_ibi_time_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_i3c_ibi_time_t *val) +int32_t lsm6dsv16x_i3c_ibi_time_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_i3c_ibi_time_t *val) { lsm6dsv16x_ctrl5_t ctrl5; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_CTRL5, (uint8_t *)&ctrl5, 1); + if (ret != 0) { + return ret; + } + switch (ctrl5.bus_act_sel) { case LSM6DSV16X_IBI_2us: *val = LSM6DSV16X_IBI_2us; @@ -6510,6 +7732,7 @@ int32_t lsm6dsv16x_i3c_ibi_time_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_i3c_ibi_ti *val = LSM6DSV16X_IBI_2us; break; } + return ret; } @@ -6534,7 +7757,8 @@ int32_t lsm6dsv16x_i3c_ibi_time_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_i3c_ibi_ti * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_sh_master_interface_pull_up_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) +int32_t lsm6dsv16x_sh_master_interface_pull_up_set(lsm6dsv16x_ctx_t *ctx, + uint8_t val) { lsm6dsv16x_if_cfg_t if_cfg; int32_t ret; @@ -6556,7 +7780,8 @@ int32_t lsm6dsv16x_sh_master_interface_pull_up_set(lsm6dsv16x_ctx_t *ctx, uint8_ * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_sh_master_interface_pull_up_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) +int32_t lsm6dsv16x_sh_master_interface_pull_up_get(lsm6dsv16x_ctx_t *ctx, + uint8_t *val) { lsm6dsv16x_if_cfg_t if_cfg; int32_t ret; @@ -6575,21 +7800,14 @@ int32_t lsm6dsv16x_sh_master_interface_pull_up_get(lsm6dsv16x_ctx_t *ctx, uint8_ * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_sh_read_data_raw_get(lsm6dsv16x_ctx_t *ctx, - lsm6dsv16x_emb_sh_read_t *val, +int32_t lsm6dsv16x_sh_read_data_raw_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val, uint8_t len) { int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SENSOR_HUB_1, (uint8_t *) val, - len); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } - + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SENSOR_HUB_1, val, len); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -6602,23 +7820,23 @@ int32_t lsm6dsv16x_sh_read_data_raw_get(lsm6dsv16x_ctx_t *ctx, * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_sh_slave_connected_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_slave_connected_t val) +int32_t lsm6dsv16x_sh_slave_connected_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sh_slave_connected_t val) { lsm6dsv16x_master_config_t master_config; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - master_config.aux_sens_on = (uint8_t)val & 0x3U; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + master_config.aux_sens_on = (uint8_t)val & 0x3U; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -6631,17 +7849,17 @@ int32_t lsm6dsv16x_sh_slave_connected_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_s * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_sh_slave_connected_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_slave_connected_t *val) +int32_t lsm6dsv16x_sh_slave_connected_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sh_slave_connected_t *val) { lsm6dsv16x_master_config_t master_config; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + if (ret != 0) { + return ret; } switch (master_config.aux_sens_on) { @@ -6665,6 +7883,7 @@ int32_t lsm6dsv16x_sh_slave_connected_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_s *val = LSM6DSV16X_SLV_0; break; } + return ret; } @@ -6682,17 +7901,16 @@ int32_t lsm6dsv16x_sh_master_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - master_config.master_on = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + master_config.master_on = val; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -6711,15 +7929,11 @@ int32_t lsm6dsv16x_sh_master_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); - } + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); *val = master_config.master_on; - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -6738,17 +7952,16 @@ int32_t lsm6dsv16x_sh_pass_through_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - master_config.pass_through_mode = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + master_config.pass_through_mode = val; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -6767,15 +7980,11 @@ int32_t lsm6dsv16x_sh_pass_through_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); - } + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); *val = master_config.pass_through_mode; - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -6788,23 +7997,23 @@ int32_t lsm6dsv16x_sh_pass_through_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_sh_syncro_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_syncro_mode_t val) +int32_t lsm6dsv16x_sh_syncro_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sh_syncro_mode_t val) { lsm6dsv16x_master_config_t master_config; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - master_config.start_config = (uint8_t)val & 0x01U; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + master_config.start_config = (uint8_t)val & 0x01U; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -6817,17 +8026,17 @@ int32_t lsm6dsv16x_sh_syncro_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_syncr * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_sh_syncro_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_syncro_mode_t *val) +int32_t lsm6dsv16x_sh_syncro_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sh_syncro_mode_t *val) { lsm6dsv16x_master_config_t master_config; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + if (ret != 0) { + return ret; } switch (master_config.start_config) { @@ -6843,6 +8052,7 @@ int32_t lsm6dsv16x_sh_syncro_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_syncr *val = LSM6DSV16X_SH_TRG_XL_GY_DRDY; break; } + return ret; } @@ -6854,23 +8064,23 @@ int32_t lsm6dsv16x_sh_syncro_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_syncr * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_sh_write_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_write_mode_t val) +int32_t lsm6dsv16x_sh_write_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sh_write_mode_t val) { lsm6dsv16x_master_config_t master_config; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - master_config.write_once = (uint8_t)val & 0x01U; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + master_config.write_once = (uint8_t)val & 0x01U; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -6883,19 +8093,18 @@ int32_t lsm6dsv16x_sh_write_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_write_ * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_sh_write_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_write_mode_t *val) +int32_t lsm6dsv16x_sh_write_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sh_write_mode_t *val) { lsm6dsv16x_master_config_t master_config; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + if (ret != 0) { + return ret; } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } - switch (master_config.write_once) { case LSM6DSV16X_EACH_SH_CYCLE: @@ -6910,6 +8119,7 @@ int32_t lsm6dsv16x_sh_write_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_write_ *val = LSM6DSV16X_EACH_SH_CYCLE; break; } + return ret; } @@ -6927,17 +8137,16 @@ int32_t lsm6dsv16x_sh_reset_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - master_config.rst_master_regs = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + master_config.rst_master_regs = val; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -6956,15 +8165,11 @@ int32_t lsm6dsv16x_sh_reset_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); - } + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_MASTER_CONFIG, (uint8_t *)&master_config, 1); *val = master_config.rst_master_regs; - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -6987,25 +8192,28 @@ int32_t lsm6dsv16x_sh_cfg_write(lsm6dsv16x_ctx_t *ctx, int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - reg.slave0_add = val->slv0_add; - reg.rw_0 = 0; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV0_ADD, (uint8_t *)®, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV0_SUBADD, - &(val->slv0_subadd), 1); + reg.slave0_add = val->slv0_add; + reg.rw_0 = 0; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV0_ADD, (uint8_t *)®, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_DATAWRITE_SLV0, - &(val->slv0_data), 1); + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV0_SUBADD, + &(val->slv0_subadd), 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_DATAWRITE_SLV0, + &(val->slv0_data), 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -7018,23 +8226,23 @@ int32_t lsm6dsv16x_sh_cfg_write(lsm6dsv16x_ctx_t *ctx, * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_sh_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_data_rate_t val) +int32_t lsm6dsv16x_sh_data_rate_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sh_data_rate_t val) { lsm6dsv16x_slv0_config_t slv0_config; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV0_CONFIG, (uint8_t *)&slv0_config, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV0_CONFIG, (uint8_t *)&slv0_config, 1); + if (ret != 0) { + goto exit; } - if (ret == 0) { - slv0_config.shub_odr = (uint8_t)val & 0x07U; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV0_CONFIG, (uint8_t *)&slv0_config, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + slv0_config.shub_odr = (uint8_t)val & 0x07U; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV0_CONFIG, (uint8_t *)&slv0_config, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -7047,17 +8255,17 @@ int32_t lsm6dsv16x_sh_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_data_ra * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_sh_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_data_rate_t *val) +int32_t lsm6dsv16x_sh_data_rate_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sh_data_rate_t *val) { lsm6dsv16x_slv0_config_t slv0_config; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV0_CONFIG, (uint8_t *)&slv0_config, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV0_CONFIG, (uint8_t *)&slv0_config, 1); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + if (ret != 0) { + return ret; } switch (slv0_config.shub_odr) { @@ -7089,396 +8297,77 @@ int32_t lsm6dsv16x_sh_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_data_ra *val = LSM6DSV16X_SH_15Hz; break; } - return ret; -} - -/** - * @brief Configure slave 0 for perform a read.[set] - * - * @param ctx read / write interface definitions - * @param val Structure that contain - * - uint8_t slv1_add; 8 bit i2c device address - * - uint8_t slv1_subadd; 8 bit register device address - * - uint8_t slv1_len; num of bit to read - * @retval interface status (MANDATORY: return 0 -> no Error) - * - */ -int32_t lsm6dsv16x_sh_slv0_cfg_read(lsm6dsv16x_ctx_t *ctx, - lsm6dsv16x_sh_cfg_read_t *val) -{ - lsm6dsv16x_slv0_add_t slv0_add; - lsm6dsv16x_slv0_config_t slv0_config; - int32_t ret; - - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - - if (ret == 0) { - slv0_add.slave0_add = val->slv_add; - slv0_add.rw_0 = 1; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV0_ADD, (uint8_t *)&slv0_add, 1); - } - - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV0_SUBADD, - &(val->slv_subadd), 1); - } - - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV0_CONFIG, - (uint8_t *)&slv0_config, 1); - } - - if (ret == 0) { - slv0_config.slave0_numop = val->slv_len; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV0_CONFIG, - (uint8_t *)&slv0_config, 1); - } - - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } - - return ret; -} - -/** - * @brief Configure slave 0 for perform a write/read.[set] - * - * @param ctx read / write interface definitions - * @param val Structure that contain - * - uint8_t slv1_add; 8 bit i2c device address - * - uint8_t slv1_subadd; 8 bit register device address - * - uint8_t slv1_len; num of bit to read - * @retval interface status (MANDATORY: return 0 -> no Error) - * - */ -int32_t lsm6dsv16x_sh_slv1_cfg_read(lsm6dsv16x_ctx_t *ctx, - lsm6dsv16x_sh_cfg_read_t *val) -{ - lsm6dsv16x_slv1_add_t slv1_add; - lsm6dsv16x_slv1_config_t slv1_config; - int32_t ret; - - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - - if (ret == 0) { - slv1_add.slave1_add = val->slv_add; - slv1_add.r_1 = 1; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV1_ADD, (uint8_t *)&slv1_add, 1); - } - - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV1_SUBADD, - &(val->slv_subadd), 1); - } - - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV1_CONFIG, - (uint8_t *)&slv1_config, 1); - } - - if (ret == 0) { - slv1_config.slave1_numop = val->slv_len; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV1_CONFIG, - (uint8_t *)&slv1_config, 1); - } - - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } return ret; } /** - * @brief Configure slave 0 for perform a write/read.[set] + * @brief Configure slave idx for perform a read.[set] * * @param ctx read / write interface definitions * @param val Structure that contain - * - uint8_t slv2_add; 8 bit i2c device address - * - uint8_t slv2_subadd; 8 bit register device address - * - uint8_t slv2_len; num of bit to read + * - uint8_t slv_add; 8 bit i2c device address + * - uint8_t slv_subadd; 8 bit register device address + * - uint8_t slv_len; num of bit to read * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_sh_slv2_cfg_read(lsm6dsv16x_ctx_t *ctx, - lsm6dsv16x_sh_cfg_read_t *val) +int32_t lsm6dsv16x_sh_slv_cfg_read(lsm6dsv16x_ctx_t *ctx, uint8_t idx, + lsm6dsv16x_sh_cfg_read_t *val) { - lsm6dsv16x_slv2_add_t slv2_add; - lsm6dsv16x_slv2_config_t slv2_config; + lsm6dsv16x_slv0_add_t slv_add; + lsm6dsv16x_slv0_config_t slv_config; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - - if (ret == 0) { - slv2_add.slave2_add = val->slv_add; - slv2_add.r_2 = 1; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV2_ADD, (uint8_t *)&slv2_add, 1); - } - - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV2_SUBADD, - &(val->slv_subadd), 1); - } - - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV2_CONFIG, - (uint8_t *)&slv2_config, 1); - } - - if (ret == 0) { - slv2_config.slave2_numop = val->slv_len; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV2_CONFIG, - (uint8_t *)&slv2_config, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } - - return ret; -} - -/** - * @brief Configure slave 0 for perform a write/read.[set] - * - * @param ctx read / write interface definitions - * @param val Structure that contain - * - uint8_t slv3_add; 8 bit i2c device address - * - uint8_t slv3_subadd; 8 bit register device address - * - uint8_t slv3_len; num of bit to read - * @retval interface status (MANDATORY: return 0 -> no Error) - * - */ -int32_t lsm6dsv16x_sh_slv3_cfg_read(lsm6dsv16x_ctx_t *ctx, - lsm6dsv16x_sh_cfg_read_t *val) -{ - lsm6dsv16x_slv3_add_t slv3_add; - lsm6dsv16x_slv3_config_t slv3_config; - int32_t ret; - - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_SENSOR_HUB_MEM_BANK); - - if (ret == 0) { - slv3_add.slave3_add = val->slv_add; - slv3_add.r_3 = 1; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV3_ADD, (uint8_t *)&slv3_add, 1); - } - - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV3_SUBADD, - &(val->slv_subadd), 1); - } - - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV3_CONFIG, - (uint8_t *)&slv3_config, 1); - } - - if (ret == 0) { - slv3_config.slave3_numop = val->slv_len; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV3_CONFIG, - (uint8_t *)&slv3_config, 1); - } - - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } - - return ret; -} - -/** - * @} - * - */ - -/** - * @defgroup Sensors for Smart Mobile Devices (S4S) - * @brief This section groups all the functions that manage the - * Sensors for Smart Mobile Devices. - * @{ - * - */ - -/** - * @brief Sensor synchronization time frame register expressed in number of samples[set] - * - * @param ctx read / write interface definitions - * @param val Sensor synchronization time frame register expressed in number of samples - * @retval interface status (MANDATORY: return 0 -> no Error) - * - */ -int32_t lsm6dsv16x_s4s_sync_samples_set(lsm6dsv16x_ctx_t *ctx, uint16_t val) -{ - uint8_t buff[2]; - int32_t ret; - - buff[1] = (uint8_t)(val / 256U); - buff[0] = (uint8_t)(val - (buff[1] * 256U)); - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_S4S_TPH_L, (uint8_t *)&buff[0], 2); - - return ret; -} - -/** - * @brief Sensor synchronization time frame register expressed in number of samples[get] - * - * @param ctx read / write interface definitions - * @param val Sensor synchronization time frame register expressed in number of samples - * @retval interface status (MANDATORY: return 0 -> no Error) - * - */ -int32_t lsm6dsv16x_s4s_sync_samples_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val) -{ - uint8_t buff[2]; - int32_t ret; - - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_S4S_TPH_L, &buff[0], 2); - *val = buff[1]; - *val = (*val * 256U) + buff[0]; - - return ret; -} - -/** - * @brief Sensor synchronization resolution ratio.[set] - * - * @param ctx read / write interface definitions - * @param val S4S_DT_RES_11, S4S_DT_RES_12, S4S_DT_RES_13, S4S_DT_RES_14, - * @retval interface status (MANDATORY: return 0 -> no Error) - * - */ -int32_t lsm6dsv16x_s4s_res_ratio_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_s4s_res_ratio_t val) -{ - lsm6dsv16x_s4s_rr_t s4s_rr; - int32_t ret; - - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_S4S_RR, (uint8_t *)&s4s_rr, 1); - if (ret == 0) { - s4s_rr.rr = (uint8_t)val & 0x3U; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_S4S_RR, (uint8_t *)&s4s_rr, 1); - } - - return ret; -} - -/** - * @brief Sensor synchronization resolution ratio.[get] - * - * @param ctx read / write interface definitions - * @param val S4S_DT_RES_11, S4S_DT_RES_12, S4S_DT_RES_13, S4S_DT_RES_14, - * @retval interface status (MANDATORY: return 0 -> no Error) - * - */ -int32_t lsm6dsv16x_s4s_res_ratio_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_s4s_res_ratio_t *val) -{ - lsm6dsv16x_s4s_rr_t s4s_rr; - int32_t ret; - - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_S4S_RR, (uint8_t *)&s4s_rr, 1); - switch (s4s_rr.rr) { - case LSM6DSV16X_S4S_DT_RES_11: - *val = LSM6DSV16X_S4S_DT_RES_11; - break; - - case LSM6DSV16X_S4S_DT_RES_12: - *val = LSM6DSV16X_S4S_DT_RES_12; - break; - - case LSM6DSV16X_S4S_DT_RES_13: - *val = LSM6DSV16X_S4S_DT_RES_13; - break; - - case LSM6DSV16X_S4S_DT_RES_14: - *val = LSM6DSV16X_S4S_DT_RES_14; - break; - - default: - *val = LSM6DSV16X_S4S_DT_RES_11; - break; - } - return ret; -} - -/** - * @brief Master command code used for S4S.[set] - * - * @param ctx read / write interface definitions - * @param val Master command code used for S4S. - * @retval interface status (MANDATORY: return 0 -> no Error) - * - */ -int32_t lsm6dsv16x_s4s_command_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) -{ - lsm6dsv16x_s4s_st_cmd_code_t s4s_st_cmd_code; - int32_t ret; - - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_S4S_ST_CMD_CODE, (uint8_t *)&s4s_st_cmd_code, 1); - if (ret == 0) { - s4s_st_cmd_code.st_cmd_code = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_S4S_ST_CMD_CODE, (uint8_t *)&s4s_st_cmd_code, 1); - } - - return ret; -} - -/** - * @brief Master command code used for S4S.[get] - * - * @param ctx read / write interface definitions - * @param val Master command code used for S4S. - * @retval interface status (MANDATORY: return 0 -> no Error) - * - */ -int32_t lsm6dsv16x_s4s_command_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) -{ - lsm6dsv16x_s4s_st_cmd_code_t s4s_st_cmd_code; - int32_t ret; - - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_S4S_ST_CMD_CODE, (uint8_t *)&s4s_st_cmd_code, 1); - *val = s4s_st_cmd_code.st_cmd_code; - - return ret; -} - -/** - * @brief DT used for S4S.[set] - * - * @param ctx read / write interface definitions - * @param val DT used for S4S. - * @retval interface status (MANDATORY: return 0 -> no Error) - * - */ -int32_t lsm6dsv16x_s4s_dt_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) -{ - lsm6dsv16x_s4s_dt_reg_t s4s_dt_reg; - int32_t ret; + slv_add.slave0_add = val->slv_add; + slv_add.rw_0 = 1; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV0_ADD + idx * 3U, + (uint8_t *)&slv_add, 1); + if (ret != 0) { + goto exit; + } - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_S4S_DT_REG, (uint8_t *)&s4s_dt_reg, 1); - if (ret == 0) { - s4s_dt_reg.dt = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_S4S_DT_REG, (uint8_t *)&s4s_dt_reg, 1); + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV0_SUBADD + idx * 3U, + &(val->slv_subadd), 1); + if (ret != 0) { + goto exit; + } + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SLV0_CONFIG + idx * 3U, + (uint8_t *)&slv_config, 1); + if (ret != 0) { + goto exit; } + slv_config.slave0_numop = val->slv_len; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SLV0_CONFIG + idx * 3U, + (uint8_t *)&slv_config, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + return ret; } /** - * @brief DT used for S4S.[get] + * @brief Sensor hub source register.[get] * * @param ctx read / write interface definitions - * @param val DT used for S4S. + * @param val union of registers from STATUS_MASTER to * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_s4s_dt_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) +int32_t lsm6dsv16x_sh_status_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_status_master_t *val) { - lsm6dsv16x_s4s_dt_reg_t s4s_dt_reg; int32_t ret; - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_S4S_DT_REG, (uint8_t *)&s4s_dt_reg, 1); - *val = s4s_dt_reg.dt; + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_STATUS_MASTER_MAINPAGE, (uint8_t *) val, 1); return ret; } @@ -7545,7 +8434,8 @@ int32_t lsm6dsv16x_ui_sdo_pull_up_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ui_i2c_i3c_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ui_i2c_i3c_mode_t val) +int32_t lsm6dsv16x_ui_i2c_i3c_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ui_i2c_i3c_mode_t val) { lsm6dsv16x_if_cfg_t if_cfg; int32_t ret; @@ -7567,12 +8457,17 @@ int32_t lsm6dsv16x_ui_i2c_i3c_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ui_i2c_ * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_ui_i2c_i3c_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ui_i2c_i3c_mode_t *val) +int32_t lsm6dsv16x_ui_i2c_i3c_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ui_i2c_i3c_mode_t *val) { lsm6dsv16x_if_cfg_t if_cfg; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_IF_CFG, (uint8_t *)&if_cfg, 1); + if (ret != 0) { + return ret; + } + switch (if_cfg.i2c_i3c_disable) { case LSM6DSV16X_I2C_I3C_ENABLE: *val = LSM6DSV16X_I2C_I3C_ENABLE; @@ -7586,6 +8481,7 @@ int32_t lsm6dsv16x_ui_i2c_i3c_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ui_i2c_ *val = LSM6DSV16X_I2C_I3C_ENABLE; break; } + return ret; } @@ -7625,6 +8521,10 @@ int32_t lsm6dsv16x_spi_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_spi_mode_t *va int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_IF_CFG, (uint8_t *)&if_cfg, 1); + if (ret != 0) { + return ret; + } + switch (if_cfg.sim) { case LSM6DSV16X_SPI_4_WIRE: *val = LSM6DSV16X_SPI_4_WIRE; @@ -7638,6 +8538,7 @@ int32_t lsm6dsv16x_spi_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_spi_mode_t *va *val = LSM6DSV16X_SPI_4_WIRE; break; } + return ret; } @@ -7683,7 +8584,7 @@ int32_t lsm6dsv16x_ui_sda_pull_up_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) } /** - * @brief SPI2 (OIS Interface) Serial Interface Mode selection. This function works also on OIS (UI_CTRL1_OIS = SPI2_CTRL1_OIS).[set] + * @brief SPI2 (OIS interface) Serial Interface Mode selection. This function works also on OIS (UI_CTRL1_OIS = SPI2_CTRL1_OIS).[set] * * @param ctx read / write interface definitions * @param val SPI2_4_WIRE, SPI2_3_WIRE, @@ -7705,7 +8606,7 @@ int32_t lsm6dsv16x_spi2_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_spi2_mode_t v } /** - * @brief SPI2 (OIS Interface) Serial Interface Mode selection. This function works also on OIS (UI_CTRL1_OIS = SPI2_CTRL1_OIS).[get] + * @brief SPI2 (OIS interface) Serial Interface Mode selection. This function works also on OIS (UI_CTRL1_OIS = SPI2_CTRL1_OIS).[get] * * @param ctx read / write interface definitions * @param val SPI2_4_WIRE, SPI2_3_WIRE, @@ -7718,6 +8619,10 @@ int32_t lsm6dsv16x_spi2_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_spi2_mode_t * int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_UI_CTRL1_OIS, (uint8_t *)&ui_ctrl1_ois, 1); + if (ret != 0) { + return ret; + } + switch (ui_ctrl1_ois.sim_ois) { case LSM6DSV16X_SPI2_4_WIRE: *val = LSM6DSV16X_SPI2_4_WIRE; @@ -7731,6 +8636,7 @@ int32_t lsm6dsv16x_spi2_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_spi2_mode_t * *val = LSM6DSV16X_SPI2_4_WIRE; break; } + return ret; } @@ -7762,17 +8668,15 @@ int32_t lsm6dsv16x_sigmot_mode_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); - } - if (ret == 0) { - emb_func_en_a.sign_motion_en = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + if (ret != 0) { + return ret; } + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); + emb_func_en_a.sign_motion_en = val; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); + + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -7791,14 +8695,14 @@ int32_t lsm6dsv16x_sigmot_mode_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); + if (ret != 0) { + return ret; } + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); *val = emb_func_en_a.sign_motion_en; - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -7823,7 +8727,8 @@ int32_t lsm6dsv16x_sigmot_mode_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_stpcnt_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_stpcnt_mode_t val) +int32_t lsm6dsv16x_stpcnt_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_stpcnt_mode_t val) { lsm6dsv16x_emb_func_en_a_t emb_func_en_a; lsm6dsv16x_emb_func_en_b_t emb_func_en_b; @@ -7831,29 +8736,32 @@ int32_t lsm6dsv16x_stpcnt_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_stpcnt_mode int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_B, (uint8_t *)&emb_func_en_b, 1); + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_B, (uint8_t *)&emb_func_en_b, 1); + if (ret != 0) { + goto exit; } - if ((val.false_step_rej == PROPERTY_ENABLE) && ((emb_func_en_a.mlc_before_fsm_en & emb_func_en_b.mlc_en) == PROPERTY_DISABLE)) { + + if ((val.false_step_rej == PROPERTY_ENABLE) + && ((emb_func_en_a.mlc_before_fsm_en & emb_func_en_b.mlc_en) == + PROPERTY_DISABLE)) { emb_func_en_a.mlc_before_fsm_en = PROPERTY_ENABLE; } - if (ret == 0) { - emb_func_en_a.pedo_en = val.step_counter_enable; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + + emb_func_en_a.pedo_en = val.step_counter_enable; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); if (ret == 0) { ret = lsm6dsv16x_ln_pg_read(ctx, LSM6DSV16X_EMB_ADV_PG_1 + LSM6DSV16X_PEDO_CMD_REG, (uint8_t *)&pedo_cmd_reg, 1); - } - if (ret == 0) { pedo_cmd_reg.fp_rejection_en = val.false_step_rej; - ret = lsm6dsv16x_ln_pg_write(ctx, LSM6DSV16X_EMB_ADV_PG_1 + LSM6DSV16X_PEDO_CMD_REG, (uint8_t *)&pedo_cmd_reg, 1); + ret += lsm6dsv16x_ln_pg_write(ctx, LSM6DSV16X_EMB_ADV_PG_1 + LSM6DSV16X_PEDO_CMD_REG, (uint8_t *)&pedo_cmd_reg, 1); } return ret; @@ -7867,23 +8775,25 @@ int32_t lsm6dsv16x_stpcnt_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_stpcnt_mode * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_stpcnt_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_stpcnt_mode_t *val) +int32_t lsm6dsv16x_stpcnt_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_stpcnt_mode_t *val) { lsm6dsv16x_emb_func_en_a_t emb_func_en_a; lsm6dsv16x_pedo_cmd_reg_t pedo_cmd_reg; int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + if (ret != 0) { + return ret; } - if (ret == 0) { - ret = lsm6dsv16x_ln_pg_read(ctx, LSM6DSV16X_EMB_ADV_PG_1 + LSM6DSV16X_PEDO_CMD_REG, (uint8_t *)&pedo_cmd_reg, 1); + ret = lsm6dsv16x_ln_pg_read(ctx, LSM6DSV16X_EMB_ADV_PG_1 + LSM6DSV16X_PEDO_CMD_REG, (uint8_t *)&pedo_cmd_reg, 1); + if (ret != 0) { + return ret; } + val->false_step_rej = pedo_cmd_reg.fp_rejection_en; val->step_counter_enable = emb_func_en_a.pedo_en; @@ -7904,12 +8814,12 @@ int32_t lsm6dsv16x_stpcnt_steps_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_STEP_COUNTER_L, &buff[0], 2); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_STEP_COUNTER_L, &buff[0], 2); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + if (ret != 0) { + return ret; } + *val = buff[1]; *val = (*val * 256U) + buff[0]; @@ -7930,18 +8840,21 @@ int32_t lsm6dsv16x_stpcnt_rst_step_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_SRC, (uint8_t *)&emb_func_src, 1); + if (ret != 0) { + return ret; } - if (ret == 0) { - emb_func_src.pedo_rst_step = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_SRC, (uint8_t *)&emb_func_src, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_SRC, (uint8_t *)&emb_func_src, 1); + if (ret != 0) { + goto exit; } + emb_func_src.pedo_rst_step = val; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_SRC, (uint8_t *)&emb_func_src, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + return ret; } @@ -7959,15 +8872,14 @@ int32_t lsm6dsv16x_stpcnt_rst_step_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_SRC, (uint8_t *)&emb_func_src, 1); + if (ret != 0) { + return ret; } + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_SRC, (uint8_t *)&emb_func_src, 1); *val = emb_func_src.pedo_rst_step; - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -8047,12 +8959,174 @@ int32_t lsm6dsv16x_stpcnt_period_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val) int32_t ret; ret = lsm6dsv16x_ln_pg_read(ctx, LSM6DSV16X_EMB_ADV_PG_1 + LSM6DSV16X_PEDO_SC_DELTAT_L, &buff[0], 2); + if (ret != 0) { + return ret; + } + *val = buff[1]; *val = (*val * 256U) + buff[0]; return ret; } +/** + * @} + * + */ + +/** + * @defgroup Sensor Fusion Low Power (SFLP) + * @brief This section groups all the functions that manage pedometer. + * @{ + * + */ + +/** + * @brief Enable SFLP Game Rotation Vector (6x).[set] + * + * @param ctx read / write interface definitions + * @param val Enable/Disable game rotation value (0/1). + * @retval interface status (MANDATORY: return 0 -> no Error) + * + */ +int32_t lsm6dsv16x_sflp_game_rotation_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) +{ + lsm6dsv16x_emb_func_en_a_t emb_func_en_a; + int32_t ret; + + ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); + if (ret != 0) { + return ret; + } + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); + if (ret != 0) { + goto exit; + } + + emb_func_en_a.sflp_game_en = val; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, + (uint8_t *)&emb_func_en_a, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + + return ret; +} + +/** + * @brief Enable SFLP Game Rotation Vector (6x).[get] + * + * @param ctx read / write interface definitions + * @param val Enable/Disable game rotation value (0/1). + * @retval interface status (MANDATORY: return 0 -> no Error) + * + */ +int32_t lsm6dsv16x_sflp_game_rotation_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) +{ + lsm6dsv16x_emb_func_en_a_t emb_func_en_a; + int32_t ret; + + ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); + if (ret != 0) { + return ret; + } + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); + *val = emb_func_en_a.sflp_game_en; + + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + + return ret; +} + +/** + * @brief SFLP Data Rate (ODR) configuration.[set] + * + * @param ctx read / write interface definitions + * @param val SFLP_15Hz, SFLP_30Hz, SFLP_60Hz, SFLP_120Hz, SFLP_240Hz, SFLP_480Hz + * @retval interface status (MANDATORY: return 0 -> no Error) + * + */ +int32_t lsm6dsv16x_sflp_data_rate_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sflp_data_rate_t val) +{ + lsm6dsv16x_sflp_odr_t sflp_odr; + int32_t ret; + + ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); + if (ret != 0) { + return ret; + } + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SFLP_ODR, (uint8_t *)&sflp_odr, 1); + if (ret != 0) { + goto exit; + } + + sflp_odr.sflp_game_odr = (uint8_t)val & 0x07U; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_SFLP_ODR, (uint8_t *)&sflp_odr, 1); + +exit: + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + + return ret; +} + +/** + * @brief SFLP Data Rate (ODR) configuration.[get] + * + * @param ctx read / write interface definitions + * @param val SFLP_15Hz, SFLP_30Hz, SFLP_60Hz, SFLP_120Hz, SFLP_240Hz, SFLP_480Hz + * @retval interface status (MANDATORY: return 0 -> no Error) + * + */ +int32_t lsm6dsv16x_sflp_data_rate_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sflp_data_rate_t *val) +{ + lsm6dsv16x_sflp_odr_t sflp_odr; + int32_t ret; + + ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_SFLP_ODR, (uint8_t *)&sflp_odr, 1); + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + if (ret != 0) { + return ret; + } + + switch (sflp_odr.sflp_game_odr) { + case LSM6DSV16X_SFLP_15Hz: + *val = LSM6DSV16X_SFLP_15Hz; + break; + + case LSM6DSV16X_SFLP_30Hz: + *val = LSM6DSV16X_SFLP_30Hz; + break; + + case LSM6DSV16X_SFLP_60Hz: + *val = LSM6DSV16X_SFLP_60Hz; + break; + + case LSM6DSV16X_SFLP_120Hz: + *val = LSM6DSV16X_SFLP_120Hz; + break; + + case LSM6DSV16X_SFLP_240Hz: + *val = LSM6DSV16X_SFLP_240Hz; + break; + + case LSM6DSV16X_SFLP_480Hz: + *val = LSM6DSV16X_SFLP_480Hz; + break; + + default: + *val = LSM6DSV16X_SFLP_15Hz; + break; + } + + return ret; +} + /** * @} * @@ -8074,16 +9148,17 @@ int32_t lsm6dsv16x_stpcnt_period_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val) * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_tap_detection_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_detection_t val) +int32_t lsm6dsv16x_tap_detection_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_tap_detection_t val) { lsm6dsv16x_tap_cfg0_t tap_cfg0; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG0, (uint8_t *)&tap_cfg0, 1); if (ret == 0) { - tap_cfg0.tap_z_en = val.tap_x_en; + tap_cfg0.tap_x_en = val.tap_x_en; tap_cfg0.tap_y_en = val.tap_y_en; - tap_cfg0.tap_x_en = val.tap_z_en; + tap_cfg0.tap_z_en = val.tap_z_en; ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_TAP_CFG0, (uint8_t *)&tap_cfg0, 1); } @@ -8098,13 +9173,18 @@ int32_t lsm6dsv16x_tap_detection_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_detec * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_tap_detection_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_detection_t *val) +int32_t lsm6dsv16x_tap_detection_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_tap_detection_t *val) { lsm6dsv16x_tap_cfg0_t tap_cfg0; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG0, (uint8_t *)&tap_cfg0, 1); - val->tap_x_en = tap_cfg0.tap_z_en; + if (ret != 0) { + return ret; + } + + val->tap_x_en = tap_cfg0.tap_x_en; val->tap_y_en = tap_cfg0.tap_y_en; val->tap_z_en = tap_cfg0.tap_z_en; @@ -8119,7 +9199,8 @@ int32_t lsm6dsv16x_tap_detection_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_detec * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_tap_thresholds_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_thresholds_t val) +int32_t lsm6dsv16x_tap_thresholds_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_tap_thresholds_t val) { lsm6dsv16x_tap_ths_6d_t tap_ths_6d; lsm6dsv16x_tap_cfg2_t tap_cfg2; @@ -8127,26 +9208,19 @@ int32_t lsm6dsv16x_tap_thresholds_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_thre int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG1, (uint8_t *)&tap_cfg1, 1); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG2, (uint8_t *)&tap_cfg2, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_THS_6D, (uint8_t *)&tap_ths_6d, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG2, (uint8_t *)&tap_cfg2, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_THS_6D, (uint8_t *)&tap_ths_6d, 1); + if (ret != 0) { + return ret; } tap_cfg1.tap_ths_x = val.x; tap_cfg2.tap_ths_y = val.y; tap_ths_6d.tap_ths_z = val.z; - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_TAP_THS_6D, (uint8_t *)&tap_ths_6d, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_TAP_CFG2, (uint8_t *)&tap_cfg2, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_TAP_CFG1, (uint8_t *)&tap_cfg1, 1); - } + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_TAP_THS_6D, (uint8_t *)&tap_ths_6d, 1); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_TAP_CFG2, (uint8_t *)&tap_cfg2, 1); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_TAP_CFG1, (uint8_t *)&tap_cfg1, 1); return ret; } @@ -8159,7 +9233,8 @@ int32_t lsm6dsv16x_tap_thresholds_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_thre * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_tap_thresholds_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_thresholds_t *val) +int32_t lsm6dsv16x_tap_thresholds_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_tap_thresholds_t *val) { lsm6dsv16x_tap_ths_6d_t tap_ths_6d; lsm6dsv16x_tap_cfg2_t tap_cfg2; @@ -8167,11 +9242,10 @@ int32_t lsm6dsv16x_tap_thresholds_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_thre int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG1, (uint8_t *)&tap_cfg1, 1); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG2, (uint8_t *)&tap_cfg2, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_THS_6D, (uint8_t *)&tap_ths_6d, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG2, (uint8_t *)&tap_cfg2, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_THS_6D, (uint8_t *)&tap_ths_6d, 1); + if (ret != 0) { + return ret; } val->x = tap_cfg1.tap_ths_x; @@ -8189,7 +9263,8 @@ int32_t lsm6dsv16x_tap_thresholds_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_thre * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_tap_axis_priority_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_axis_priority_t val) +int32_t lsm6dsv16x_tap_axis_priority_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_tap_axis_priority_t val) { lsm6dsv16x_tap_cfg1_t tap_cfg1; int32_t ret; @@ -8211,12 +9286,17 @@ int32_t lsm6dsv16x_tap_axis_priority_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_a * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_tap_axis_priority_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_axis_priority_t *val) +int32_t lsm6dsv16x_tap_axis_priority_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_tap_axis_priority_t *val) { lsm6dsv16x_tap_cfg1_t tap_cfg1; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_CFG1, (uint8_t *)&tap_cfg1, 1); + if (ret != 0) { + return ret; + } + switch (tap_cfg1.tap_priority) { case LSM6DSV16X_XYZ : *val = LSM6DSV16X_XYZ ; @@ -8246,6 +9326,7 @@ int32_t lsm6dsv16x_tap_axis_priority_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_a *val = LSM6DSV16X_XYZ ; break; } + return ret; } @@ -8257,17 +9338,18 @@ int32_t lsm6dsv16x_tap_axis_priority_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_a * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_tap_time_windows_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_time_windows_t val) +int32_t lsm6dsv16x_tap_time_windows_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_tap_time_windows_t val) { - lsm6dsv16x_int_dur2_t int_dur2; + lsm6dsv16x_tap_dur_t tap_dur; int32_t ret; - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&int_dur2, 1); + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1); if (ret == 0) { - int_dur2.shock = val.shock; - int_dur2.quiet = val.quiet; - int_dur2.dur = val.tap_gap; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&int_dur2, 1); + tap_dur.shock = val.shock; + tap_dur.quiet = val.quiet; + tap_dur.dur = val.tap_gap; + ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1); } return ret; @@ -8281,15 +9363,20 @@ int32_t lsm6dsv16x_tap_time_windows_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_ti * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_tap_time_windows_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_time_windows_t *val) +int32_t lsm6dsv16x_tap_time_windows_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_tap_time_windows_t *val) { - lsm6dsv16x_int_dur2_t int_dur2; + lsm6dsv16x_tap_dur_t tap_dur; int32_t ret; - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_INT_DUR2, (uint8_t *)&int_dur2, 1); - val->shock = int_dur2.shock; - val->quiet = int_dur2.quiet; - val->tap_gap = int_dur2.dur; + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TAP_DUR, (uint8_t *)&tap_dur, 1); + if (ret != 0) { + return ret; + } + + val->shock = tap_dur.shock; + val->quiet = tap_dur.quiet; + val->tap_gap = tap_dur.dur; return ret; } @@ -8330,6 +9417,10 @@ int32_t lsm6dsv16x_tap_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_mode_t *va int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_WAKE_UP_THS, (uint8_t *)&wake_up_ths, 1); + if (ret != 0) { + return ret; + } + switch (wake_up_ths.single_double_tap) { case LSM6DSV16X_ONLY_SINGLE: *val = LSM6DSV16X_ONLY_SINGLE; @@ -8343,6 +9434,7 @@ int32_t lsm6dsv16x_tap_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_mode_t *va *val = LSM6DSV16X_ONLY_SINGLE; break; } + return ret; } @@ -8373,17 +9465,16 @@ int32_t lsm6dsv16x_tilt_mode_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); - } - if (ret == 0) { - emb_func_en_a.tilt_en = val; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + if (ret != 0) { + return ret; } + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); + emb_func_en_a.tilt_en = val; + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); + + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); + return ret; } @@ -8401,14 +9492,14 @@ int32_t lsm6dsv16x_tilt_mode_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val) int32_t ret; ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_EMBED_FUNC_MEM_BANK); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); + if (ret != 0) { + return ret; } + + ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_EMB_FUNC_EN_A, (uint8_t *)&emb_func_en_a, 1); *val = emb_func_en_a.tilt_en; - if (ret == 0) { - ret = lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); - } + ret += lsm6dsv16x_mem_bank_set(ctx, LSM6DSV16X_MAIN_MEM_BANK); return ret; } @@ -8440,6 +9531,10 @@ int32_t lsm6dsv16x_timestamp_raw_get(lsm6dsv16x_ctx_t *ctx, uint32_t *val) int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_TIMESTAMP0, &buff[0], 4); + if (ret != 0) { + return ret; + } + *val = buff[3]; *val = (*val * 256U) + buff[2]; *val = (*val * 256U) + buff[1]; @@ -8538,6 +9633,10 @@ int32_t lsm6dsv16x_act_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_mode_t *va int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_FUNCTIONS_ENABLE, (uint8_t *)&functions_enable, 1); + if (ret != 0) { + return ret; + } + switch (functions_enable.inact_en) { case LSM6DSV16X_XL_AND_GY_NOT_AFFECTED: *val = LSM6DSV16X_XL_AND_GY_NOT_AFFECTED; @@ -8559,6 +9658,7 @@ int32_t lsm6dsv16x_act_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_mode_t *va *val = LSM6DSV16X_XL_AND_GY_NOT_AFFECTED; break; } + return ret; } @@ -8570,7 +9670,8 @@ int32_t lsm6dsv16x_act_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_mode_t *va * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_act_from_sleep_to_act_dur_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_from_sleep_to_act_dur_t val) +int32_t lsm6dsv16x_act_from_sleep_to_act_dur_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_act_from_sleep_to_act_dur_t val) { lsm6dsv16x_inactivity_dur_t inactivity_dur; int32_t ret; @@ -8592,12 +9693,17 @@ int32_t lsm6dsv16x_act_from_sleep_to_act_dur_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv1 * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_act_from_sleep_to_act_dur_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_from_sleep_to_act_dur_t *val) +int32_t lsm6dsv16x_act_from_sleep_to_act_dur_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_act_from_sleep_to_act_dur_t *val) { lsm6dsv16x_inactivity_dur_t inactivity_dur; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_INACTIVITY_DUR, (uint8_t *)&inactivity_dur, 1); + if (ret != 0) { + return ret; + } + switch (inactivity_dur.inact_dur) { case LSM6DSV16X_SLEEP_TO_ACT_AT_1ST_SAMPLE: *val = LSM6DSV16X_SLEEP_TO_ACT_AT_1ST_SAMPLE; @@ -8619,6 +9725,7 @@ int32_t lsm6dsv16x_act_from_sleep_to_act_dur_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv1 *val = LSM6DSV16X_SLEEP_TO_ACT_AT_1ST_SAMPLE; break; } + return ret; } @@ -8630,7 +9737,8 @@ int32_t lsm6dsv16x_act_from_sleep_to_act_dur_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv1 * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_act_sleep_xl_odr_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_sleep_xl_odr_t val) +int32_t lsm6dsv16x_act_sleep_xl_odr_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_act_sleep_xl_odr_t val) { lsm6dsv16x_inactivity_dur_t inactivity_dur; int32_t ret; @@ -8652,12 +9760,17 @@ int32_t lsm6dsv16x_act_sleep_xl_odr_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_sl * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_act_sleep_xl_odr_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_sleep_xl_odr_t *val) +int32_t lsm6dsv16x_act_sleep_xl_odr_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_act_sleep_xl_odr_t *val) { lsm6dsv16x_inactivity_dur_t inactivity_dur; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_INACTIVITY_DUR, (uint8_t *)&inactivity_dur, 1); + if (ret != 0) { + return ret; + } + switch (inactivity_dur.xl_inact_odr) { case LSM6DSV16X_1Hz875: *val = LSM6DSV16X_1Hz875; @@ -8679,6 +9792,7 @@ int32_t lsm6dsv16x_act_sleep_xl_odr_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_sl *val = LSM6DSV16X_1Hz875; break; } + return ret; } @@ -8690,88 +9804,35 @@ int32_t lsm6dsv16x_act_sleep_xl_odr_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_sl * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_act_thresholds_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_thresholds_t val) +int32_t lsm6dsv16x_act_thresholds_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_act_thresholds_t *val) { lsm6dsv16x_inactivity_ths_t inactivity_ths; lsm6dsv16x_inactivity_dur_t inactivity_dur; lsm6dsv16x_wake_up_ths_t wake_up_ths; + lsm6dsv16x_wake_up_dur_t wake_up_dur; int32_t ret; - float tmp; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_INACTIVITY_DUR, (uint8_t *)&inactivity_dur, 1); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_INACTIVITY_THS, (uint8_t *)&inactivity_ths, 1); - } - - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_WAKE_UP_THS, (uint8_t *)&wake_up_ths, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_INACTIVITY_THS, (uint8_t *)&inactivity_ths, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_WAKE_UP_THS, (uint8_t *)&wake_up_ths, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_WAKE_UP_DUR, (uint8_t *)&wake_up_dur, 1); + if (ret != 0) { + return ret; } - if ((val.wk_ths_mg < (uint32_t)(7.8125f * 63.0f)) && (val.inact_ths_mg < (uint32_t)(7.8125f * 63.0f))) { - inactivity_dur.wu_inact_ths_w = 0; - - tmp = (float)val.inact_ths_mg / 7.8125f; - inactivity_ths.inact_ths = (uint8_t)tmp; - - tmp = (float)val.wk_ths_mg / 7.8125f; - wake_up_ths.wk_ths = (uint8_t)tmp; - } else if ((val.wk_ths_mg < (uint32_t)(15.625f * 63.0f)) && (val.inact_ths_mg < (uint32_t)(15.625f * 63.0f))) { - inactivity_dur.wu_inact_ths_w = 1; - - tmp = (float)val.inact_ths_mg / 15.625f; - inactivity_ths.inact_ths = (uint8_t)tmp; - - tmp = (float)val.wk_ths_mg / 15.625f; - wake_up_ths.wk_ths = (uint8_t)tmp; - } else if ((val.wk_ths_mg < (uint32_t)(31.25f * 63.0f)) && (val.inact_ths_mg < (uint32_t)(31.25f * 63.0f))) { - inactivity_dur.wu_inact_ths_w = 2; - - tmp = (float)val.inact_ths_mg / 31.25f; - inactivity_ths.inact_ths = (uint8_t)tmp; - - tmp = (float)val.wk_ths_mg / 31.25f; - wake_up_ths.wk_ths = (uint8_t)tmp; - } else if ((val.wk_ths_mg < (uint32_t)(62.5f * 63.0f)) && (val.inact_ths_mg < (uint32_t)(62.5f * 63.0f))) { - inactivity_dur.wu_inact_ths_w = 3; - - tmp = (float)val.inact_ths_mg / 62.5f; - inactivity_ths.inact_ths = (uint8_t)tmp; - - tmp = (float)val.wk_ths_mg / 62.5f; - wake_up_ths.wk_ths = (uint8_t)tmp; - } else if ((val.wk_ths_mg < (uint32_t)(125.0f * 63.0f)) && (val.inact_ths_mg < (uint32_t)(125.0f * 63.0f))) { - inactivity_dur.wu_inact_ths_w = 4; - - tmp = (float)val.inact_ths_mg / 125.0f; - inactivity_ths.inact_ths = (uint8_t)tmp; - - tmp = (float)val.wk_ths_mg / 125.0f; - wake_up_ths.wk_ths = (uint8_t)tmp; - } else if ((val.wk_ths_mg < (uint32_t)(250.0f * 63.0f)) && (val.inact_ths_mg < (uint32_t)(250.0f * 63.0f))) { - inactivity_dur.wu_inact_ths_w = 5; - - tmp = (float)val.inact_ths_mg / 250.0f; - inactivity_ths.inact_ths = (uint8_t)tmp; - - tmp = (float)val.wk_ths_mg / 250.0f; - wake_up_ths.wk_ths = (uint8_t)tmp; - } else { // out of limit - inactivity_dur.wu_inact_ths_w = 5; - inactivity_ths.inact_ths = 0x3FU; - wake_up_ths.wk_ths = 0x3FU; - } - - if (ret == 0) { - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_INACTIVITY_DUR, (uint8_t *)&inactivity_dur, 1); - } - if (ret == 0) { + inactivity_dur.wu_inact_ths_w = val->inactivity_cfg.wu_inact_ths_w; + inactivity_dur.xl_inact_odr = val->inactivity_cfg.xl_inact_odr; + inactivity_dur.inact_dur = val->inactivity_cfg.inact_dur; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_INACTIVITY_THS, (uint8_t *)&inactivity_ths, 1); - } - if (ret == 0) { + inactivity_ths.inact_ths = val->inactivity_ths; + wake_up_ths.wk_ths = val->threshold; + wake_up_dur.wake_dur = val->duration; - ret = lsm6dsv16x_write_reg(ctx, LSM6DSV16X_WAKE_UP_THS, (uint8_t *)&wake_up_ths, 1); - } + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_INACTIVITY_DUR, (uint8_t *)&inactivity_dur, 1); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_INACTIVITY_THS, (uint8_t *)&inactivity_ths, 1); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_WAKE_UP_THS, (uint8_t *)&wake_up_ths, 1); + ret += lsm6dsv16x_write_reg(ctx, LSM6DSV16X_WAKE_UP_DUR, (uint8_t *)&wake_up_dur, 1); return ret; } @@ -8784,71 +9845,30 @@ int32_t lsm6dsv16x_act_thresholds_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_thre * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_act_thresholds_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_thresholds_t *val) +int32_t lsm6dsv16x_act_thresholds_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_act_thresholds_t *val) { lsm6dsv16x_inactivity_dur_t inactivity_dur; lsm6dsv16x_inactivity_ths_t inactivity_ths; lsm6dsv16x_wake_up_ths_t wake_up_ths; + lsm6dsv16x_wake_up_dur_t wake_up_dur; int32_t ret; - float tmp; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_INACTIVITY_DUR, (uint8_t *)&inactivity_dur, 1); - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_INACTIVITY_THS, (uint8_t *)&inactivity_ths, 1); - } - if (ret == 0) { - ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_WAKE_UP_THS, (uint8_t *)&wake_up_ths, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_INACTIVITY_THS, (uint8_t *)&inactivity_ths, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_WAKE_UP_THS, (uint8_t *)&wake_up_ths, 1); + ret += lsm6dsv16x_read_reg(ctx, LSM6DSV16X_WAKE_UP_DUR, (uint8_t *)&wake_up_dur, 1); + if (ret != 0) { + return ret; } - switch (inactivity_dur.wu_inact_ths_w) { - case 0: - tmp = (float)wake_up_ths.wk_ths * 7.8125f; - val->wk_ths_mg = (uint32_t)tmp; - - tmp = (float)inactivity_ths.inact_ths * 7.8125f; - val->inact_ths_mg = (uint32_t)tmp; - break; - - case 1: - tmp = (float)wake_up_ths.wk_ths * 15.625f; - val->wk_ths_mg = (uint32_t)tmp; - - tmp = (float)inactivity_ths.inact_ths * 15.625f; - val->inact_ths_mg = (uint32_t)tmp; - break; - - case 2: - tmp = (float)wake_up_ths.wk_ths * 31.25f; - val->wk_ths_mg = (uint32_t)tmp; - - tmp = (float)inactivity_ths.inact_ths * 31.25f; - val->inact_ths_mg = (uint32_t)tmp; - break; - - case 3: - tmp = (float)wake_up_ths.wk_ths * 62.5f; - val->wk_ths_mg = (uint32_t)tmp; - - tmp = (float)inactivity_ths.inact_ths * 62.5f; - val->inact_ths_mg = (uint32_t)tmp; - break; - - case 4: - tmp = (float)wake_up_ths.wk_ths * 125.0f; - val->wk_ths_mg = (uint32_t)tmp; - - tmp = (float)inactivity_ths.inact_ths * 125.0f; - val->inact_ths_mg = (uint32_t)tmp; - break; - - default: - tmp = (float)wake_up_ths.wk_ths * 250.0f; - val->wk_ths_mg = (uint32_t)tmp; + val->inactivity_cfg.wu_inact_ths_w = inactivity_dur.wu_inact_ths_w; + val->inactivity_cfg.xl_inact_odr = inactivity_dur.xl_inact_odr; + val->inactivity_cfg.inact_dur = inactivity_dur.inact_dur; - tmp = (float)inactivity_ths.inact_ths * 250.0f; - val->inact_ths_mg = (uint32_t)tmp; - break; - } + val->inactivity_ths = inactivity_ths.inact_ths; + val->threshold = wake_up_ths.wk_ths; + val->duration = wake_up_dur.wake_dur; return ret; } @@ -8861,7 +9881,8 @@ int32_t lsm6dsv16x_act_thresholds_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_thre * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_act_wkup_time_windows_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_wkup_time_windows_t val) +int32_t lsm6dsv16x_act_wkup_time_windows_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_act_wkup_time_windows_t val) { lsm6dsv16x_wake_up_dur_t wake_up_dur; int32_t ret; @@ -8884,12 +9905,17 @@ int32_t lsm6dsv16x_act_wkup_time_windows_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_a * @retval interface status (MANDATORY: return 0 -> no Error) * */ -int32_t lsm6dsv16x_act_wkup_time_windows_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_wkup_time_windows_t *val) +int32_t lsm6dsv16x_act_wkup_time_windows_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_act_wkup_time_windows_t *val) { lsm6dsv16x_wake_up_dur_t wake_up_dur; int32_t ret; ret = lsm6dsv16x_read_reg(ctx, LSM6DSV16X_WAKE_UP_DUR, (uint8_t *)&wake_up_dur, 1); + if (ret != 0) { + return ret; + } + val->shock = wake_up_dur.wake_dur; val->quiet = wake_up_dur.sleep_dur; @@ -8899,4 +9925,4 @@ int32_t lsm6dsv16x_act_wkup_time_windows_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_a /** * @} * - */ + */ \ No newline at end of file diff --git a/src/lsm6dsv16x_reg.h b/src/lsm6dsv16x_reg.h index 37ec2ae..499c627 100644 --- a/src/lsm6dsv16x_reg.h +++ b/src/lsm6dsv16x_reg.h @@ -7,7 +7,7 @@ ****************************************************************************** * @attention * - *

© Copyright (c) 2021 STMicroelectronics. + *

© Copyright (c) 2022 STMicroelectronics. * All rights reserved.

* * This software component is licensed by ST under BSD 3-Clause license, @@ -100,13 +100,6 @@ typedef struct { #define PROPERTY_DISABLE (0U) #define PROPERTY_ENABLE (1U) -#endif /* MEMS_SHARED_TYPES */ - -/** - * @} - * - */ - /** @addtogroup Interfaces_Functions * @brief This section provide a set of functions used to read and * write a generic register of the device. @@ -115,13 +108,16 @@ typedef struct { * */ -typedef int32_t (*lsm6dsv16x_write_ptr)(void *, uint8_t, uint8_t *, uint16_t); +typedef int32_t (*lsm6dsv16x_write_ptr)(void *, uint8_t, uint8_t *, uint16_t); typedef int32_t (*lsm6dsv16x_read_ptr)(void *, uint8_t, uint8_t *, uint16_t); +typedef void (*lsm6dsv16x_mdelay_ptr)(uint32_t millisec); typedef struct { /** Component mandatory fields **/ lsm6dsv16x_write_ptr write_reg; lsm6dsv16x_read_ptr read_reg; + /** Component optional fields **/ + lsm6dsv16x_mdelay_ptr mdelay; /** Customizable optional pointer **/ void *handle; } lsm6dsv16x_ctx_t; @@ -131,6 +127,8 @@ typedef struct { * */ +#endif /* MEMS_SHARED_TYPES */ + #ifndef MEMS_UCF_SHARED_TYPES #define MEMS_UCF_SHARED_TYPES @@ -157,6 +155,11 @@ typedef struct { #endif /* MEMS_UCF_SHARED_TYPES */ +/** + * @} + * + */ + /** @defgroup LSM6DSV16X_Infos * @{ * @@ -179,661 +182,643 @@ typedef struct { * */ -#define LSM6DSV16X_FUNC_CFG_ACCESS 0x1U +#define LSM6DSV16X_FUNC_CFG_ACCESS 0x1U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ois_ctrl_from_ui : 1; - uint8_t spi2_reset : 1; - uint8_t sw_por : 1; - uint8_t fsm_wr_ctrl_en : 1; - uint8_t not_used0 : 2; - uint8_t shub_reg_access : 1; + uint8_t ois_ctrl_from_ui : 1; + uint8_t spi2_reset : 1; + uint8_t sw_por : 1; + uint8_t fsm_wr_ctrl_en : 1; + uint8_t not_used0 : 2; + uint8_t shub_reg_access : 1; uint8_t emb_func_reg_access : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN uint8_t emb_func_reg_access : 1; - uint8_t shub_reg_access : 1; - uint8_t not_used0 : 2; - uint8_t fsm_wr_ctrl_en : 1; - uint8_t sw_por : 1; - uint8_t spi2_reset : 1; - uint8_t ois_ctrl_from_ui : 1; + uint8_t shub_reg_access : 1; + uint8_t not_used0 : 2; + uint8_t fsm_wr_ctrl_en : 1; + uint8_t sw_por : 1; + uint8_t spi2_reset : 1; + uint8_t ois_ctrl_from_ui : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_func_cfg_access_t; -#define LSM6DSV16X_PIN_CTRL 0x2U +#define LSM6DSV16X_PIN_CTRL 0x2U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 5; - uint8_t ibhr_por_en : 1; - uint8_t sdo_pu_en : 1; - uint8_t ois_pu_dis : 1; + uint8_t not_used0 : 5; + uint8_t ibhr_por_en : 1; + uint8_t sdo_pu_en : 1; + uint8_t ois_pu_dis : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ois_pu_dis : 1; - uint8_t sdo_pu_en : 1; - uint8_t ibhr_por_en : 1; - uint8_t not_used0 : 5; + uint8_t ois_pu_dis : 1; + uint8_t sdo_pu_en : 1; + uint8_t ibhr_por_en : 1; + uint8_t not_used0 : 5; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_pin_ctrl_t; -#define LSM6DSV16X_IF_CFG 0x3U +#define LSM6DSV16X_IF_CFG 0x3U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t i2c_i3c_disable : 1; - uint8_t not_used0 : 1; - uint8_t sim : 1; - uint8_t pp_od : 1; - uint8_t h_lactive : 1; - uint8_t asf_ctrl : 1; - uint8_t shub_pu_en : 1; - uint8_t sda_pu_en : 1; + uint8_t i2c_i3c_disable : 1; + uint8_t not_used0 : 1; + uint8_t sim : 1; + uint8_t pp_od : 1; + uint8_t h_lactive : 1; + uint8_t asf_ctrl : 1; + uint8_t shub_pu_en : 1; + uint8_t sda_pu_en : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sda_pu_en : 1; - uint8_t shub_pu_en : 1; - uint8_t asf_ctrl : 1; - uint8_t h_lactive : 1; - uint8_t pp_od : 1; - uint8_t sim : 1; - uint8_t not_used0 : 1; - uint8_t i2c_i3c_disable : 1; + uint8_t sda_pu_en : 1; + uint8_t shub_pu_en : 1; + uint8_t asf_ctrl : 1; + uint8_t h_lactive : 1; + uint8_t pp_od : 1; + uint8_t sim : 1; + uint8_t not_used0 : 1; + uint8_t i2c_i3c_disable : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_if_cfg_t; -#define LSM6DSV16X_S4S_TPH_L 0x4U +#define LSM6DSV16X_ODR_TRIG_CFG 0x6U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t tph : 7; - uint8_t tph_h_sel : 1; + uint8_t odr_trig_nodr : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t tph_h_sel : 1; - uint8_t tph : 7; + uint8_t odr_trig_nodr : 8; #endif /* DRV_BYTE_ORDER */ -} lsm6dsv16x_s4s_tph_l_t; +} lsm6dsv16x_odr_trig_cfg_t; -#define LSM6DSV16X_S4S_TPH_H 0x5U +#define LSM6DSV16X_FIFO_CTRL1 0x7U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t tph : 8; + uint8_t wtm : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t tph : 8; -#endif /* DRV_BYTE_ORDER */ -} lsm6dsv16x_s4s_tph_h_t; - -#define LSM6DSV16X_S4S_RR 0x6U -typedef struct { -#if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t rr : 2; - uint8_t not_used0 : 6; -#elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 6; - uint8_t rr : 2; -#endif /* DRV_BYTE_ORDER */ -} lsm6dsv16x_s4s_rr_t; - -#define LSM6DSV16X_FIFO_CTRL1 0x7U -typedef struct { -#if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t wtm : 8; -#elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t wtm : 8; + uint8_t wtm : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fifo_ctrl1_t; -#define LSM6DSV16X_FIFO_CTRL2 0x8U +#define LSM6DSV16X_FIFO_CTRL2 0x8U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t xl_dualc_batch_from_fsm : 1; - uint8_t uncompr_rate : 2; - uint8_t not_used0 : 1; - uint8_t odr_chg_en : 1; - uint8_t not_used1 : 1; - uint8_t fifo_compr_rt_en : 1; - uint8_t stop_on_wtm : 1; + uint8_t xl_dualc_batch_from_fsm : 1; + uint8_t uncompr_rate : 2; + uint8_t not_used0 : 1; + uint8_t odr_chg_en : 1; + uint8_t not_used1 : 1; + uint8_t fifo_compr_rt_en : 1; + uint8_t stop_on_wtm : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t stop_on_wtm : 1; - uint8_t fifo_compr_rt_en : 1; - uint8_t not_used1 : 1; - uint8_t odr_chg_en : 1; - uint8_t not_used0 : 1; - uint8_t uncompr_rate : 2; - uint8_t xl_dualc_batch_from_fsm : 1; + uint8_t stop_on_wtm : 1; + uint8_t fifo_compr_rt_en : 1; + uint8_t not_used1 : 1; + uint8_t odr_chg_en : 1; + uint8_t not_used0 : 1; + uint8_t uncompr_rate : 2; + uint8_t xl_dualc_batch_from_fsm : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fifo_ctrl2_t; -#define LSM6DSV16X_FIFO_CTRL3 0x9U +#define LSM6DSV16X_FIFO_CTRL3 0x9U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t bdr_xl : 4; - uint8_t bdr_gy : 4; + uint8_t bdr_xl : 4; + uint8_t bdr_gy : 4; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t bdr_gy : 4; - uint8_t bdr_xl : 4; + uint8_t bdr_gy : 4; + uint8_t bdr_xl : 4; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fifo_ctrl3_t; -#define LSM6DSV16X_FIFO_CTRL4 0x0AU +#define LSM6DSV16X_FIFO_CTRL4 0x0AU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fifo_mode : 3; - uint8_t g_eis_fifo_en : 1; - uint8_t odr_t_batch : 2; - uint8_t dec_ts_batch : 2; + uint8_t fifo_mode : 3; + uint8_t g_eis_fifo_en : 1; + uint8_t odr_t_batch : 2; + uint8_t dec_ts_batch : 2; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t dec_ts_batch : 2; - uint8_t odr_t_batch : 2; - uint8_t g_eis_fifo_en : 1; - uint8_t fifo_mode : 3; + uint8_t dec_ts_batch : 2; + uint8_t odr_t_batch : 2; + uint8_t g_eis_fifo_en : 1; + uint8_t fifo_mode : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fifo_ctrl4_t; -#define LSM6DSV16X_COUNTER_BDR_REG1 0x0BU +#define LSM6DSV16X_COUNTER_BDR_REG1 0x0BU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t cnt_bdr_th : 2; - uint8_t not_used0 : 3; - uint8_t trig_counter_bdr : 2; - uint8_t not_used1 : 1; + uint8_t cnt_bdr_th : 2; + uint8_t not_used0 : 3; + uint8_t trig_counter_bdr : 2; + uint8_t not_used1 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 1; - uint8_t trig_counter_bdr : 2; - uint8_t not_used0 : 3; - uint8_t cnt_bdr_th : 2; + uint8_t not_used1 : 1; + uint8_t trig_counter_bdr : 2; + uint8_t not_used0 : 3; + uint8_t cnt_bdr_th : 2; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_counter_bdr_reg1_t; -#define LSM6DSV16X_COUNTER_BDR_REG2 0x0CU +#define LSM6DSV16X_COUNTER_BDR_REG2 0x0CU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t cnt_bdr_th : 8; + uint8_t cnt_bdr_th : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t cnt_bdr_th : 8; + uint8_t cnt_bdr_th : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_counter_bdr_reg2_t; -#define LSM6DSV16X_INT1_CTRL 0x0DU +#define LSM6DSV16X_INT1_CTRL 0x0DU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t int1_drdy_xl : 1; - uint8_t int1_drdy_g : 1; - uint8_t not_used0 : 1; - uint8_t int1_fifo_th : 1; - uint8_t int1_fifo_ovr : 1; - uint8_t int1_fifo_full : 1; - uint8_t int1_cnt_bdr : 1; - uint8_t not_used1 : 1; + uint8_t int1_drdy_xl : 1; + uint8_t int1_drdy_g : 1; + uint8_t not_used0 : 1; + uint8_t int1_fifo_th : 1; + uint8_t int1_fifo_ovr : 1; + uint8_t int1_fifo_full : 1; + uint8_t int1_cnt_bdr : 1; + uint8_t not_used1 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 1; - uint8_t int1_cnt_bdr : 1; - uint8_t int1_fifo_full : 1; - uint8_t int1_fifo_ovr : 1; - uint8_t int1_fifo_th : 1; - uint8_t not_used0 : 1; - uint8_t int1_drdy_g : 1; - uint8_t int1_drdy_xl : 1; + uint8_t not_used1 : 1; + uint8_t int1_cnt_bdr : 1; + uint8_t int1_fifo_full : 1; + uint8_t int1_fifo_ovr : 1; + uint8_t int1_fifo_th : 1; + uint8_t not_used0 : 1; + uint8_t int1_drdy_g : 1; + uint8_t int1_drdy_xl : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_int1_ctrl_t; -#define LSM6DSV16X_INT2_CTRL 0x0EU +#define LSM6DSV16X_INT2_CTRL 0x0EU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t int2_drdy_xl : 1; - uint8_t int2_drdy_g : 1; - uint8_t int2_drdy_g_eis : 1; - uint8_t int2_fifo_th : 1; - uint8_t int2_fifo_ovr : 1; - uint8_t int2_fifo_full : 1; - uint8_t int2_cnt_bdr : 1; + uint8_t int2_drdy_xl : 1; + uint8_t int2_drdy_g : 1; + uint8_t int2_drdy_g_eis : 1; + uint8_t int2_fifo_th : 1; + uint8_t int2_fifo_ovr : 1; + uint8_t int2_fifo_full : 1; + uint8_t int2_cnt_bdr : 1; uint8_t int2_emb_func_endop : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN uint8_t int2_emb_func_endop : 1; - uint8_t int2_cnt_bdr : 1; - uint8_t int2_fifo_full : 1; - uint8_t int2_fifo_ovr : 1; - uint8_t int2_fifo_th : 1; - uint8_t int2_drdy_g_eis : 1; - uint8_t int2_drdy_g : 1; - uint8_t int2_drdy_xl : 1; + uint8_t int2_cnt_bdr : 1; + uint8_t int2_fifo_full : 1; + uint8_t int2_fifo_ovr : 1; + uint8_t int2_fifo_th : 1; + uint8_t int2_drdy_g_eis : 1; + uint8_t int2_drdy_g : 1; + uint8_t int2_drdy_xl : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_int2_ctrl_t; -#define LSM6DSV16X_WHO_AM_I 0x0FU +#define LSM6DSV16X_WHO_AM_I 0x0FU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t id : 8; + uint8_t id : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t id : 8; + uint8_t id : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_who_am_i_t; -#define LSM6DSV16X_CTRL1 0x10U +#define LSM6DSV16X_CTRL1 0x10U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t odr_xl : 4; - uint8_t op_mode_xl : 3; - uint8_t not_used0 : 1; + uint8_t odr_xl : 4; + uint8_t op_mode_xl : 3; + uint8_t not_used0 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 1; - uint8_t op_mode_xl : 3; - uint8_t odr_xl : 4; + uint8_t not_used0 : 1; + uint8_t op_mode_xl : 3; + uint8_t odr_xl : 4; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ctrl1_t; -#define LSM6DSV16X_CTRL2 0x11U +#define LSM6DSV16X_CTRL2 0x11U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t odr_g : 4; - uint8_t op_mode_g : 3; - uint8_t not_used0 : 1; + uint8_t odr_g : 4; + uint8_t op_mode_g : 3; + uint8_t not_used0 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 1; - uint8_t op_mode_g : 3; - uint8_t odr_g : 4; + uint8_t not_used0 : 1; + uint8_t op_mode_g : 3; + uint8_t odr_g : 4; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ctrl2_t; -#define LSM6DSV16X_CTRL3 0x12U +#define LSM6DSV16X_CTRL3 0x12U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sw_reset : 1; - uint8_t not_used0 : 1; - uint8_t if_inc : 1; - uint8_t not_used1 : 3; - uint8_t bdu : 1; - uint8_t boot : 1; + uint8_t sw_reset : 1; + uint8_t not_used0 : 1; + uint8_t if_inc : 1; + uint8_t not_used1 : 3; + uint8_t bdu : 1; + uint8_t boot : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t boot : 1; - uint8_t bdu : 1; - uint8_t not_used1 : 3; - uint8_t if_inc : 1; - uint8_t not_used0 : 1; - uint8_t sw_reset : 1; + uint8_t boot : 1; + uint8_t bdu : 1; + uint8_t not_used1 : 3; + uint8_t if_inc : 1; + uint8_t not_used0 : 1; + uint8_t sw_reset : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ctrl3_t; -#define LSM6DSV16X_CTRL4 0x13U +#define LSM6DSV16X_CTRL4 0x13U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t int2_in_lh : 1; - uint8_t drdy_pulsed : 1; - uint8_t int2_drdy_temp : 1; - uint8_t drdy_mask : 1; - uint8_t int2_on_int1 : 1; - uint8_t not_used0 : 3; + uint8_t int2_in_lh : 1; + uint8_t drdy_pulsed : 1; + uint8_t int2_drdy_temp : 1; + uint8_t drdy_mask : 1; + uint8_t int2_on_int1 : 1; + uint8_t not_used0 : 3; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 3; - uint8_t int2_on_int1 : 1; - uint8_t drdy_mask : 1; - uint8_t int2_drdy_temp : 1; - uint8_t drdy_pulsed : 1; - uint8_t int2_in_lh : 1; + uint8_t not_used0 : 3; + uint8_t int2_on_int1 : 1; + uint8_t drdy_mask : 1; + uint8_t int2_drdy_temp : 1; + uint8_t drdy_pulsed : 1; + uint8_t int2_in_lh : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ctrl4_t; -#define LSM6DSV16X_CTRL5 0x14U +#define LSM6DSV16X_CTRL5 0x14U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t int_en_i3c : 1; - uint8_t bus_act_sel : 2; - uint8_t not_used0 : 5; + uint8_t int_en_i3c : 1; + uint8_t bus_act_sel : 2; + uint8_t not_used0 : 5; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 5; - uint8_t bus_act_sel : 2; - uint8_t int_en_i3c : 1; + uint8_t not_used0 : 5; + uint8_t bus_act_sel : 2; + uint8_t int_en_i3c : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ctrl5_t; -#define LSM6DSV16X_CTRL6 0x15U +#define LSM6DSV16X_CTRL6 0x15U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fs_g : 4; - uint8_t lpf1_g_bw : 3; - uint8_t not_used0 : 1; + uint8_t fs_g : 4; + uint8_t lpf1_g_bw : 3; + uint8_t not_used0 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 1; - uint8_t lpf1_g_bw : 3; - uint8_t fs_g : 4; + uint8_t not_used0 : 1; + uint8_t lpf1_g_bw : 3; + uint8_t fs_g : 4; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ctrl6_t; -#define LSM6DSV16X_CTRL7 0x16U +#define LSM6DSV16X_CTRL7 0x16U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t lpf1_g_en : 1; - uint8_t not_used0 : 3; - uint8_t ah_qvar_c_zin : 2; - uint8_t int2_drdy_ah_qvar : 1; - uint8_t ah_qvar_en : 1; + uint8_t lpf1_g_en : 1; + uint8_t not_used0 : 3; + uint8_t ah_qvar_c_zin : 2; + uint8_t int2_drdy_ah_qvar : 1; + uint8_t ah_qvar_en : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ah_qvar_en : 1; - uint8_t int2_drdy_ah_qvar : 1; - uint8_t ah_qvar_c_zin : 2; - uint8_t not_used0 : 3; - uint8_t lpf1_g_en : 1; + uint8_t ah_qvar_en : 1; + uint8_t int2_drdy_ah_qvar : 1; + uint8_t ah_qvar_c_zin : 2; + uint8_t not_used0 : 3; + uint8_t lpf1_g_en : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ctrl7_t; -#define LSM6DSV16X_CTRL8 0x17U +#define LSM6DSV16X_CTRL8 0x17U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fs_xl : 2; - uint8_t not_used0 : 1; - uint8_t xl_dualc_en : 1; - uint8_t not_used1 : 1; - uint8_t hp_lpf2_xl_bw : 3; + uint8_t fs_xl : 2; + uint8_t not_used0 : 1; + uint8_t xl_dualc_en : 1; + uint8_t not_used1 : 1; + uint8_t hp_lpf2_xl_bw : 3; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t hp_lpf2_xl_bw : 3; - uint8_t not_used1 : 1; - uint8_t xl_dualc_en : 1; - uint8_t not_used0 : 1; - uint8_t fs_xl : 2; + uint8_t hp_lpf2_xl_bw : 3; + uint8_t not_used1 : 1; + uint8_t xl_dualc_en : 1; + uint8_t not_used0 : 1; + uint8_t fs_xl : 2; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ctrl8_t; -#define LSM6DSV16X_CTRL9 0x18U +#define LSM6DSV16X_CTRL9 0x18U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t usr_off_on_out : 1; - uint8_t usr_off_w : 1; - uint8_t not_used0 : 1; - uint8_t lpf2_xl_en : 1; - uint8_t hp_slope_xl_en : 1; - uint8_t xl_fastsettl_mode : 1; - uint8_t hp_ref_mode_xl : 1; - uint8_t not_used1 : 1; + uint8_t usr_off_on_out : 1; + uint8_t usr_off_w : 1; + uint8_t not_used0 : 1; + uint8_t lpf2_xl_en : 1; + uint8_t hp_slope_xl_en : 1; + uint8_t xl_fastsettl_mode : 1; + uint8_t hp_ref_mode_xl : 1; + uint8_t not_used1 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 1; - uint8_t hp_ref_mode_xl : 1; - uint8_t xl_fastsettl_mode : 1; - uint8_t hp_slope_xl_en : 1; - uint8_t lpf2_xl_en : 1; - uint8_t not_used0 : 1; - uint8_t usr_off_w : 1; - uint8_t usr_off_on_out : 1; + uint8_t not_used1 : 1; + uint8_t hp_ref_mode_xl : 1; + uint8_t xl_fastsettl_mode : 1; + uint8_t hp_slope_xl_en : 1; + uint8_t lpf2_xl_en : 1; + uint8_t not_used0 : 1; + uint8_t usr_off_w : 1; + uint8_t usr_off_on_out : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ctrl9_t; -#define LSM6DSV16X_CTRL10 0x19U +#define LSM6DSV16X_CTRL10 0x19U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t st_xl : 2; - uint8_t st_g : 2; - uint8_t not_used0 : 4; + uint8_t st_xl : 2; + uint8_t st_g : 2; + uint8_t not_used0 : 2; + uint8_t emb_func_debug : 1; + uint8_t not_used1 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 4; - uint8_t st_g : 2; - uint8_t st_xl : 2; + uint8_t not_used1 : 1; + uint8_t emb_func_debug : 1; + uint8_t not_used0 : 2; + uint8_t st_g : 2; + uint8_t st_xl : 2; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ctrl10_t; -#define LSM6DSV16X_CTRL_STATUS 0x1AU +#define LSM6DSV16X_CTRL_STATUS 0x1AU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used1 : 5; - uint8_t fsm_wr_ctrl_status : 1; - uint8_t not_used0 : 2; + uint8_t not_used0 : 2; + uint8_t fsm_wr_ctrl_status : 1; + uint8_t not_used1 : 5; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 2; - uint8_t fsm_wr_ctrl_status : 1; - uint8_t not_used1 : 5; + uint8_t not_used1 : 5; + uint8_t fsm_wr_ctrl_status : 1; + uint8_t not_used0 : 2; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ctrl_status_t; -#define LSM6DSV16X_FIFO_STATUS1 0x1BU +#define LSM6DSV16X_FIFO_STATUS1 0x1BU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t diff_fifo : 8; + uint8_t diff_fifo : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t diff_fifo : 8; + uint8_t diff_fifo : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fifo_status1_t; -#define LSM6DSV16X_FIFO_STATUS2 0x1CU +#define LSM6DSV16X_FIFO_STATUS2 0x1CU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t diff_fifo : 1; - uint8_t not_used0 : 2; - uint8_t fifo_ovr_latched : 1; - uint8_t counter_bdr_ia : 1; - uint8_t fifo_full_ia : 1; - uint8_t fifo_ovr_ia : 1; - uint8_t fifo_wtm_ia : 1; + uint8_t diff_fifo : 1; + uint8_t not_used0 : 2; + uint8_t fifo_ovr_latched : 1; + uint8_t counter_bdr_ia : 1; + uint8_t fifo_full_ia : 1; + uint8_t fifo_ovr_ia : 1; + uint8_t fifo_wtm_ia : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fifo_wtm_ia : 1; - uint8_t fifo_ovr_ia : 1; - uint8_t fifo_full_ia : 1; - uint8_t counter_bdr_ia : 1; - uint8_t fifo_ovr_latched : 1; - uint8_t not_used0 : 2; - uint8_t diff_fifo : 1; + uint8_t fifo_wtm_ia : 1; + uint8_t fifo_ovr_ia : 1; + uint8_t fifo_full_ia : 1; + uint8_t counter_bdr_ia : 1; + uint8_t fifo_ovr_latched : 1; + uint8_t not_used0 : 2; + uint8_t diff_fifo : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fifo_status2_t; -#define LSM6DSV16X_ALL_INT_SRC 0x1DU +#define LSM6DSV16X_ALL_INT_SRC 0x1DU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ff_ia : 1; - uint8_t wu_ia : 1; - uint8_t tap_ia : 1; - uint8_t not_used0 : 1; - uint8_t d6d_ia : 1; - uint8_t sleep_change_ia : 1; - uint8_t shub_ia : 1; - uint8_t emb_func_ia : 1; + uint8_t ff_ia : 1; + uint8_t wu_ia : 1; + uint8_t tap_ia : 1; + uint8_t not_used0 : 1; + uint8_t d6d_ia : 1; + uint8_t sleep_change_ia : 1; + uint8_t shub_ia : 1; + uint8_t emb_func_ia : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t emb_func_ia : 1; - uint8_t shub_ia : 1; - uint8_t sleep_change_ia : 1; - uint8_t d6d_ia : 1; - uint8_t not_used0 : 1; - uint8_t tap_ia : 1; - uint8_t wu_ia : 1; - uint8_t ff_ia : 1; + uint8_t emb_func_ia : 1; + uint8_t shub_ia : 1; + uint8_t sleep_change_ia : 1; + uint8_t d6d_ia : 1; + uint8_t not_used0 : 1; + uint8_t tap_ia : 1; + uint8_t wu_ia : 1; + uint8_t ff_ia : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_all_int_src_t; -#define LSM6DSV16X_STATUS_REG 0x1EU +#define LSM6DSV16X_STATUS_REG 0x1EU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t xlda : 1; - uint8_t gda : 1; - uint8_t tda : 1; - uint8_t ah_qvarda : 1; - uint8_t gda_eis : 1; - uint8_t ois_drdy : 1; - uint8_t not_used0 : 1; - uint8_t timestamp_endcount : 1; + uint8_t xlda : 1; + uint8_t gda : 1; + uint8_t tda : 1; + uint8_t ah_qvarda : 1; + uint8_t gda_eis : 1; + uint8_t ois_drdy : 1; + uint8_t not_used0 : 1; + uint8_t timestamp_endcount : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t timestamp_endcount : 1; - uint8_t not_used0 : 1; - uint8_t ois_drdy : 1; - uint8_t gda_eis : 1; - uint8_t ah_qvarda : 1; - uint8_t tda : 1; - uint8_t gda : 1; - uint8_t xlda : 1; + uint8_t timestamp_endcount : 1; + uint8_t not_used0 : 1; + uint8_t ois_drdy : 1; + uint8_t gda_eis : 1; + uint8_t ah_qvarda : 1; + uint8_t tda : 1; + uint8_t gda : 1; + uint8_t xlda : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_status_reg_t; -#define LSM6DSV16X_OUT_TEMP_L 0x20U +#define LSM6DSV16X_OUT_TEMP_L 0x20U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t temp : 8; + uint8_t temp : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t temp : 8; + uint8_t temp : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_out_temp_l_t; -#define LSM6DSV16X_OUT_TEMP_H 0x21U +#define LSM6DSV16X_OUT_TEMP_H 0x21U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t temp : 8; + uint8_t temp : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t temp : 8; + uint8_t temp : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_out_temp_h_t; -#define LSM6DSV16X_OUTX_L_G 0x22U +#define LSM6DSV16X_OUTX_L_G 0x22U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t outx_g : 8; + uint8_t outx_g : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t outx_g : 8; + uint8_t outx_g : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_outx_l_g_t; -#define LSM6DSV16X_OUTX_H_G 0x23U +#define LSM6DSV16X_OUTX_H_G 0x23U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t outx_g : 8; + uint8_t outx_g : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t outx_g : 8; + uint8_t outx_g : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_outx_h_g_t; -#define LSM6DSV16X_OUTY_L_G 0x24U +#define LSM6DSV16X_OUTY_L_G 0x24U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t outy_g : 8; + uint8_t outy_g : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t outy_g : 8; + uint8_t outy_g : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_outy_l_g_t; -#define LSM6DSV16X_OUTY_H_G 0x25U +#define LSM6DSV16X_OUTY_H_G 0x25U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t outy_g : 8; + uint8_t outy_g : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t outy_g : 8; + uint8_t outy_g : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_outy_h_g_t; -#define LSM6DSV16X_OUTZ_L_G 0x26U +#define LSM6DSV16X_OUTZ_L_G 0x26U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t outz_g : 8; + uint8_t outz_g : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t outz_g : 8; + uint8_t outz_g : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_outz_l_g_t; -#define LSM6DSV16X_OUTZ_H_G 0x27U +#define LSM6DSV16X_OUTZ_H_G 0x27U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t outz_g : 8; + uint8_t outz_g : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t outz_g : 8; + uint8_t outz_g : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_outz_h_g_t; -#define LSM6DSV16X_OUTX_L_A 0x28U +#define LSM6DSV16X_OUTX_L_A 0x28U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t outx_a : 8; + uint8_t outx_a : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t outx_a : 8; + uint8_t outx_a : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_outx_l_a_t; -#define LSM6DSV16X_OUTX_H_A 0x29U +#define LSM6DSV16X_OUTX_H_A 0x29U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t outx_a : 8; + uint8_t outx_a : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t outx_a : 8; + uint8_t outx_a : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_outx_h_a_t; -#define LSM6DSV16X_OUTY_L_A 0x2AU +#define LSM6DSV16X_OUTY_L_A 0x2AU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t outy_a : 8; + uint8_t outy_a : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t outy_a : 8; + uint8_t outy_a : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_outy_l_a_t; -#define LSM6DSV16X_OUTY_H_A 0x2BU +#define LSM6DSV16X_OUTY_H_A 0x2BU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t outy_a : 8; + uint8_t outy_a : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t outy_a : 8; + uint8_t outy_a : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_outy_h_a_t; -#define LSM6DSV16X_OUTZ_L_A 0x2CU +#define LSM6DSV16X_OUTZ_L_A 0x2CU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t outz_a : 8; + uint8_t outz_a : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t outz_a : 8; + uint8_t outz_a : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_outz_l_a_t; -#define LSM6DSV16X_OUTZ_H_A 0x2DU +#define LSM6DSV16X_OUTZ_H_A 0x2DU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t outz_a : 8; + uint8_t outz_a : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t outz_a : 8; + uint8_t outz_a : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_outz_h_a_t; -#define LSM6DSV16X_UI_OUTX_L_G_OIS_EIS 0x2EU +#define LSM6DSV16X_UI_OUTX_L_G_OIS_EIS 0x2EU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ui_outx_g_ois_eis : 8; + uint8_t ui_outx_g_ois_eis : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ui_outx_g_ois_eis : 8; + uint8_t ui_outx_g_ois_eis : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_outx_l_g_ois_eis_t; -#define LSM6DSV16X_UI_OUTX_H_G_OIS_EIS 0x2FU +#define LSM6DSV16X_UI_OUTX_H_G_OIS_EIS 0x2FU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ui_outx_g_ois_eis : 8; + uint8_t ui_outx_g_ois_eis : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ui_outx_g_ois_eis : 8; + uint8_t ui_outx_g_ois_eis : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_outx_h_g_ois_eis_t; -#define LSM6DSV16X_UI_OUTY_L_G_OIS_EIS 0x30U +#define LSM6DSV16X_UI_OUTY_L_G_OIS_EIS 0x30U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ui_outy_g_ois_eis : 8; + uint8_t ui_outy_g_ois_eis : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ui_outy_g_ois_eis : 8; + uint8_t ui_outy_g_ois_eis : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_outy_l_g_ois_eis_t; -#define LSM6DSV16X_UI_OUTY_H_G_OIS_EIS 0x31U +#define LSM6DSV16X_UI_OUTY_H_G_OIS_EIS 0x31U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ui_outy_g_ois_eis : 8; + uint8_t ui_outy_g_ois_eis : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ui_outy_g_ois_eis : 8; + uint8_t ui_outy_g_ois_eis : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_outy_h_g_ois_eis_t; -#define LSM6DSV16X_UI_OUTZ_L_G_OIS_EIS 0x32U +#define LSM6DSV16X_UI_OUTZ_L_G_OIS_EIS 0x32U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ui_outz_g_ois_eis : 8; + uint8_t ui_outz_g_ois_eis : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ui_outz_g_ois_eis : 8; + uint8_t ui_outz_g_ois_eis : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_outz_l_g_ois_eis_t; -#define LSM6DSV16X_UI_OUTZ_H_G_OIS_EIS 0x33U +#define LSM6DSV16X_UI_OUTZ_H_G_OIS_EIS 0x33U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ui_outz_g_ois_eis : 8; + uint8_t ui_outz_g_ois_eis : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ui_outz_g_ois_eis : 8; + uint8_t ui_outz_g_ois_eis : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_outz_h_g_ois_eis_t; -#define LSM6DSV16X_UI_OUTX_L_A_OIS_DUALC 0x34U +#define LSM6DSV16X_UI_OUTX_L_A_OIS_DUALC 0x34U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN uint8_t ui_outx_a_ois_dualc : 8; @@ -842,7 +827,7 @@ typedef struct { #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_outx_l_a_ois_dualc_t; -#define LSM6DSV16X_UI_OUTX_H_A_OIS_DUALC 0x35U +#define LSM6DSV16X_UI_OUTX_H_A_OIS_DUALC 0x35U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN uint8_t ui_outx_a_ois_dualc : 8; @@ -851,7 +836,7 @@ typedef struct { #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_outx_h_a_ois_dualc_t; -#define LSM6DSV16X_UI_OUTY_L_A_OIS_DUALC 0x36U +#define LSM6DSV16X_UI_OUTY_L_A_OIS_DUALC 0x36U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN uint8_t ui_outy_a_ois_dualc : 8; @@ -860,7 +845,7 @@ typedef struct { #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_outy_l_a_ois_dualc_t; -#define LSM6DSV16X_UI_OUTY_H_A_OIS_DUALC 0x37U +#define LSM6DSV16X_UI_OUTY_H_A_OIS_DUALC 0x37U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN uint8_t ui_outy_a_ois_dualc : 8; @@ -869,7 +854,7 @@ typedef struct { #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_outy_h_a_ois_dualc_t; -#define LSM6DSV16X_UI_OUTZ_L_A_OIS_DUALC 0x38U +#define LSM6DSV16X_UI_OUTZ_L_A_OIS_DUALC 0x38U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN uint8_t ui_outz_a_ois_dualc : 8; @@ -878,7 +863,7 @@ typedef struct { #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_outz_l_a_ois_dualc_t; -#define LSM6DSV16X_UI_OUTZ_H_A_OIS_DUALC 0x39U +#define LSM6DSV16X_UI_OUTZ_H_A_OIS_DUALC 0x39U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN uint8_t ui_outz_a_ois_dualc : 8; @@ -887,731 +872,724 @@ typedef struct { #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_outz_h_a_ois_dualc_t; -#define LSM6DSV16X_AH_QVAR_OUT_L 0x3AU +#define LSM6DSV16X_AH_QVAR_OUT_L 0x3AU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ah_qvar : 8; + uint8_t ah_qvar : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ah_qvar : 8; + uint8_t ah_qvar : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ah_qvar_out_l_t; -#define LSM6DSV16X_AH_QVAR_OUT_H 0x3BU +#define LSM6DSV16X_AH_QVAR_OUT_H 0x3BU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ah_qvar : 8; + uint8_t ah_qvar : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ah_qvar : 8; + uint8_t ah_qvar : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ah_qvar_out_h_t; -#define LSM6DSV16X_TIMESTAMP0 0x40U +#define LSM6DSV16X_TIMESTAMP0 0x40U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t timestamp : 8; + uint8_t timestamp : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t timestamp : 8; + uint8_t timestamp : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_timestamp0_t; -#define LSM6DSV16X_TIMESTAMP1 0x41U +#define LSM6DSV16X_TIMESTAMP1 0x41U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t timestamp : 8; + uint8_t timestamp : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t timestamp : 8; + uint8_t timestamp : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_timestamp1_t; -#define LSM6DSV16X_TIMESTAMP2 0x42U +#define LSM6DSV16X_TIMESTAMP2 0x42U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t timestamp : 8; + uint8_t timestamp : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t timestamp : 8; + uint8_t timestamp : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_timestamp2_t; -#define LSM6DSV16X_TIMESTAMP3 0x43U +#define LSM6DSV16X_TIMESTAMP3 0x43U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t timestamp : 8; + uint8_t timestamp : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t timestamp : 8; + uint8_t timestamp : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_timestamp3_t; -#define LSM6DSV16X_UI_STATUS_REG_OIS 0x44U +#define LSM6DSV16X_UI_STATUS_REG_OIS 0x44U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t xlda_ois : 1; - uint8_t gda_ois : 1; - uint8_t gyro_settling : 1; - uint8_t not_used0 : 5; + uint8_t xlda_ois : 1; + uint8_t gda_ois : 1; + uint8_t gyro_settling : 1; + uint8_t not_used0 : 5; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 5; - uint8_t gyro_settling : 1; - uint8_t gda_ois : 1; - uint8_t xlda_ois : 1; + uint8_t not_used0 : 5; + uint8_t gyro_settling : 1; + uint8_t gda_ois : 1; + uint8_t xlda_ois : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_status_reg_ois_t; -#define LSM6DSV16X_WAKE_UP_SRC 0x45U +#define LSM6DSV16X_WAKE_UP_SRC 0x45U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t z_wu : 1; - uint8_t y_wu : 1; - uint8_t x_wu : 1; - uint8_t wu_ia : 1; - uint8_t sleep_state : 1; - uint8_t ff_ia : 1; - uint8_t sleep_change_ia : 1; - uint8_t not_used0 : 1; + uint8_t z_wu : 1; + uint8_t y_wu : 1; + uint8_t x_wu : 1; + uint8_t wu_ia : 1; + uint8_t sleep_state : 1; + uint8_t ff_ia : 1; + uint8_t sleep_change_ia : 1; + uint8_t not_used0 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 1; - uint8_t sleep_change_ia : 1; - uint8_t ff_ia : 1; - uint8_t sleep_state : 1; - uint8_t wu_ia : 1; - uint8_t x_wu : 1; - uint8_t y_wu : 1; - uint8_t z_wu : 1; + uint8_t not_used0 : 1; + uint8_t sleep_change_ia : 1; + uint8_t ff_ia : 1; + uint8_t sleep_state : 1; + uint8_t wu_ia : 1; + uint8_t x_wu : 1; + uint8_t y_wu : 1; + uint8_t z_wu : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_wake_up_src_t; -#define LSM6DSV16X_TAP_SRC 0x46U +#define LSM6DSV16X_TAP_SRC 0x46U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t z_tap : 1; - uint8_t y_tap : 1; - uint8_t x_tap : 1; - uint8_t tap_sign : 1; - uint8_t double_tap : 1; - uint8_t single_tap : 1; - uint8_t tap_ia : 1; - uint8_t not_used0 : 1; + uint8_t z_tap : 1; + uint8_t y_tap : 1; + uint8_t x_tap : 1; + uint8_t tap_sign : 1; + uint8_t double_tap : 1; + uint8_t single_tap : 1; + uint8_t tap_ia : 1; + uint8_t not_used0 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 1; - uint8_t tap_ia : 1; - uint8_t single_tap : 1; - uint8_t double_tap : 1; - uint8_t tap_sign : 1; - uint8_t x_tap : 1; - uint8_t y_tap : 1; - uint8_t z_tap : 1; + uint8_t not_used0 : 1; + uint8_t tap_ia : 1; + uint8_t single_tap : 1; + uint8_t double_tap : 1; + uint8_t tap_sign : 1; + uint8_t x_tap : 1; + uint8_t y_tap : 1; + uint8_t z_tap : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_tap_src_t; -#define LSM6DSV16X_D6D_SRC 0x47U +#define LSM6DSV16X_D6D_SRC 0x47U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t xl : 1; - uint8_t xh : 1; - uint8_t yl : 1; - uint8_t yh : 1; - uint8_t zl : 1; - uint8_t zh : 1; - uint8_t d6d_ia : 1; - uint8_t not_used0 : 1; + uint8_t xl : 1; + uint8_t xh : 1; + uint8_t yl : 1; + uint8_t yh : 1; + uint8_t zl : 1; + uint8_t zh : 1; + uint8_t d6d_ia : 1; + uint8_t not_used0 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 1; - uint8_t d6d_ia : 1; - uint8_t zh : 1; - uint8_t zl : 1; - uint8_t yh : 1; - uint8_t yl : 1; - uint8_t xh : 1; - uint8_t xl : 1; + uint8_t not_used0 : 1; + uint8_t d6d_ia : 1; + uint8_t zh : 1; + uint8_t zl : 1; + uint8_t yh : 1; + uint8_t yl : 1; + uint8_t xh : 1; + uint8_t xl : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_d6d_src_t; -#define LSM6DSV16X_STATUS_MASTER_MAINPAGE 0x48U +#define LSM6DSV16X_STATUS_MASTER_MAINPAGE 0x48U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sens_hub_endop : 1; - uint8_t not_used0 : 2; - uint8_t slave0_nack : 1; - uint8_t slave1_nack : 1; - uint8_t slave2_nack : 1; - uint8_t slave3_nack : 1; - uint8_t wr_once_done : 1; + uint8_t sens_hub_endop : 1; + uint8_t not_used0 : 2; + uint8_t slave0_nack : 1; + uint8_t slave1_nack : 1; + uint8_t slave2_nack : 1; + uint8_t slave3_nack : 1; + uint8_t wr_once_done : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t wr_once_done : 1; - uint8_t slave3_nack : 1; - uint8_t slave2_nack : 1; - uint8_t slave1_nack : 1; - uint8_t slave0_nack : 1; - uint8_t not_used0 : 2; - uint8_t sens_hub_endop : 1; + uint8_t wr_once_done : 1; + uint8_t slave3_nack : 1; + uint8_t slave2_nack : 1; + uint8_t slave1_nack : 1; + uint8_t slave0_nack : 1; + uint8_t not_used0 : 2; + uint8_t sens_hub_endop : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_status_master_mainpage_t; #define LSM6DSV16X_EMB_FUNC_STATUS_MAINPAGE 0x49U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 3; - uint8_t is_step_det : 1; - uint8_t is_tilt : 1; - uint8_t is_sigmot : 1; - uint8_t not_used1 : 1; - uint8_t is_fsm_lc : 1; + uint8_t not_used0 : 3; + uint8_t is_step_det : 1; + uint8_t is_tilt : 1; + uint8_t is_sigmot : 1; + uint8_t not_used1 : 1; + uint8_t is_fsm_lc : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t is_fsm_lc : 1; - uint8_t not_used1 : 1; - uint8_t is_sigmot : 1; - uint8_t is_tilt : 1; - uint8_t is_step_det : 1; - uint8_t not_used0 : 3; + uint8_t is_fsm_lc : 1; + uint8_t not_used1 : 1; + uint8_t is_sigmot : 1; + uint8_t is_tilt : 1; + uint8_t is_step_det : 1; + uint8_t not_used0 : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_emb_func_status_mainpage_t; -#define LSM6DSV16X_FSM_STATUS_MAINPAGE 0x4AU +#define LSM6DSV16X_FSM_STATUS_MAINPAGE 0x4AU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t is_fsm1 : 1; - uint8_t is_fsm2 : 1; - uint8_t is_fsm3 : 1; - uint8_t is_fsm4 : 1; - uint8_t is_fsm5 : 1; - uint8_t is_fsm6 : 1; - uint8_t is_fsm7 : 1; - uint8_t is_fsm8 : 1; + uint8_t is_fsm1 : 1; + uint8_t is_fsm2 : 1; + uint8_t is_fsm3 : 1; + uint8_t is_fsm4 : 1; + uint8_t is_fsm5 : 1; + uint8_t is_fsm6 : 1; + uint8_t is_fsm7 : 1; + uint8_t is_fsm8 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t is_fsm8 : 1; - uint8_t is_fsm7 : 1; - uint8_t is_fsm6 : 1; - uint8_t is_fsm5 : 1; - uint8_t is_fsm4 : 1; - uint8_t is_fsm3 : 1; - uint8_t is_fsm2 : 1; - uint8_t is_fsm1 : 1; + uint8_t is_fsm8 : 1; + uint8_t is_fsm7 : 1; + uint8_t is_fsm6 : 1; + uint8_t is_fsm5 : 1; + uint8_t is_fsm4 : 1; + uint8_t is_fsm3 : 1; + uint8_t is_fsm2 : 1; + uint8_t is_fsm1 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_status_mainpage_t; -#define LSM6DSV16X_MLC_STATUS_MAINPAGE 0x4BU +#define LSM6DSV16X_MLC_STATUS_MAINPAGE 0x4BU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t is_mlc1 : 1; - uint8_t is_mlc2 : 1; - uint8_t is_mlc3 : 1; - uint8_t is_mlc4 : 1; - uint8_t not_used0 : 4; + uint8_t is_mlc1 : 1; + uint8_t is_mlc2 : 1; + uint8_t is_mlc3 : 1; + uint8_t is_mlc4 : 1; + uint8_t not_used0 : 4; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 4; - uint8_t is_mlc4 : 1; - uint8_t is_mlc3 : 1; - uint8_t is_mlc2 : 1; - uint8_t is_mlc1 : 1; + uint8_t not_used0 : 4; + uint8_t is_mlc4 : 1; + uint8_t is_mlc3 : 1; + uint8_t is_mlc2 : 1; + uint8_t is_mlc1 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_mlc_status_mainpage_t; -#define LSM6DSV16X_INTERNAL_FREQ 0x4FU +#define LSM6DSV16X_INTERNAL_FREQ 0x4FU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t freq_fine : 8; + uint8_t freq_fine : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t freq_fine : 8; + uint8_t freq_fine : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_internal_freq_t; -#define LSM6DSV16X_FUNCTIONS_ENABLE 0x50U +#define LSM6DSV16X_FUNCTIONS_ENABLE 0x50U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t inact_en : 2; - uint8_t not_used0 : 1; + uint8_t inact_en : 2; + uint8_t not_used0 : 1; uint8_t dis_rst_lir_all_int : 1; - uint8_t not_used1 : 2; - uint8_t timestamp_en : 1; - uint8_t interrupts_enable : 1; + uint8_t not_used1 : 2; + uint8_t timestamp_en : 1; + uint8_t interrupts_enable : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t interrupts_enable : 1; - uint8_t timestamp_en : 1; - uint8_t not_used1 : 2; + uint8_t interrupts_enable : 1; + uint8_t timestamp_en : 1; + uint8_t not_used1 : 2; uint8_t dis_rst_lir_all_int : 1; - uint8_t not_used0 : 1; - uint8_t inact_en : 2; + uint8_t not_used0 : 1; + uint8_t inact_en : 2; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_functions_enable_t; -#define LSM6DSV16X_DEN 0x51U +#define LSM6DSV16X_DEN 0x51U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t den_xl_g : 1; - uint8_t den_z : 1; - uint8_t den_y : 1; - uint8_t den_x : 1; - uint8_t den_xl_en : 1; - uint8_t lvl2_en : 1; - uint8_t lvl1_en : 1; - uint8_t not_used0 : 1; + uint8_t den_xl_g : 1; + uint8_t den_z : 1; + uint8_t den_y : 1; + uint8_t den_x : 1; + uint8_t den_xl_en : 1; + uint8_t lvl2_en : 1; + uint8_t lvl1_en : 1; + uint8_t not_used0 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 1; - uint8_t lvl1_en : 1; - uint8_t lvl2_en : 1; - uint8_t den_xl_en : 1; - uint8_t den_x : 1; - uint8_t den_y : 1; - uint8_t den_z : 1; - uint8_t den_xl_g : 1; + uint8_t not_used0 : 1; + uint8_t lvl1_en : 1; + uint8_t lvl2_en : 1; + uint8_t den_xl_en : 1; + uint8_t den_x : 1; + uint8_t den_y : 1; + uint8_t den_z : 1; + uint8_t den_xl_g : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_den_t; -#define LSM6DSV16X_INACTIVITY_DUR 0x54U +#define LSM6DSV16X_INACTIVITY_DUR 0x54U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t inact_dur : 2; - uint8_t xl_inact_odr : 2; - uint8_t wu_inact_ths_w : 3; + uint8_t inact_dur : 2; + uint8_t xl_inact_odr : 2; + uint8_t wu_inact_ths_w : 3; uint8_t sleep_status_on_int : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN uint8_t sleep_status_on_int : 1; - uint8_t wu_inact_ths_w : 3; - uint8_t xl_inact_odr : 2; - uint8_t inact_dur : 2; + uint8_t wu_inact_ths_w : 3; + uint8_t xl_inact_odr : 2; + uint8_t inact_dur : 2; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_inactivity_dur_t; -#define LSM6DSV16X_INACTIVITY_THS 0x55U +#define LSM6DSV16X_INACTIVITY_THS 0x55U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t inact_ths : 6; - uint8_t not_used0 : 2; + uint8_t inact_ths : 6; + uint8_t not_used0 : 2; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 2; - uint8_t inact_ths : 6; + uint8_t not_used0 : 2; + uint8_t inact_ths : 6; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_inactivity_ths_t; -#define LSM6DSV16X_TAP_CFG0 0x56U +#define LSM6DSV16X_TAP_CFG0 0x56U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t lir : 1; - uint8_t tap_z_en : 1; - uint8_t tap_y_en : 1; - uint8_t tap_x_en : 1; - uint8_t slope_fds : 1; - uint8_t not_used0 : 1; - uint8_t low_pass_on_6d : 1; - uint8_t not_used1 : 1; + uint8_t lir : 1; + uint8_t tap_z_en : 1; + uint8_t tap_y_en : 1; + uint8_t tap_x_en : 1; + uint8_t slope_fds : 1; + uint8_t hw_func_mask_xl_settl : 1; + uint8_t low_pass_on_6d : 1; + uint8_t not_used1 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 1; - uint8_t low_pass_on_6d : 1; - uint8_t not_used0 : 1; - uint8_t slope_fds : 1; - uint8_t tap_x_en : 1; - uint8_t tap_y_en : 1; - uint8_t tap_z_en : 1; - uint8_t lir : 1; + uint8_t not_used1 : 1; + uint8_t low_pass_on_6d : 1; + uint8_t hw_func_mask_xl_settl : 1; + uint8_t slope_fds : 1; + uint8_t tap_x_en : 1; + uint8_t tap_y_en : 1; + uint8_t tap_z_en : 1; + uint8_t lir : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_tap_cfg0_t; -#define LSM6DSV16X_TAP_CFG1 0x57U +#define LSM6DSV16X_TAP_CFG1 0x57U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t tap_ths_x : 5; - uint8_t tap_priority : 3; + uint8_t tap_ths_x : 5; + uint8_t tap_priority : 3; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t tap_priority : 3; - uint8_t tap_ths_x : 5; + uint8_t tap_priority : 3; + uint8_t tap_ths_x : 5; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_tap_cfg1_t; -#define LSM6DSV16X_TAP_CFG2 0x58U +#define LSM6DSV16X_TAP_CFG2 0x58U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t tap_ths_y : 5; - uint8_t not_used0 : 3; + uint8_t tap_ths_y : 5; + uint8_t not_used0 : 3; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 3; - uint8_t tap_ths_y : 5; + uint8_t not_used0 : 3; + uint8_t tap_ths_y : 5; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_tap_cfg2_t; -#define LSM6DSV16X_TAP_THS_6D 0x59U +#define LSM6DSV16X_TAP_THS_6D 0x59U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t tap_ths_z : 5; - uint8_t sixd_ths : 2; - uint8_t d4d_en : 1; + uint8_t tap_ths_z : 5; + uint8_t sixd_ths : 2; + uint8_t d4d_en : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t d4d_en : 1; - uint8_t sixd_ths : 2; - uint8_t tap_ths_z : 5; + uint8_t d4d_en : 1; + uint8_t sixd_ths : 2; + uint8_t tap_ths_z : 5; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_tap_ths_6d_t; -#define LSM6DSV16X_INT_DUR2 0x5AU +#define LSM6DSV16X_TAP_DUR 0x5AU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t shock : 2; - uint8_t quiet : 2; - uint8_t dur : 4; + uint8_t shock : 2; + uint8_t quiet : 2; + uint8_t dur : 4; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t dur : 4; - uint8_t quiet : 2; - uint8_t shock : 2; + uint8_t dur : 4; + uint8_t quiet : 2; + uint8_t shock : 2; #endif /* DRV_BYTE_ORDER */ -} lsm6dsv16x_int_dur2_t; +} lsm6dsv16x_tap_dur_t; -#define LSM6DSV16X_WAKE_UP_THS 0x5BU +#define LSM6DSV16X_WAKE_UP_THS 0x5BU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t wk_ths : 6; - uint8_t usr_off_on_wu : 1; - uint8_t single_double_tap : 1; + uint8_t wk_ths : 6; + uint8_t usr_off_on_wu : 1; + uint8_t single_double_tap : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t single_double_tap : 1; - uint8_t usr_off_on_wu : 1; - uint8_t wk_ths : 6; + uint8_t single_double_tap : 1; + uint8_t usr_off_on_wu : 1; + uint8_t wk_ths : 6; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_wake_up_ths_t; -#define LSM6DSV16X_WAKE_UP_DUR 0x5CU +#define LSM6DSV16X_WAKE_UP_DUR 0x5CU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sleep_dur : 4; - uint8_t not_used0 : 1; - uint8_t wake_dur : 2; - uint8_t ff_dur : 1; + uint8_t sleep_dur : 4; + uint8_t not_used0 : 1; + uint8_t wake_dur : 2; + uint8_t ff_dur : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ff_dur : 1; - uint8_t wake_dur : 2; - uint8_t not_used0 : 1; - uint8_t sleep_dur : 4; + uint8_t ff_dur : 1; + uint8_t wake_dur : 2; + uint8_t not_used0 : 1; + uint8_t sleep_dur : 4; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_wake_up_dur_t; -#define LSM6DSV16X_FREE_FALL 0x5DU +#define LSM6DSV16X_FREE_FALL 0x5DU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ff_ths : 3; - uint8_t ff_dur : 5; + uint8_t ff_ths : 3; + uint8_t ff_dur : 5; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ff_dur : 5; - uint8_t ff_ths : 3; + uint8_t ff_dur : 5; + uint8_t ff_ths : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_free_fall_t; -#define LSM6DSV16X_MD1_CFG 0x5EU +#define LSM6DSV16X_MD1_CFG 0x5EU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t int1_shub : 1; - uint8_t int1_emb_func : 1; - uint8_t int1_6d : 1; - uint8_t int1_double_tap : 1; - uint8_t int1_ff : 1; - uint8_t int1_wu : 1; - uint8_t int1_single_tap : 1; - uint8_t int1_sleep_change : 1; + uint8_t int1_shub : 1; + uint8_t int1_emb_func : 1; + uint8_t int1_6d : 1; + uint8_t int1_double_tap : 1; + uint8_t int1_ff : 1; + uint8_t int1_wu : 1; + uint8_t int1_single_tap : 1; + uint8_t int1_sleep_change : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t int1_sleep_change : 1; - uint8_t int1_single_tap : 1; - uint8_t int1_wu : 1; - uint8_t int1_ff : 1; - uint8_t int1_double_tap : 1; - uint8_t int1_6d : 1; - uint8_t int1_emb_func : 1; - uint8_t int1_shub : 1; + uint8_t int1_sleep_change : 1; + uint8_t int1_single_tap : 1; + uint8_t int1_wu : 1; + uint8_t int1_ff : 1; + uint8_t int1_double_tap : 1; + uint8_t int1_6d : 1; + uint8_t int1_emb_func : 1; + uint8_t int1_shub : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_md1_cfg_t; -#define LSM6DSV16X_MD2_CFG 0x5FU +#define LSM6DSV16X_MD2_CFG 0x5FU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t int2_timestamp : 1; - uint8_t int2_emb_func : 1; - uint8_t int2_6d : 1; - uint8_t int2_double_tap : 1; - uint8_t int2_ff : 1; - uint8_t int2_wu : 1; - uint8_t int2_single_tap : 1; - uint8_t int2_sleep_change : 1; + uint8_t int2_timestamp : 1; + uint8_t int2_emb_func : 1; + uint8_t int2_6d : 1; + uint8_t int2_double_tap : 1; + uint8_t int2_ff : 1; + uint8_t int2_wu : 1; + uint8_t int2_single_tap : 1; + uint8_t int2_sleep_change : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t int2_sleep_change : 1; - uint8_t int2_single_tap : 1; - uint8_t int2_wu : 1; - uint8_t int2_ff : 1; - uint8_t int2_double_tap : 1; - uint8_t int2_6d : 1; - uint8_t int2_emb_func : 1; - uint8_t int2_timestamp : 1; + uint8_t int2_sleep_change : 1; + uint8_t int2_single_tap : 1; + uint8_t int2_wu : 1; + uint8_t int2_ff : 1; + uint8_t int2_double_tap : 1; + uint8_t int2_6d : 1; + uint8_t int2_emb_func : 1; + uint8_t int2_timestamp : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_md2_cfg_t; -#define LSM6DSV16X_S4S_ST_CMD_CODE 0x60U -typedef struct { -#if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t st_cmd_code : 8; -#elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t st_cmd_code : 8; -#endif /* DRV_BYTE_ORDER */ -} lsm6dsv16x_s4s_st_cmd_code_t; - -#define LSM6DSV16X_S4S_DT_REG 0x61U +#define LSM6DSV16X_HAODR_CFG 0x62U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t dt : 8; + uint8_t haodr_sel : 2; + uint8_t not_used0 : 6; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t dt : 8; + uint8_t not_used0 : 6; + uint8_t haodr_sel : 2; #endif /* DRV_BYTE_ORDER */ -} lsm6dsv16x_s4s_dt_reg_t; +} lsm6dsv16x_haodr_cfg_t; -#define LSM6DSV16X_EMB_FUNC_CFG 0x63U +#define LSM6DSV16X_EMB_FUNC_CFG 0x63U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 3; - uint8_t emb_func_disable : 1; - uint8_t emb_func_irq_mask_xl_settl : 1; + uint8_t not_used0 : 3; + uint8_t emb_func_disable : 1; + uint8_t emb_func_irq_mask_xl_settl : 1; uint8_t emb_func_irq_mask_g_settl : 1; - uint8_t not_used1 : 2; + uint8_t not_used1 : 2; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 2; + uint8_t not_used1 : 2; uint8_t emb_func_irq_mask_g_settl : 1; - uint8_t emb_func_irq_mask_xl_settl : 1; - uint8_t emb_func_disable : 1; - uint8_t not_used0 : 3; + uint8_t emb_func_irq_mask_xl_settl : 1; + uint8_t emb_func_disable : 1; + uint8_t not_used0 : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_emb_func_cfg_t; -#define LSM6DSV16X_UI_HANDSHAKE_CTRL 0x64U +#define LSM6DSV16X_UI_HANDSHAKE_CTRL 0x64U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ui_shared_req : 1; - uint8_t ui_shared_ack : 1; - uint8_t not_used0 : 6; + uint8_t ui_shared_req : 1; + uint8_t ui_shared_ack : 1; + uint8_t not_used0 : 6; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 6; - uint8_t ui_shared_ack : 1; - uint8_t ui_shared_req : 1; + uint8_t not_used0 : 6; + uint8_t ui_shared_ack : 1; + uint8_t ui_shared_req : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_handshake_ctrl_t; -#define LSM6DSV16X_UI_SPI2_SHARED_0 0x65U +#define LSM6DSV16X_UI_SPI2_SHARED_0 0x65U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ui_spi2_shared : 8; + uint8_t ui_spi2_shared : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ui_spi2_shared : 8; + uint8_t ui_spi2_shared : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_spi2_shared_0_t; -#define LSM6DSV16X_UI_SPI2_SHARED_1 0x66U +#define LSM6DSV16X_UI_SPI2_SHARED_1 0x66U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ui_spi2_shared : 8; + uint8_t ui_spi2_shared : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ui_spi2_shared : 8; + uint8_t ui_spi2_shared : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_spi2_shared_1_t; -#define LSM6DSV16X_UI_SPI2_SHARED_2 0x67U +#define LSM6DSV16X_UI_SPI2_SHARED_2 0x67U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ui_spi2_shared : 8; + uint8_t ui_spi2_shared : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ui_spi2_shared : 8; + uint8_t ui_spi2_shared : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_spi2_shared_2_t; -#define LSM6DSV16X_UI_SPI2_SHARED_3 0x68U +#define LSM6DSV16X_UI_SPI2_SHARED_3 0x68U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ui_spi2_shared : 8; + uint8_t ui_spi2_shared : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ui_spi2_shared : 8; + uint8_t ui_spi2_shared : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_spi2_shared_3_t; -#define LSM6DSV16X_UI_SPI2_SHARED_4 0x69U +#define LSM6DSV16X_UI_SPI2_SHARED_4 0x69U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ui_spi2_shared : 8; + uint8_t ui_spi2_shared : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ui_spi2_shared : 8; + uint8_t ui_spi2_shared : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_spi2_shared_4_t; -#define LSM6DSV16X_UI_SPI2_SHARED_5 0x6AU +#define LSM6DSV16X_UI_SPI2_SHARED_5 0x6AU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ui_spi2_shared : 8; + uint8_t ui_spi2_shared : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ui_spi2_shared : 8; + uint8_t ui_spi2_shared : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_spi2_shared_5_t; -#define LSM6DSV16X_CTRL_EIS 0x6BU +#define LSM6DSV16X_CTRL_EIS 0x6BU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fs_g_eis : 3; - uint8_t g_eis_on_g_ois_out_reg : 1; - uint8_t lpf_g_eis_bw : 1; - uint8_t not_used0 : 1; - uint8_t odr_g_eis : 2; + uint8_t fs_g_eis : 3; + uint8_t g_eis_on_g_ois_out_reg : 1; + uint8_t lpf_g_eis_bw : 1; + uint8_t not_used0 : 1; + uint8_t odr_g_eis : 2; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t odr_g_eis : 2; - uint8_t not_used0 : 1; - uint8_t lpf_g_eis_bw : 1; - uint8_t g_eis_on_g_ois_out_reg : 1; - uint8_t fs_g_eis : 3; + uint8_t odr_g_eis : 2; + uint8_t not_used0 : 1; + uint8_t lpf_g_eis_bw : 1; + uint8_t g_eis_on_g_ois_out_reg : 1; + uint8_t fs_g_eis : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ctrl_eis_t; -#define LSM6DSV16X_UI_INT_OIS 0x6FU +#define LSM6DSV16X_UI_INT_OIS 0x6FU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 4; - uint8_t st_ois_clampdis : 1; - uint8_t not_used1 : 1; - uint8_t drdy_mask_ois : 1; - uint8_t int2_drdy_ois : 1; + uint8_t not_used0 : 4; + uint8_t st_ois_clampdis : 1; + uint8_t not_used1 : 1; + uint8_t drdy_mask_ois : 1; + uint8_t int2_drdy_ois : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t int2_drdy_ois : 1; - uint8_t drdy_mask_ois : 1; - uint8_t not_used1 : 1; - uint8_t st_ois_clampdis : 1; - uint8_t not_used0 : 4; + uint8_t int2_drdy_ois : 1; + uint8_t drdy_mask_ois : 1; + uint8_t not_used1 : 1; + uint8_t st_ois_clampdis : 1; + uint8_t not_used0 : 4; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_int_ois_t; -#define LSM6DSV16X_UI_CTRL1_OIS 0x70U +#define LSM6DSV16X_UI_CTRL1_OIS 0x70U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t spi2_read_en : 1; - uint8_t ois_g_en : 1; - uint8_t ois_xl_en : 1; - uint8_t not_used0 : 2; - uint8_t sim_ois : 1; - uint8_t not_used1 : 2; + uint8_t spi2_read_en : 1; + uint8_t ois_g_en : 1; + uint8_t ois_xl_en : 1; + uint8_t not_used0 : 2; + uint8_t sim_ois : 1; + uint8_t not_used1 : 2; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 2; - uint8_t sim_ois : 1; - uint8_t not_used0 : 2; - uint8_t ois_xl_en : 1; - uint8_t ois_g_en : 1; - uint8_t spi2_read_en : 1; + uint8_t not_used1 : 2; + uint8_t sim_ois : 1; + uint8_t not_used0 : 2; + uint8_t ois_xl_en : 1; + uint8_t ois_g_en : 1; + uint8_t spi2_read_en : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_ctrl1_ois_t; -#define LSM6DSV16X_UI_CTRL2_OIS 0x71U +#define LSM6DSV16X_UI_CTRL2_OIS 0x71U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fs_g_ois : 3; - uint8_t lpf1_g_ois_bw : 2; - uint8_t not_used0 : 3; + uint8_t fs_g_ois : 3; + uint8_t lpf1_g_ois_bw : 2; + uint8_t not_used0 : 3; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 3; - uint8_t lpf1_g_ois_bw : 2; - uint8_t fs_g_ois : 3; + uint8_t not_used0 : 3; + uint8_t lpf1_g_ois_bw : 2; + uint8_t fs_g_ois : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_ctrl2_ois_t; -#define LSM6DSV16X_UI_CTRL3_OIS 0x72U +#define LSM6DSV16X_UI_CTRL3_OIS 0x72U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fs_xl_ois : 2; - uint8_t not_used0 : 1; - uint8_t lpf_xl_ois_bw : 3; - uint8_t not_used1 : 2; + uint8_t fs_xl_ois : 2; + uint8_t not_used0 : 1; + uint8_t lpf_xl_ois_bw : 3; + uint8_t not_used1 : 2; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 2; - uint8_t lpf_xl_ois_bw : 3; - uint8_t not_used0 : 1; - uint8_t fs_xl_ois : 2; + uint8_t not_used1 : 2; + uint8_t lpf_xl_ois_bw : 3; + uint8_t not_used0 : 1; + uint8_t fs_xl_ois : 2; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ui_ctrl3_ois_t; -#define LSM6DSV16X_X_OFS_USR 0x73U +#define LSM6DSV16X_X_OFS_USR 0x73U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t x_ofs_usr : 8; + uint8_t x_ofs_usr : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t x_ofs_usr : 8; + uint8_t x_ofs_usr : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_x_ofs_usr_t; -#define LSM6DSV16X_Y_OFS_USR 0x74U +#define LSM6DSV16X_Y_OFS_USR 0x74U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t y_ofs_usr : 8; + uint8_t y_ofs_usr : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t y_ofs_usr : 8; + uint8_t y_ofs_usr : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_y_ofs_usr_t; -#define LSM6DSV16X_Z_OFS_USR 0x75U +#define LSM6DSV16X_Z_OFS_USR 0x75U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t z_ofs_usr : 8; + uint8_t z_ofs_usr : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t z_ofs_usr : 8; + uint8_t z_ofs_usr : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_z_ofs_usr_t; -#define LSM6DSV16X_FIFO_DATA_OUT_TAG 0x78U +#define LSM6DSV16X_FIFO_DATA_OUT_TAG 0x78U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 1; - uint8_t tag_cnt : 2; - uint8_t tag_sensor : 5; + uint8_t not_used0 : 1; + uint8_t tag_cnt : 2; + uint8_t tag_sensor : 5; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t tag_sensor : 5; - uint8_t tag_cnt : 2; - uint8_t not_used0 : 1; + uint8_t tag_sensor : 5; + uint8_t tag_cnt : 2; + uint8_t not_used0 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fifo_data_out_tag_t; -#define LSM6DSV16X_FIFO_DATA_OUT_X_L 0x79U +#define LSM6DSV16X_FIFO_DATA_OUT_X_L 0x79U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fifo_data_out : 8; + uint8_t fifo_data_out : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fifo_data_out : 8; + uint8_t fifo_data_out : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fifo_data_out_x_l_t; -#define LSM6DSV16X_FIFO_DATA_OUT_X_H 0x7AU +#define LSM6DSV16X_FIFO_DATA_OUT_X_H 0x7AU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fifo_data_out : 8; + uint8_t fifo_data_out : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fifo_data_out : 8; + uint8_t fifo_data_out : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fifo_data_out_x_h_t; -#define LSM6DSV16X_FIFO_DATA_OUT_Y_L 0x7BU +#define LSM6DSV16X_FIFO_DATA_OUT_Y_L 0x7BU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fifo_data_out : 8; + uint8_t fifo_data_out : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fifo_data_out : 8; + uint8_t fifo_data_out : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fifo_data_out_y_l_t; -#define LSM6DSV16X_FIFO_DATA_OUT_Y_H 0x7CU +#define LSM6DSV16X_FIFO_DATA_OUT_Y_H 0x7CU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fifo_data_out : 8; + uint8_t fifo_data_out : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fifo_data_out : 8; + uint8_t fifo_data_out : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fifo_data_out_y_h_t; -#define LSM6DSV16X_FIFO_DATA_OUT_Z_L 0x7DU +#define LSM6DSV16X_FIFO_DATA_OUT_Z_L 0x7DU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fifo_data_out : 8; + uint8_t fifo_data_out : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fifo_data_out : 8; + uint8_t fifo_data_out : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fifo_data_out_z_l_t; -#define LSM6DSV16X_FIFO_DATA_OUT_Z_H 0x7EU +#define LSM6DSV16X_FIFO_DATA_OUT_Z_H 0x7EU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fifo_data_out : 8; + uint8_t fifo_data_out : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fifo_data_out : 8; + uint8_t fifo_data_out : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fifo_data_out_z_h_t; @@ -1625,232 +1603,232 @@ typedef struct { * */ -#define LSM6DSV16X_SPI2_WHO_AM_I 0x0FU +#define LSM6DSV16X_SPI2_WHO_AM_I 0x0FU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t id : 8; + uint8_t id : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t id : 8; + uint8_t id : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_who_am_i_t; -#define LSM6DSV16X_SPI2_STATUS_REG_OIS 0x1EU +#define LSM6DSV16X_SPI2_STATUS_REG_OIS 0x1EU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t xlda : 1; - uint8_t gda : 1; - uint8_t gyro_settling : 1; - uint8_t not_used0 : 5; + uint8_t xlda : 1; + uint8_t gda : 1; + uint8_t gyro_settling : 1; + uint8_t not_used0 : 5; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 5; - uint8_t gyro_settling : 1; - uint8_t gda : 1; - uint8_t xlda : 1; + uint8_t not_used0 : 5; + uint8_t gyro_settling : 1; + uint8_t gda : 1; + uint8_t xlda : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_status_reg_ois_t; -#define LSM6DSV16X_SPI2_OUT_TEMP_L 0x20U +#define LSM6DSV16X_SPI2_OUT_TEMP_L 0x20U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t temp : 8; + uint8_t temp : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t temp : 8; + uint8_t temp : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_out_temp_l_t; -#define LSM6DSV16X_SPI2_OUT_TEMP_H 0x21U +#define LSM6DSV16X_SPI2_OUT_TEMP_H 0x21U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t temp : 8; + uint8_t temp : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t temp : 8; + uint8_t temp : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_out_temp_h_t; -#define LSM6DSV16X_SPI2_OUTX_L_G_OIS 0x22U +#define LSM6DSV16X_SPI2_OUTX_L_G_OIS 0x22U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t spi2_outx_g_ois : 8; + uint8_t spi2_outx_g_ois : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t spi2_outx_g_ois : 8; + uint8_t spi2_outx_g_ois : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_outx_l_g_ois_t; -#define LSM6DSV16X_SPI2_OUTX_H_G_OIS 0x23U +#define LSM6DSV16X_SPI2_OUTX_H_G_OIS 0x23U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t spi2_outx_g_ois : 8; + uint8_t spi2_outx_g_ois : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t spi2_outx_g_ois : 8; + uint8_t spi2_outx_g_ois : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_outx_h_g_ois_t; -#define LSM6DSV16X_SPI2_OUTY_L_G_OIS 0x24U +#define LSM6DSV16X_SPI2_OUTY_L_G_OIS 0x24U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t spi2_outy_g_ois : 8; + uint8_t spi2_outy_g_ois : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t spi2_outy_g_ois : 8; + uint8_t spi2_outy_g_ois : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_outy_l_g_ois_t; -#define LSM6DSV16X_SPI2_OUTY_H_G_OIS 0x25U +#define LSM6DSV16X_SPI2_OUTY_H_G_OIS 0x25U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t spi2_outy_g_ois : 8; + uint8_t spi2_outy_g_ois : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t spi2_outy_g_ois : 8; + uint8_t spi2_outy_g_ois : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_outy_h_g_ois_t; -#define LSM6DSV16X_SPI2_OUTZ_L_G_OIS 0x26U +#define LSM6DSV16X_SPI2_OUTZ_L_G_OIS 0x26U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t spi2_outz_g_ois : 8; + uint8_t spi2_outz_g_ois : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t spi2_outz_g_ois : 8; + uint8_t spi2_outz_g_ois : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_outz_l_g_ois_t; -#define LSM6DSV16X_SPI2_OUTZ_H_G_OIS 0x27U +#define LSM6DSV16X_SPI2_OUTZ_H_G_OIS 0x27U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t spi2_outz_g_ois : 8; + uint8_t spi2_outz_g_ois : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t spi2_outz_g_ois : 8; + uint8_t spi2_outz_g_ois : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_outz_h_g_ois_t; -#define LSM6DSV16X_SPI2_OUTX_L_A_OIS 0x28U +#define LSM6DSV16X_SPI2_OUTX_L_A_OIS 0x28U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t spi2_outx_a_ois : 8; + uint8_t spi2_outx_a_ois : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t spi2_outx_a_ois : 8; + uint8_t spi2_outx_a_ois : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_outx_l_a_ois_t; -#define LSM6DSV16X_SPI2_OUTX_H_A_OIS 0x29U +#define LSM6DSV16X_SPI2_OUTX_H_A_OIS 0x29U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t spi2_outx_a_ois : 8; + uint8_t spi2_outx_a_ois : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t spi2_outx_a_ois : 8; + uint8_t spi2_outx_a_ois : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_outx_h_a_ois_t; -#define LSM6DSV16X_SPI2_OUTY_L_A_OIS 0x2AU +#define LSM6DSV16X_SPI2_OUTY_L_A_OIS 0x2AU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t spi2_outy_a_ois : 8; + uint8_t spi2_outy_a_ois : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t spi2_outy_a_ois : 8; + uint8_t spi2_outy_a_ois : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_outy_l_a_ois_t; -#define LSM6DSV16X_SPI2_OUTY_H_A_OIS 0x2BU +#define LSM6DSV16X_SPI2_OUTY_H_A_OIS 0x2BU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t spi2_outy_a_ois : 8; + uint8_t spi2_outy_a_ois : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t spi2_outy_a_ois : 8; + uint8_t spi2_outy_a_ois : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_outy_h_a_ois_t; -#define LSM6DSV16X_SPI2_OUTZ_L_A_OIS 0x2CU +#define LSM6DSV16X_SPI2_OUTZ_L_A_OIS 0x2CU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t spi2_outz_a_ois : 8; + uint8_t spi2_outz_a_ois : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t spi2_outz_a_ois : 8; + uint8_t spi2_outz_a_ois : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_outz_l_a_ois_t; -#define LSM6DSV16X_SPI2_OUTZ_H_A_OIS 0x2DU +#define LSM6DSV16X_SPI2_OUTZ_H_A_OIS 0x2DU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t spi2_outz_a_ois : 8; + uint8_t spi2_outz_a_ois : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t spi2_outz_a_ois : 8; + uint8_t spi2_outz_a_ois : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_outz_h_a_ois_t; -#define LSM6DSV16X_SPI2_HANDSHAKE_CTRL 0x6EU +#define LSM6DSV16X_SPI2_HANDSHAKE_CTRL 0x6EU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t spi2_shared_ack : 1; - uint8_t spi2_shared_req : 1; - uint8_t not_used0 : 6; + uint8_t spi2_shared_ack : 1; + uint8_t spi2_shared_req : 1; + uint8_t not_used0 : 6; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 6; - uint8_t spi2_shared_req : 1; - uint8_t spi2_shared_ack : 1; + uint8_t not_used0 : 6; + uint8_t spi2_shared_req : 1; + uint8_t spi2_shared_ack : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_handshake_ctrl_t; -#define LSM6DSV16X_SPI2_INT_OIS 0x6FU +#define LSM6DSV16X_SPI2_INT_OIS 0x6FU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t st_xl_ois : 2; - uint8_t st_g_ois : 2; - uint8_t st_ois_clampdis : 1; - uint8_t not_used0 : 1; - uint8_t drdy_mask_ois : 1; - uint8_t int2_drdy_ois : 1; + uint8_t st_xl_ois : 2; + uint8_t st_g_ois : 2; + uint8_t st_ois_clampdis : 1; + uint8_t not_used0 : 1; + uint8_t drdy_mask_ois : 1; + uint8_t int2_drdy_ois : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t int2_drdy_ois : 1; - uint8_t drdy_mask_ois : 1; - uint8_t not_used0 : 1; - uint8_t st_ois_clampdis : 1; - uint8_t st_g_ois : 2; - uint8_t st_xl_ois : 2; + uint8_t int2_drdy_ois : 1; + uint8_t drdy_mask_ois : 1; + uint8_t not_used0 : 1; + uint8_t st_ois_clampdis : 1; + uint8_t st_g_ois : 2; + uint8_t st_xl_ois : 2; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_int_ois_t; -#define LSM6DSV16X_SPI2_CTRL1_OIS 0x70U +#define LSM6DSV16X_SPI2_CTRL1_OIS 0x70U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t spi2_read_en : 1; - uint8_t ois_g_en : 1; - uint8_t ois_xl_en : 1; - uint8_t not_used0 : 2; - uint8_t sim_ois : 1; - uint8_t not_used1 : 2; + uint8_t spi2_read_en : 1; + uint8_t ois_g_en : 1; + uint8_t ois_xl_en : 1; + uint8_t not_used0 : 2; + uint8_t sim_ois : 1; + uint8_t not_used1 : 2; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 2; - uint8_t sim_ois : 1; - uint8_t not_used0 : 2; - uint8_t ois_xl_en : 1; - uint8_t ois_g_en : 1; - uint8_t spi2_read_en : 1; + uint8_t not_used1 : 2; + uint8_t sim_ois : 1; + uint8_t not_used0 : 2; + uint8_t ois_xl_en : 1; + uint8_t ois_g_en : 1; + uint8_t spi2_read_en : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_ctrl1_ois_t; -#define LSM6DSV16X_SPI2_CTRL2_OIS 0x71U +#define LSM6DSV16X_SPI2_CTRL2_OIS 0x71U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fs_g_ois : 3; - uint8_t lpf1_g_ois_bw : 2; - uint8_t not_used0 : 3; + uint8_t fs_g_ois : 3; + uint8_t lpf1_g_ois_bw : 2; + uint8_t not_used0 : 3; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 3; - uint8_t lpf1_g_ois_bw : 2; - uint8_t fs_g_ois : 3; + uint8_t not_used0 : 3; + uint8_t lpf1_g_ois_bw : 2; + uint8_t fs_g_ois : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_ctrl2_ois_t; -#define LSM6DSV16X_SPI2_CTRL3_OIS 0x72U +#define LSM6DSV16X_SPI2_CTRL3_OIS 0x72U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fs_xl_ois : 2; - uint8_t not_used0 : 1; - uint8_t lpf_xl_ois_bw : 3; - uint8_t not_used1 : 2; + uint8_t fs_xl_ois : 2; + uint8_t not_used0 : 1; + uint8_t lpf_xl_ois_bw : 3; + uint8_t not_used1 : 2; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 2; - uint8_t lpf_xl_ois_bw : 3; - uint8_t not_used0 : 1; - uint8_t fs_xl_ois : 2; + uint8_t not_used1 : 2; + uint8_t lpf_xl_ois_bw : 3; + uint8_t not_used0 : 1; + uint8_t fs_xl_ois : 2; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_spi2_ctrl3_ois_t; @@ -1864,670 +1842,699 @@ typedef struct { * */ -#define LSM6DSV16X_PAGE_SEL 0x2U +#define LSM6DSV16X_PAGE_SEL 0x2U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 4; - uint8_t page_sel : 4; + uint8_t not_used0 : 4; + uint8_t page_sel : 4; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t page_sel : 4; - uint8_t not_used0 : 4; + uint8_t page_sel : 4; + uint8_t not_used0 : 4; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_page_sel_t; -#define LSM6DSV16X_EMB_FUNC_EN_A 0x4U +#define LSM6DSV16X_EMB_FUNC_EN_A 0x4U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 3; - uint8_t pedo_en : 1; - uint8_t tilt_en : 1; - uint8_t sign_motion_en : 1; - uint8_t not_used1 : 1; - uint8_t mlc_before_fsm_en : 1; + uint8_t not_used0 : 1; + uint8_t sflp_game_en : 1; + uint8_t not_used2 : 1; + uint8_t pedo_en : 1; + uint8_t tilt_en : 1; + uint8_t sign_motion_en : 1; + uint8_t not_used1 : 1; + uint8_t mlc_before_fsm_en : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t mlc_before_fsm_en : 1; - uint8_t not_used1 : 1; - uint8_t sign_motion_en : 1; - uint8_t tilt_en : 1; - uint8_t pedo_en : 1; - uint8_t not_used0 : 3; + uint8_t mlc_before_fsm_en : 1; + uint8_t not_used1 : 1; + uint8_t sign_motion_en : 1; + uint8_t tilt_en : 1; + uint8_t pedo_en : 1; + uint8_t not_used2 : 1; + uint8_t sflp_game_en : 1; + uint8_t not_used0 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_emb_func_en_a_t; -#define LSM6DSV16X_EMB_FUNC_EN_B 0x5U +#define LSM6DSV16X_EMB_FUNC_EN_B 0x5U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_en : 1; - uint8_t not_used0 : 2; - uint8_t fifo_compr_en : 1; - uint8_t mlc_en : 1; - uint8_t not_used1 : 3; + uint8_t fsm_en : 1; + uint8_t not_used0 : 2; + uint8_t fifo_compr_en : 1; + uint8_t mlc_en : 1; + uint8_t not_used1 : 3; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 3; - uint8_t mlc_en : 1; - uint8_t fifo_compr_en : 1; - uint8_t not_used0 : 2; - uint8_t fsm_en : 1; + uint8_t not_used1 : 3; + uint8_t mlc_en : 1; + uint8_t fifo_compr_en : 1; + uint8_t not_used0 : 2; + uint8_t fsm_en : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_emb_func_en_b_t; -#define LSM6DSV16X_EMB_FUNC_EXEC_STATUS 0x7U +#define LSM6DSV16X_EMB_FUNC_EXEC_STATUS 0x7U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t emb_func_endop : 1; - uint8_t emb_func_exec_ovr : 1; - uint8_t not_used0 : 6; + uint8_t emb_func_endop : 1; + uint8_t emb_func_exec_ovr : 1; + uint8_t not_used0 : 6; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 6; - uint8_t emb_func_exec_ovr : 1; - uint8_t emb_func_endop : 1; + uint8_t not_used0 : 6; + uint8_t emb_func_exec_ovr : 1; + uint8_t emb_func_endop : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_emb_func_exec_status_t; -#define LSM6DSV16X_PAGE_ADDRESS 0x8U +#define LSM6DSV16X_PAGE_ADDRESS 0x8U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t page_addr : 8; + uint8_t page_addr : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t page_addr : 8; + uint8_t page_addr : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_page_address_t; -#define LSM6DSV16X_PAGE_VALUE 0x9U +#define LSM6DSV16X_PAGE_VALUE 0x9U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t page_value : 8; + uint8_t page_value : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t page_value : 8; + uint8_t page_value : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_page_value_t; -#define LSM6DSV16X_EMB_FUNC_INT1 0x0AU +#define LSM6DSV16X_EMB_FUNC_INT1 0x0AU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 3; - uint8_t int1_step_detector : 1; - uint8_t int1_tilt : 1; - uint8_t int1_sig_mot : 1; - uint8_t not_used1 : 1; - uint8_t int1_fsm_lc : 1; + uint8_t not_used0 : 3; + uint8_t int1_step_detector : 1; + uint8_t int1_tilt : 1; + uint8_t int1_sig_mot : 1; + uint8_t not_used1 : 1; + uint8_t int1_fsm_lc : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t int1_fsm_lc : 1; - uint8_t not_used1 : 1; - uint8_t int1_sig_mot : 1; - uint8_t int1_tilt : 1; - uint8_t int1_step_detector : 1; - uint8_t not_used0 : 3; + uint8_t int1_fsm_lc : 1; + uint8_t not_used1 : 1; + uint8_t int1_sig_mot : 1; + uint8_t int1_tilt : 1; + uint8_t int1_step_detector : 1; + uint8_t not_used0 : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_emb_func_int1_t; -#define LSM6DSV16X_FSM_INT1 0x0BU +#define LSM6DSV16X_FSM_INT1 0x0BU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t int1_fsm1 : 1; - uint8_t int1_fsm2 : 1; - uint8_t int1_fsm3 : 1; - uint8_t int1_fsm4 : 1; - uint8_t int1_fsm5 : 1; - uint8_t int1_fsm6 : 1; - uint8_t int1_fsm7 : 1; - uint8_t int1_fsm8 : 1; + uint8_t int1_fsm1 : 1; + uint8_t int1_fsm2 : 1; + uint8_t int1_fsm3 : 1; + uint8_t int1_fsm4 : 1; + uint8_t int1_fsm5 : 1; + uint8_t int1_fsm6 : 1; + uint8_t int1_fsm7 : 1; + uint8_t int1_fsm8 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t int1_fsm8 : 1; - uint8_t int1_fsm7 : 1; - uint8_t int1_fsm6 : 1; - uint8_t int1_fsm5 : 1; - uint8_t int1_fsm4 : 1; - uint8_t int1_fsm3 : 1; - uint8_t int1_fsm2 : 1; - uint8_t int1_fsm1 : 1; + uint8_t int1_fsm8 : 1; + uint8_t int1_fsm7 : 1; + uint8_t int1_fsm6 : 1; + uint8_t int1_fsm5 : 1; + uint8_t int1_fsm4 : 1; + uint8_t int1_fsm3 : 1; + uint8_t int1_fsm2 : 1; + uint8_t int1_fsm1 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_int1_t; -#define LSM6DSV16X_MLC_INT1 0x0DU +#define LSM6DSV16X_MLC_INT1 0x0DU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t int1_mlc1 : 1; - uint8_t int1_mlc2 : 1; - uint8_t int1_mlc3 : 1; - uint8_t int1_mlc4 : 1; - uint8_t not_used0 : 4; + uint8_t int1_mlc1 : 1; + uint8_t int1_mlc2 : 1; + uint8_t int1_mlc3 : 1; + uint8_t int1_mlc4 : 1; + uint8_t not_used0 : 4; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 4; - uint8_t int1_mlc4 : 1; - uint8_t int1_mlc3 : 1; - uint8_t int1_mlc2 : 1; - uint8_t int1_mlc1 : 1; + uint8_t not_used0 : 4; + uint8_t int1_mlc4 : 1; + uint8_t int1_mlc3 : 1; + uint8_t int1_mlc2 : 1; + uint8_t int1_mlc1 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_mlc_int1_t; -#define LSM6DSV16X_EMB_FUNC_INT2 0x0EU +#define LSM6DSV16X_EMB_FUNC_INT2 0x0EU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 3; - uint8_t int2_step_detector : 1; - uint8_t int2_tilt : 1; - uint8_t int2_sig_mot : 1; - uint8_t not_used1 : 1; - uint8_t int2_fsm_lc : 1; + uint8_t not_used0 : 3; + uint8_t int2_step_detector : 1; + uint8_t int2_tilt : 1; + uint8_t int2_sig_mot : 1; + uint8_t not_used1 : 1; + uint8_t int2_fsm_lc : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t int2_fsm_lc : 1; - uint8_t not_used1 : 1; - uint8_t int2_sig_mot : 1; - uint8_t int2_tilt : 1; - uint8_t int2_step_detector : 1; - uint8_t not_used0 : 3; + uint8_t int2_fsm_lc : 1; + uint8_t not_used1 : 1; + uint8_t int2_sig_mot : 1; + uint8_t int2_tilt : 1; + uint8_t int2_step_detector : 1; + uint8_t not_used0 : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_emb_func_int2_t; -#define LSM6DSV16X_FSM_INT2 0x0FU +#define LSM6DSV16X_FSM_INT2 0x0FU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t int2_fsm1 : 1; - uint8_t int2_fsm2 : 1; - uint8_t int2_fsm3 : 1; - uint8_t int2_fsm4 : 1; - uint8_t int2_fsm5 : 1; - uint8_t int2_fsm6 : 1; - uint8_t int2_fsm7 : 1; - uint8_t int2_fsm8 : 1; + uint8_t int2_fsm1 : 1; + uint8_t int2_fsm2 : 1; + uint8_t int2_fsm3 : 1; + uint8_t int2_fsm4 : 1; + uint8_t int2_fsm5 : 1; + uint8_t int2_fsm6 : 1; + uint8_t int2_fsm7 : 1; + uint8_t int2_fsm8 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t int2_fsm8 : 1; - uint8_t int2_fsm7 : 1; - uint8_t int2_fsm6 : 1; - uint8_t int2_fsm5 : 1; - uint8_t int2_fsm4 : 1; - uint8_t int2_fsm3 : 1; - uint8_t int2_fsm2 : 1; - uint8_t int2_fsm1 : 1; + uint8_t int2_fsm8 : 1; + uint8_t int2_fsm7 : 1; + uint8_t int2_fsm6 : 1; + uint8_t int2_fsm5 : 1; + uint8_t int2_fsm4 : 1; + uint8_t int2_fsm3 : 1; + uint8_t int2_fsm2 : 1; + uint8_t int2_fsm1 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_int2_t; -#define LSM6DSV16X_MLC_INT2 0x11U +#define LSM6DSV16X_MLC_INT2 0x11U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t int2_mlc1 : 1; - uint8_t int2_mlc2 : 1; - uint8_t int2_mlc3 : 1; - uint8_t int2_mlc4 : 1; - uint8_t not_used0 : 4; + uint8_t int2_mlc1 : 1; + uint8_t int2_mlc2 : 1; + uint8_t int2_mlc3 : 1; + uint8_t int2_mlc4 : 1; + uint8_t not_used0 : 4; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 4; - uint8_t int2_mlc4 : 1; - uint8_t int2_mlc3 : 1; - uint8_t int2_mlc2 : 1; - uint8_t int2_mlc1 : 1; + uint8_t not_used0 : 4; + uint8_t int2_mlc4 : 1; + uint8_t int2_mlc3 : 1; + uint8_t int2_mlc2 : 1; + uint8_t int2_mlc1 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_mlc_int2_t; -#define LSM6DSV16X_EMB_FUNC_STATUS 0x12U +#define LSM6DSV16X_EMB_FUNC_STATUS 0x12U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 3; - uint8_t is_step_det : 1; - uint8_t is_tilt : 1; - uint8_t is_sigmot : 1; - uint8_t not_used1 : 1; - uint8_t is_fsm_lc : 1; + uint8_t not_used0 : 3; + uint8_t is_step_det : 1; + uint8_t is_tilt : 1; + uint8_t is_sigmot : 1; + uint8_t not_used1 : 1; + uint8_t is_fsm_lc : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t is_fsm_lc : 1; - uint8_t not_used1 : 1; - uint8_t is_sigmot : 1; - uint8_t is_tilt : 1; - uint8_t is_step_det : 1; - uint8_t not_used0 : 3; + uint8_t is_fsm_lc : 1; + uint8_t not_used1 : 1; + uint8_t is_sigmot : 1; + uint8_t is_tilt : 1; + uint8_t is_step_det : 1; + uint8_t not_used0 : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_emb_func_status_t; -#define LSM6DSV16X_FSM_STATUS 0x13U +#define LSM6DSV16X_FSM_STATUS 0x13U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t is_fsm1 : 1; - uint8_t is_fsm2 : 1; - uint8_t is_fsm3 : 1; - uint8_t is_fsm4 : 1; - uint8_t is_fsm5 : 1; - uint8_t is_fsm6 : 1; - uint8_t is_fsm7 : 1; - uint8_t is_fsm8 : 1; + uint8_t is_fsm1 : 1; + uint8_t is_fsm2 : 1; + uint8_t is_fsm3 : 1; + uint8_t is_fsm4 : 1; + uint8_t is_fsm5 : 1; + uint8_t is_fsm6 : 1; + uint8_t is_fsm7 : 1; + uint8_t is_fsm8 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t is_fsm8 : 1; - uint8_t is_fsm7 : 1; - uint8_t is_fsm6 : 1; - uint8_t is_fsm5 : 1; - uint8_t is_fsm4 : 1; - uint8_t is_fsm3 : 1; - uint8_t is_fsm2 : 1; - uint8_t is_fsm1 : 1; + uint8_t is_fsm8 : 1; + uint8_t is_fsm7 : 1; + uint8_t is_fsm6 : 1; + uint8_t is_fsm5 : 1; + uint8_t is_fsm4 : 1; + uint8_t is_fsm3 : 1; + uint8_t is_fsm2 : 1; + uint8_t is_fsm1 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_status_t; -#define LSM6DSV16X_MLC_STATUS 0x15U +#define LSM6DSV16X_MLC_STATUS 0x15U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t is_mlc1 : 1; - uint8_t is_mlc2 : 1; - uint8_t is_mlc3 : 1; - uint8_t is_mlc4 : 1; - uint8_t not_used0 : 4; + uint8_t is_mlc1 : 1; + uint8_t is_mlc2 : 1; + uint8_t is_mlc3 : 1; + uint8_t is_mlc4 : 1; + uint8_t not_used0 : 4; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 4; - uint8_t is_mlc4 : 1; - uint8_t is_mlc3 : 1; - uint8_t is_mlc2 : 1; - uint8_t is_mlc1 : 1; + uint8_t not_used0 : 4; + uint8_t is_mlc4 : 1; + uint8_t is_mlc3 : 1; + uint8_t is_mlc2 : 1; + uint8_t is_mlc1 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_mlc_status_t; -#define LSM6DSV16X_PAGE_RW 0x17U +#define LSM6DSV16X_PAGE_RW 0x17U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 5; - uint8_t page_read : 1; - uint8_t page_write : 1; - uint8_t emb_func_lir : 1; + uint8_t not_used0 : 5; + uint8_t page_read : 1; + uint8_t page_write : 1; + uint8_t emb_func_lir : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t emb_func_lir : 1; - uint8_t page_write : 1; - uint8_t page_read : 1; - uint8_t not_used0 : 5; + uint8_t emb_func_lir : 1; + uint8_t page_write : 1; + uint8_t page_read : 1; + uint8_t not_used0 : 5; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_page_rw_t; -#define LSM6DSV16X_EMB_FUNC_FIFO_EN_A 0x44U +#define LSM6DSV16X_EMB_FUNC_FIFO_EN_A 0x44U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 6; - uint8_t step_counter_fifo_en : 1; - uint8_t mlc_fifo_en : 1; + uint8_t not_used0 : 1; + uint8_t sflp_game_fifo_en : 1; + uint8_t not_used1 : 2; + uint8_t sflp_gravity_fifo_en : 1; + uint8_t sflp_gbias_fifo_en : 1; + uint8_t step_counter_fifo_en : 1; + uint8_t mlc_fifo_en : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t mlc_fifo_en : 1; - uint8_t step_counter_fifo_en : 1; - uint8_t not_used0 : 6; + uint8_t mlc_fifo_en : 1; + uint8_t step_counter_fifo_en : 1; + uint8_t sflp_gbias_fifo_en : 1; + uint8_t sflp_gravity_fifo_en : 1; + uint8_t not_used1 : 2; + uint8_t sflp_game_fifo_en : 1; + uint8_t not_used0 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_emb_func_fifo_en_a_t; -#define LSM6DSV16X_EMB_FUNC_FIFO_EN_B 0x45U +#define LSM6DSV16X_EMB_FUNC_FIFO_EN_B 0x45U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 1; - uint8_t mlc_filter_feature_fifo_en : 1; - uint8_t not_used1 : 6; + uint8_t not_used0 : 1; + uint8_t mlc_filter_feature_fifo_en : 1; + uint8_t not_used1 : 6; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 6; - uint8_t mlc_filter_feature_fifo_en : 1; - uint8_t not_used0 : 1; + uint8_t not_used1 : 6; + uint8_t mlc_filter_feature_fifo_en : 1; + uint8_t not_used0 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_emb_func_fifo_en_b_t; -#define LSM6DSV16X_FSM_ENABLE 0x46U +#define LSM6DSV16X_FSM_ENABLE 0x46U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm1_en : 1; - uint8_t fsm2_en : 1; - uint8_t fsm3_en : 1; - uint8_t fsm4_en : 1; - uint8_t fsm5_en : 1; - uint8_t fsm6_en : 1; - uint8_t fsm7_en : 1; - uint8_t fsm8_en : 1; + uint8_t fsm1_en : 1; + uint8_t fsm2_en : 1; + uint8_t fsm3_en : 1; + uint8_t fsm4_en : 1; + uint8_t fsm5_en : 1; + uint8_t fsm6_en : 1; + uint8_t fsm7_en : 1; + uint8_t fsm8_en : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm8_en : 1; - uint8_t fsm7_en : 1; - uint8_t fsm6_en : 1; - uint8_t fsm5_en : 1; - uint8_t fsm4_en : 1; - uint8_t fsm3_en : 1; - uint8_t fsm2_en : 1; - uint8_t fsm1_en : 1; + uint8_t fsm8_en : 1; + uint8_t fsm7_en : 1; + uint8_t fsm6_en : 1; + uint8_t fsm5_en : 1; + uint8_t fsm4_en : 1; + uint8_t fsm3_en : 1; + uint8_t fsm2_en : 1; + uint8_t fsm1_en : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_enable_t; -#define LSM6DSV16X_FSM_LONG_COUNTER_L 0x48U +#define LSM6DSV16X_FSM_LONG_COUNTER_L 0x48U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_lc : 8; + uint8_t fsm_lc : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_lc : 8; + uint8_t fsm_lc : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_long_counter_l_t; -#define LSM6DSV16X_FSM_LONG_COUNTER_H 0x49U +#define LSM6DSV16X_FSM_LONG_COUNTER_H 0x49U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_lc : 8; + uint8_t fsm_lc : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_lc : 8; + uint8_t fsm_lc : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_long_counter_h_t; -#define LSM6DSV16X_INT_ACK_MASK 0x4BU +#define LSM6DSV16X_INT_ACK_MASK 0x4BU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t iack_mask : 8; + uint8_t iack_mask : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t iack_mask : 8; + uint8_t iack_mask : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_int_ack_mask_t; -#define LSM6DSV16X_FSM_OUTS1 0x4CU +#define LSM6DSV16X_FSM_OUTS1 0x4CU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm1_n_v : 1; - uint8_t fsm1_p_v : 1; - uint8_t fsm1_n_z : 1; - uint8_t fsm1_p_z : 1; - uint8_t fsm1_n_y : 1; - uint8_t fsm1_p_y : 1; - uint8_t fsm1_n_x : 1; - uint8_t fsm1_p_x : 1; + uint8_t fsm1_n_v : 1; + uint8_t fsm1_p_v : 1; + uint8_t fsm1_n_z : 1; + uint8_t fsm1_p_z : 1; + uint8_t fsm1_n_y : 1; + uint8_t fsm1_p_y : 1; + uint8_t fsm1_n_x : 1; + uint8_t fsm1_p_x : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm1_p_x : 1; - uint8_t fsm1_n_x : 1; - uint8_t fsm1_p_y : 1; - uint8_t fsm1_n_y : 1; - uint8_t fsm1_p_z : 1; - uint8_t fsm1_n_z : 1; - uint8_t fsm1_p_v : 1; - uint8_t fsm1_n_v : 1; + uint8_t fsm1_p_x : 1; + uint8_t fsm1_n_x : 1; + uint8_t fsm1_p_y : 1; + uint8_t fsm1_n_y : 1; + uint8_t fsm1_p_z : 1; + uint8_t fsm1_n_z : 1; + uint8_t fsm1_p_v : 1; + uint8_t fsm1_n_v : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_outs1_t; -#define LSM6DSV16X_FSM_OUTS2 0x4DU +#define LSM6DSV16X_FSM_OUTS2 0x4DU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm2_n_v : 1; - uint8_t fsm2_p_v : 1; - uint8_t fsm2_n_z : 1; - uint8_t fsm2_p_z : 1; - uint8_t fsm2_n_y : 1; - uint8_t fsm2_p_y : 1; - uint8_t fsm2_n_x : 1; - uint8_t fsm2_p_x : 1; + uint8_t fsm2_n_v : 1; + uint8_t fsm2_p_v : 1; + uint8_t fsm2_n_z : 1; + uint8_t fsm2_p_z : 1; + uint8_t fsm2_n_y : 1; + uint8_t fsm2_p_y : 1; + uint8_t fsm2_n_x : 1; + uint8_t fsm2_p_x : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm2_p_x : 1; - uint8_t fsm2_n_x : 1; - uint8_t fsm2_p_y : 1; - uint8_t fsm2_n_y : 1; - uint8_t fsm2_p_z : 1; - uint8_t fsm2_n_z : 1; - uint8_t fsm2_p_v : 1; - uint8_t fsm2_n_v : 1; + uint8_t fsm2_p_x : 1; + uint8_t fsm2_n_x : 1; + uint8_t fsm2_p_y : 1; + uint8_t fsm2_n_y : 1; + uint8_t fsm2_p_z : 1; + uint8_t fsm2_n_z : 1; + uint8_t fsm2_p_v : 1; + uint8_t fsm2_n_v : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_outs2_t; -#define LSM6DSV16X_FSM_OUTS3 0x4EU +#define LSM6DSV16X_FSM_OUTS3 0x4EU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm3_n_v : 1; - uint8_t fsm3_p_v : 1; - uint8_t fsm3_n_z : 1; - uint8_t fsm3_p_z : 1; - uint8_t fsm3_n_y : 1; - uint8_t fsm3_p_y : 1; - uint8_t fsm3_n_x : 1; - uint8_t fsm3_p_x : 1; + uint8_t fsm3_n_v : 1; + uint8_t fsm3_p_v : 1; + uint8_t fsm3_n_z : 1; + uint8_t fsm3_p_z : 1; + uint8_t fsm3_n_y : 1; + uint8_t fsm3_p_y : 1; + uint8_t fsm3_n_x : 1; + uint8_t fsm3_p_x : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm3_p_x : 1; - uint8_t fsm3_n_x : 1; - uint8_t fsm3_p_y : 1; - uint8_t fsm3_n_y : 1; - uint8_t fsm3_p_z : 1; - uint8_t fsm3_n_z : 1; - uint8_t fsm3_p_v : 1; - uint8_t fsm3_n_v : 1; + uint8_t fsm3_p_x : 1; + uint8_t fsm3_n_x : 1; + uint8_t fsm3_p_y : 1; + uint8_t fsm3_n_y : 1; + uint8_t fsm3_p_z : 1; + uint8_t fsm3_n_z : 1; + uint8_t fsm3_p_v : 1; + uint8_t fsm3_n_v : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_outs3_t; -#define LSM6DSV16X_FSM_OUTS4 0x4FU +#define LSM6DSV16X_FSM_OUTS4 0x4FU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm4_n_v : 1; - uint8_t fsm4_p_v : 1; - uint8_t fsm4_n_z : 1; - uint8_t fsm4_p_z : 1; - uint8_t fsm4_n_y : 1; - uint8_t fsm4_p_y : 1; - uint8_t fsm4_n_x : 1; - uint8_t fsm4_p_x : 1; + uint8_t fsm4_n_v : 1; + uint8_t fsm4_p_v : 1; + uint8_t fsm4_n_z : 1; + uint8_t fsm4_p_z : 1; + uint8_t fsm4_n_y : 1; + uint8_t fsm4_p_y : 1; + uint8_t fsm4_n_x : 1; + uint8_t fsm4_p_x : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm4_p_x : 1; - uint8_t fsm4_n_x : 1; - uint8_t fsm4_p_y : 1; - uint8_t fsm4_n_y : 1; - uint8_t fsm4_p_z : 1; - uint8_t fsm4_n_z : 1; - uint8_t fsm4_p_v : 1; - uint8_t fsm4_n_v : 1; + uint8_t fsm4_p_x : 1; + uint8_t fsm4_n_x : 1; + uint8_t fsm4_p_y : 1; + uint8_t fsm4_n_y : 1; + uint8_t fsm4_p_z : 1; + uint8_t fsm4_n_z : 1; + uint8_t fsm4_p_v : 1; + uint8_t fsm4_n_v : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_outs4_t; -#define LSM6DSV16X_FSM_OUTS5 0x50U +#define LSM6DSV16X_FSM_OUTS5 0x50U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm5_n_v : 1; - uint8_t fsm5_p_v : 1; - uint8_t fsm5_n_z : 1; - uint8_t fsm5_p_z : 1; - uint8_t fsm5_n_y : 1; - uint8_t fsm5_p_y : 1; - uint8_t fsm5_n_x : 1; - uint8_t fsm5_p_x : 1; + uint8_t fsm5_n_v : 1; + uint8_t fsm5_p_v : 1; + uint8_t fsm5_n_z : 1; + uint8_t fsm5_p_z : 1; + uint8_t fsm5_n_y : 1; + uint8_t fsm5_p_y : 1; + uint8_t fsm5_n_x : 1; + uint8_t fsm5_p_x : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm5_p_x : 1; - uint8_t fsm5_n_x : 1; - uint8_t fsm5_p_y : 1; - uint8_t fsm5_n_y : 1; - uint8_t fsm5_p_z : 1; - uint8_t fsm5_n_z : 1; - uint8_t fsm5_p_v : 1; - uint8_t fsm5_n_v : 1; + uint8_t fsm5_p_x : 1; + uint8_t fsm5_n_x : 1; + uint8_t fsm5_p_y : 1; + uint8_t fsm5_n_y : 1; + uint8_t fsm5_p_z : 1; + uint8_t fsm5_n_z : 1; + uint8_t fsm5_p_v : 1; + uint8_t fsm5_n_v : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_outs5_t; -#define LSM6DSV16X_FSM_OUTS6 0x51U +#define LSM6DSV16X_FSM_OUTS6 0x51U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm6_n_v : 1; - uint8_t fsm6_p_v : 1; - uint8_t fsm6_n_z : 1; - uint8_t fsm6_p_z : 1; - uint8_t fsm6_n_y : 1; - uint8_t fsm6_p_y : 1; - uint8_t fsm6_n_x : 1; - uint8_t fsm6_p_x : 1; + uint8_t fsm6_n_v : 1; + uint8_t fsm6_p_v : 1; + uint8_t fsm6_n_z : 1; + uint8_t fsm6_p_z : 1; + uint8_t fsm6_n_y : 1; + uint8_t fsm6_p_y : 1; + uint8_t fsm6_n_x : 1; + uint8_t fsm6_p_x : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm6_p_x : 1; - uint8_t fsm6_n_x : 1; - uint8_t fsm6_p_y : 1; - uint8_t fsm6_n_y : 1; - uint8_t fsm6_p_z : 1; - uint8_t fsm6_n_z : 1; - uint8_t fsm6_p_v : 1; - uint8_t fsm6_n_v : 1; + uint8_t fsm6_p_x : 1; + uint8_t fsm6_n_x : 1; + uint8_t fsm6_p_y : 1; + uint8_t fsm6_n_y : 1; + uint8_t fsm6_p_z : 1; + uint8_t fsm6_n_z : 1; + uint8_t fsm6_p_v : 1; + uint8_t fsm6_n_v : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_outs6_t; -#define LSM6DSV16X_FSM_OUTS7 0x52U +#define LSM6DSV16X_FSM_OUTS7 0x52U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm7_n_v : 1; - uint8_t fsm7_p_v : 1; - uint8_t fsm7_n_z : 1; - uint8_t fsm7_p_z : 1; - uint8_t fsm7_n_y : 1; - uint8_t fsm7_p_y : 1; - uint8_t fsm7_n_x : 1; - uint8_t fsm7_p_x : 1; + uint8_t fsm7_n_v : 1; + uint8_t fsm7_p_v : 1; + uint8_t fsm7_n_z : 1; + uint8_t fsm7_p_z : 1; + uint8_t fsm7_n_y : 1; + uint8_t fsm7_p_y : 1; + uint8_t fsm7_n_x : 1; + uint8_t fsm7_p_x : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm7_p_x : 1; - uint8_t fsm7_n_x : 1; - uint8_t fsm7_p_y : 1; - uint8_t fsm7_n_y : 1; - uint8_t fsm7_p_z : 1; - uint8_t fsm7_n_z : 1; - uint8_t fsm7_p_v : 1; - uint8_t fsm7_n_v : 1; + uint8_t fsm7_p_x : 1; + uint8_t fsm7_n_x : 1; + uint8_t fsm7_p_y : 1; + uint8_t fsm7_n_y : 1; + uint8_t fsm7_p_z : 1; + uint8_t fsm7_n_z : 1; + uint8_t fsm7_p_v : 1; + uint8_t fsm7_n_v : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_outs7_t; -#define LSM6DSV16X_FSM_OUTS8 0x53U +#define LSM6DSV16X_FSM_OUTS8 0x53U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm8_n_v : 1; - uint8_t fsm8_p_v : 1; - uint8_t fsm8_n_z : 1; - uint8_t fsm8_p_z : 1; - uint8_t fsm8_n_y : 1; - uint8_t fsm8_p_y : 1; - uint8_t fsm8_n_x : 1; - uint8_t fsm8_p_x : 1; + uint8_t fsm8_n_v : 1; + uint8_t fsm8_p_v : 1; + uint8_t fsm8_n_z : 1; + uint8_t fsm8_p_z : 1; + uint8_t fsm8_n_y : 1; + uint8_t fsm8_p_y : 1; + uint8_t fsm8_n_x : 1; + uint8_t fsm8_p_x : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm8_p_x : 1; - uint8_t fsm8_n_x : 1; - uint8_t fsm8_p_y : 1; - uint8_t fsm8_n_y : 1; - uint8_t fsm8_p_z : 1; - uint8_t fsm8_n_z : 1; - uint8_t fsm8_p_v : 1; - uint8_t fsm8_n_v : 1; + uint8_t fsm8_p_x : 1; + uint8_t fsm8_n_x : 1; + uint8_t fsm8_p_y : 1; + uint8_t fsm8_n_y : 1; + uint8_t fsm8_p_z : 1; + uint8_t fsm8_n_z : 1; + uint8_t fsm8_p_v : 1; + uint8_t fsm8_n_v : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_outs8_t; -#define LSM6DSV16X_FSM_ODR 0x5FU +#define LSM6DSV16X_SFLP_ODR 0x5EU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 3; - uint8_t fsm_odr : 3; - uint8_t not_used1 : 2; + uint8_t not_used0 : 3; + uint8_t sflp_game_odr : 3; + uint8_t not_used1 : 2; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 2; - uint8_t fsm_odr : 3; - uint8_t not_used0 : 3; + uint8_t not_used1 : 2; + uint8_t sflp_game_odr : 3; + uint8_t not_used0 : 3; +#endif /* DRV_BYTE_ORDER */ +} lsm6dsv16x_sflp_odr_t; + +#define LSM6DSV16X_FSM_ODR 0x5FU +typedef struct { +#if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN + uint8_t not_used0 : 3; + uint8_t fsm_odr : 3; + uint8_t not_used1 : 2; +#elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN + uint8_t not_used1 : 2; + uint8_t fsm_odr : 3; + uint8_t not_used0 : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_odr_t; -#define LSM6DSV16X_MLC_ODR 0x60U +#define LSM6DSV16X_MLC_ODR 0x60U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 4; - uint8_t mlc_odr : 3; - uint8_t not_used1 : 1; + uint8_t not_used0 : 4; + uint8_t mlc_odr : 3; + uint8_t not_used1 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 1; - uint8_t mlc_odr : 3; - uint8_t not_used0 : 4; + uint8_t not_used1 : 1; + uint8_t mlc_odr : 3; + uint8_t not_used0 : 4; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_mlc_odr_t; -#define LSM6DSV16X_STEP_COUNTER_L 0x62U +#define LSM6DSV16X_STEP_COUNTER_L 0x62U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t step : 8; + uint8_t step : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t step : 8; + uint8_t step : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_step_counter_l_t; -#define LSM6DSV16X_STEP_COUNTER_H 0x63U +#define LSM6DSV16X_STEP_COUNTER_H 0x63U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t step : 8; + uint8_t step : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t step : 8; + uint8_t step : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_step_counter_h_t; -#define LSM6DSV16X_EMB_FUNC_SRC 0x64U +#define LSM6DSV16X_EMB_FUNC_SRC 0x64U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 2; + uint8_t not_used0 : 2; uint8_t stepcounter_bit_set : 1; - uint8_t step_overflow : 1; + uint8_t step_overflow : 1; uint8_t step_count_delta_ia : 1; - uint8_t step_detected : 1; - uint8_t not_used1 : 1; - uint8_t pedo_rst_step : 1; + uint8_t step_detected : 1; + uint8_t not_used1 : 1; + uint8_t pedo_rst_step : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t pedo_rst_step : 1; - uint8_t not_used1 : 1; - uint8_t step_detected : 1; + uint8_t pedo_rst_step : 1; + uint8_t not_used1 : 1; + uint8_t step_detected : 1; uint8_t step_count_delta_ia : 1; - uint8_t step_overflow : 1; + uint8_t step_overflow : 1; uint8_t stepcounter_bit_set : 1; - uint8_t not_used0 : 2; + uint8_t not_used0 : 2; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_emb_func_src_t; -#define LSM6DSV16X_EMB_FUNC_INIT_A 0x66U +#define LSM6DSV16X_EMB_FUNC_INIT_A 0x66U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 3; - uint8_t step_det_init : 1; - uint8_t tilt_init : 1; - uint8_t sig_mot_init : 1; - uint8_t not_used1 : 1; + uint8_t not_used0 : 1; + uint8_t sflp_game_init : 1; + uint8_t not_used2 : 1; + uint8_t step_det_init : 1; + uint8_t tilt_init : 1; + uint8_t sig_mot_init : 1; + uint8_t not_used1 : 1; uint8_t mlc_before_fsm_init : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN uint8_t mlc_before_fsm_init : 1; - uint8_t not_used1 : 1; - uint8_t sig_mot_init : 1; - uint8_t tilt_init : 1; - uint8_t step_det_init : 1; - uint8_t not_used0 : 3; + uint8_t not_used1 : 1; + uint8_t sig_mot_init : 1; + uint8_t tilt_init : 1; + uint8_t step_det_init : 1; + uint8_t not_used2 : 1; + uint8_t sflp_game_init : 1; + uint8_t not_used0 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_emb_func_init_a_t; -#define LSM6DSV16X_EMB_FUNC_INIT_B 0x67U +#define LSM6DSV16X_EMB_FUNC_INIT_B 0x67U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_init : 1; - uint8_t not_used0 : 2; - uint8_t fifo_compr_init : 1; - uint8_t mlc_init : 1; - uint8_t not_used1 : 3; + uint8_t fsm_init : 1; + uint8_t not_used0 : 2; + uint8_t fifo_compr_init : 1; + uint8_t mlc_init : 1; + uint8_t not_used1 : 3; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 3; - uint8_t mlc_init : 1; - uint8_t fifo_compr_init : 1; - uint8_t not_used0 : 2; - uint8_t fsm_init : 1; + uint8_t not_used1 : 3; + uint8_t mlc_init : 1; + uint8_t fifo_compr_init : 1; + uint8_t not_used0 : 2; + uint8_t fsm_init : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_emb_func_init_b_t; -#define LSM6DSV16X_MLC1_SRC 0x70U +#define LSM6DSV16X_MLC1_SRC 0x70U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t mlc1_src : 8; + uint8_t mlc1_src : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t mlc1_src : 8; + uint8_t mlc1_src : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_mlc1_src_t; -#define LSM6DSV16X_MLC2_SRC 0x71U +#define LSM6DSV16X_MLC2_SRC 0x71U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t mlc2_src : 8; + uint8_t mlc2_src : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t mlc2_src : 8; + uint8_t mlc2_src : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_mlc2_src_t; -#define LSM6DSV16X_MLC3_SRC 0x72U +#define LSM6DSV16X_MLC3_SRC 0x72U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t mlc3_src : 8; + uint8_t mlc3_src : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t mlc3_src : 8; + uint8_t mlc3_src : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_mlc3_src_t; -#define LSM6DSV16X_MLC4_SRC 0x73U +#define LSM6DSV16X_MLC4_SRC 0x73U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t mlc4_src : 8; + uint8_t mlc4_src : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t mlc4_src : 8; + uint8_t mlc4_src : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_mlc4_src_t; @@ -2540,211 +2547,265 @@ typedef struct { * @{ * */ -#define LSM6DSV16X_EMB_ADV_PG_0 0x000 +#define LSM6DSV16X_EMB_ADV_PG_0 0x000U + +#define LSM6DSV16X_SFLP_GAME_GBIASX_L 0x6EU +typedef struct { +#if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN + uint8_t gbiasx : 8; +#elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN + uint8_t gbiasx : 8; +#endif /* DRV_BYTE_ORDER */ +} lsm6dsv16x_sflp_game_gbiasx_l_t; -#define LSM6DSV16X_FSM_EXT_SENSITIVITY_L 0xBAU +#define LSM6DSV16X_SFLP_GAME_GBIASX_H 0x6FU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_s : 8; + uint8_t gbiasx : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_s : 8; + uint8_t gbiasx : 8; +#endif /* DRV_BYTE_ORDER */ +} lsm6dsv16x_sflp_game_gbiasx_h_t; + +#define LSM6DSV16X_SFLP_GAME_GBIASY_L 0x70U +typedef struct { +#if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN + uint8_t gbiasy : 8; +#elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN + uint8_t gbiasy : 8; +#endif /* DRV_BYTE_ORDER */ +} lsm6dsv16x_sflp_game_gbiasy_l_t; + +#define LSM6DSV16X_SFLP_GAME_GBIASY_H 0x71U +typedef struct { +#if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN + uint8_t gbiasy : 8; +#elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN + uint8_t gbiasy : 8; +#endif /* DRV_BYTE_ORDER */ +} lsm6dsv16x_sflp_game_gbiasy_h_t; + +#define LSM6DSV16X_SFLP_GAME_GBIASZ_L 0x72U +typedef struct { +#if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN + uint8_t gbiasz : 8; +#elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN + uint8_t gbiasz : 8; +#endif /* DRV_BYTE_ORDER */ +} lsm6dsv16x_sflp_game_gbiasz_l_t; + +#define LSM6DSV16X_SFLP_GAME_GBIASZ_H 0x73U +typedef struct { +#if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN + uint8_t gbiasz : 8; +#elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN + uint8_t gbiasz : 8; +#endif /* DRV_BYTE_ORDER */ +} lsm6dsv16x_sflp_game_gbiasz_h_t; + +#define LSM6DSV16X_FSM_EXT_SENSITIVITY_L 0xBAU +typedef struct { +#if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN + uint8_t fsm_ext_s : 8; +#elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN + uint8_t fsm_ext_s : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_sensitivity_l_t; -#define LSM6DSV16X_FSM_EXT_SENSITIVITY_H 0xBBU +#define LSM6DSV16X_FSM_EXT_SENSITIVITY_H 0xBBU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_s : 8; + uint8_t fsm_ext_s : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_s : 8; + uint8_t fsm_ext_s : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_sensitivity_h_t; -#define LSM6DSV16X_FSM_EXT_OFFX_L 0xC0U +#define LSM6DSV16X_FSM_EXT_OFFX_L 0xC0U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_offx : 8; + uint8_t fsm_ext_offx : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_offx : 8; + uint8_t fsm_ext_offx : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_offx_l_t; -#define LSM6DSV16X_FSM_EXT_OFFX_H 0xC1U +#define LSM6DSV16X_FSM_EXT_OFFX_H 0xC1U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_offx : 8; + uint8_t fsm_ext_offx : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_offx : 8; + uint8_t fsm_ext_offx : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_offx_h_t; -#define LSM6DSV16X_FSM_EXT_OFFY_L 0xC2U +#define LSM6DSV16X_FSM_EXT_OFFY_L 0xC2U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_offy : 8; + uint8_t fsm_ext_offy : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_offy : 8; + uint8_t fsm_ext_offy : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_offy_l_t; -#define LSM6DSV16X_FSM_EXT_OFFY_H 0xC3U +#define LSM6DSV16X_FSM_EXT_OFFY_H 0xC3U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_offy : 8; + uint8_t fsm_ext_offy : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_offy : 8; + uint8_t fsm_ext_offy : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_offy_h_t; -#define LSM6DSV16X_FSM_EXT_OFFZ_L 0xC4U +#define LSM6DSV16X_FSM_EXT_OFFZ_L 0xC4U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_offz : 8; + uint8_t fsm_ext_offz : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_offz : 8; + uint8_t fsm_ext_offz : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_offz_l_t; -#define LSM6DSV16X_FSM_EXT_OFFZ_H 0xC5U +#define LSM6DSV16X_FSM_EXT_OFFZ_H 0xC5U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_offz : 8; + uint8_t fsm_ext_offz : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_offz : 8; + uint8_t fsm_ext_offz : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_offz_h_t; -#define LSM6DSV16X_FSM_EXT_MATRIX_XX_L 0xC6U +#define LSM6DSV16X_FSM_EXT_MATRIX_XX_L 0xC6U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_mat_xx : 8; + uint8_t fsm_ext_mat_xx : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_mat_xx : 8; + uint8_t fsm_ext_mat_xx : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_matrix_xx_l_t; -#define LSM6DSV16X_FSM_EXT_MATRIX_XX_H 0xC7U +#define LSM6DSV16X_FSM_EXT_MATRIX_XX_H 0xC7U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_mat_xx : 8; + uint8_t fsm_ext_mat_xx : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_mat_xx : 8; + uint8_t fsm_ext_mat_xx : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_matrix_xx_h_t; -#define LSM6DSV16X_FSM_EXT_MATRIX_XY_L 0xC8U +#define LSM6DSV16X_FSM_EXT_MATRIX_XY_L 0xC8U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_mat_xy : 8; + uint8_t fsm_ext_mat_xy : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_mat_xy : 8; + uint8_t fsm_ext_mat_xy : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_matrix_xy_l_t; -#define LSM6DSV16X_FSM_EXT_MATRIX_XY_H 0xC9U +#define LSM6DSV16X_FSM_EXT_MATRIX_XY_H 0xC9U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_mat_xy : 8; + uint8_t fsm_ext_mat_xy : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_mat_xy : 8; + uint8_t fsm_ext_mat_xy : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_matrix_xy_h_t; -#define LSM6DSV16X_FSM_EXT_MATRIX_XZ_L 0xCAU +#define LSM6DSV16X_FSM_EXT_MATRIX_XZ_L 0xCAU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_mat_xz : 8; + uint8_t fsm_ext_mat_xz : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_mat_xz : 8; + uint8_t fsm_ext_mat_xz : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_matrix_xz_l_t; -#define LSM6DSV16X_FSM_EXT_MATRIX_XZ_H 0xCBU +#define LSM6DSV16X_FSM_EXT_MATRIX_XZ_H 0xCBU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_mat_xz : 8; + uint8_t fsm_ext_mat_xz : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_mat_xz : 8; + uint8_t fsm_ext_mat_xz : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_matrix_xz_h_t; -#define LSM6DSV16X_FSM_EXT_MATRIX_YY_L 0xCCU +#define LSM6DSV16X_FSM_EXT_MATRIX_YY_L 0xCCU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_mat_yy : 8; + uint8_t fsm_ext_mat_yy : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_mat_yy : 8; + uint8_t fsm_ext_mat_yy : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_matrix_yy_l_t; -#define LSM6DSV16X_FSM_EXT_MATRIX_YY_H 0xCDU +#define LSM6DSV16X_FSM_EXT_MATRIX_YY_H 0xCDU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_mat_yy : 8; + uint8_t fsm_ext_mat_yy : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_mat_yy : 8; + uint8_t fsm_ext_mat_yy : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_matrix_yy_h_t; -#define LSM6DSV16X_FSM_EXT_MATRIX_YZ_L 0xCEU +#define LSM6DSV16X_FSM_EXT_MATRIX_YZ_L 0xCEU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_mat_yz : 8; + uint8_t fsm_ext_mat_yz : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_mat_yz : 8; + uint8_t fsm_ext_mat_yz : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_matrix_yz_l_t; -#define LSM6DSV16X_FSM_EXT_MATRIX_YZ_H 0xCFU +#define LSM6DSV16X_FSM_EXT_MATRIX_YZ_H 0xCFU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_mat_yz : 8; + uint8_t fsm_ext_mat_yz : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_mat_yz : 8; + uint8_t fsm_ext_mat_yz : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_matrix_yz_h_t; -#define LSM6DSV16X_FSM_EXT_MATRIX_ZZ_L 0xD0U +#define LSM6DSV16X_FSM_EXT_MATRIX_ZZ_L 0xD0U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_mat_zz : 8; + uint8_t fsm_ext_mat_zz : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_mat_zz : 8; + uint8_t fsm_ext_mat_zz : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_matrix_zz_l_t; -#define LSM6DSV16X_FSM_EXT_MATRIX_ZZ_H 0xD1U +#define LSM6DSV16X_FSM_EXT_MATRIX_ZZ_H 0xD1U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_ext_mat_zz : 8; + uint8_t fsm_ext_mat_zz : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_ext_mat_zz : 8; + uint8_t fsm_ext_mat_zz : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_ext_matrix_zz_h_t; -#define LSM6DSV16X_EXT_CFG_A 0xD4U +#define LSM6DSV16X_EXT_CFG_A 0xD4U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ext_z_axis : 3; - uint8_t not_used0 : 1; - uint8_t ext_y_axis : 3; - uint8_t not_used1 : 1; + uint8_t ext_z_axis : 3; + uint8_t not_used0 : 1; + uint8_t ext_y_axis : 3; + uint8_t not_used1 : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 1; - uint8_t ext_y_axis : 3; - uint8_t not_used0 : 1; - uint8_t ext_z_axis : 3; + uint8_t not_used1 : 1; + uint8_t ext_y_axis : 3; + uint8_t not_used0 : 1; + uint8_t ext_z_axis : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ext_cfg_a_t; -#define LSM6DSV16X_EXT_CFG_B 0xD5U +#define LSM6DSV16X_EXT_CFG_B 0xD5U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ext_x_axis : 3; - uint8_t not_used0 : 5; + uint8_t ext_x_axis : 3; + uint8_t not_used0 : 5; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 5; - uint8_t ext_x_axis : 3; + uint8_t not_used0 : 5; + uint8_t ext_x_axis : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ext_cfg_b_t; @@ -2757,110 +2818,110 @@ typedef struct { * @{ * */ -#define LSM6DSV16X_EMB_ADV_PG_1 0x100 +#define LSM6DSV16X_EMB_ADV_PG_1 0x100U -#define LSM6DSV16X_FSM_LC_TIMEOUT_L 0x7AU +#define LSM6DSV16X_FSM_LC_TIMEOUT_L 0x7AU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_lc_timeout : 8; + uint8_t fsm_lc_timeout : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_lc_timeout : 8; + uint8_t fsm_lc_timeout : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_lc_timeout_l_t; -#define LSM6DSV16X_FSM_LC_TIMEOUT_H 0x7BU +#define LSM6DSV16X_FSM_LC_TIMEOUT_H 0x7BU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_lc_timeout : 8; + uint8_t fsm_lc_timeout : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_lc_timeout : 8; + uint8_t fsm_lc_timeout : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_lc_timeout_h_t; -#define LSM6DSV16X_FSM_PROGRAMS 0x7CU +#define LSM6DSV16X_FSM_PROGRAMS 0x7CU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_n_prog : 8; + uint8_t fsm_n_prog : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_n_prog : 8; + uint8_t fsm_n_prog : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_programs_t; -#define LSM6DSV16X_FSM_START_ADD_L 0x7EU +#define LSM6DSV16X_FSM_START_ADD_L 0x7EU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_start : 8; + uint8_t fsm_start : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_start : 8; + uint8_t fsm_start : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_start_add_l_t; -#define LSM6DSV16X_FSM_START_ADD_H 0x7FU +#define LSM6DSV16X_FSM_START_ADD_H 0x7FU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t fsm_start : 8; + uint8_t fsm_start : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t fsm_start : 8; + uint8_t fsm_start : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_fsm_start_add_h_t; -#define LSM6DSV16X_PEDO_CMD_REG 0x83U +#define LSM6DSV16X_PEDO_CMD_REG 0x83U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 2; - uint8_t fp_rejection_en : 1; - uint8_t carry_count_en : 1; - uint8_t not_used1 : 4; + uint8_t not_used0 : 2; + uint8_t fp_rejection_en : 1; + uint8_t carry_count_en : 1; + uint8_t not_used1 : 4; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 4; - uint8_t carry_count_en : 1; - uint8_t fp_rejection_en : 1; - uint8_t not_used0 : 2; + uint8_t not_used1 : 4; + uint8_t carry_count_en : 1; + uint8_t fp_rejection_en : 1; + uint8_t not_used0 : 2; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_pedo_cmd_reg_t; -#define LSM6DSV16X_PEDO_DEB_STEPS_CONF 0x84U +#define LSM6DSV16X_PEDO_DEB_STEPS_CONF 0x84U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t deb_step : 8; + uint8_t deb_step : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t deb_step : 8; + uint8_t deb_step : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_pedo_deb_steps_conf_t; -#define LSM6DSV16X_PEDO_SC_DELTAT_L 0xD0U +#define LSM6DSV16X_PEDO_SC_DELTAT_L 0xD0U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t pd_sc : 8; + uint8_t pd_sc : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t pd_sc : 8; + uint8_t pd_sc : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_pedo_sc_deltat_l_t; -#define LSM6DSV16X_PEDO_SC_DELTAT_H 0xD1U +#define LSM6DSV16X_PEDO_SC_DELTAT_H 0xD1U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t pd_sc : 8; + uint8_t pd_sc : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t pd_sc : 8; + uint8_t pd_sc : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_pedo_sc_deltat_h_t; #define LSM6DSV16X_MLC_EXT_SENSITIVITY_L 0xE8U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t mlc_ext_s : 8; + uint8_t mlc_ext_s : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t mlc_ext_s : 8; + uint8_t mlc_ext_s : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_mlc_ext_sensitivity_l_t; #define LSM6DSV16X_MLC_EXT_SENSITIVITY_H 0xE9U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t mlc_ext_s : 8; + uint8_t mlc_ext_s : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t mlc_ext_s : 8; + uint8_t mlc_ext_s : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_mlc_ext_sensitivity_h_t; @@ -2868,63 +2929,63 @@ typedef struct { * @{ * */ -#define LSM6DSV16X_EMB_ADV_PG_2 0x200 +#define LSM6DSV16X_EMB_ADV_PG_2 0x200U -#define LSM6DSV16X_EXT_FORMAT 0x00 +#define LSM6DSV16X_EXT_FORMAT 0x00 typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t not_used0 : 2; - uint8_t ext_format_sel : 1; - uint8_t not_used1 : 5; + uint8_t not_used0 : 2; + uint8_t ext_format_sel : 1; + uint8_t not_used1 : 5; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used1 : 5; - uint8_t ext_format_sel : 1; - uint8_t not_used0 : 2; + uint8_t not_used1 : 5; + uint8_t ext_format_sel : 1; + uint8_t not_used0 : 2; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ext_format_t; -#define LSM6DSV16X_EXT_3BYTE_SENSITIVITY_L 0x02U +#define LSM6DSV16X_EXT_3BYTE_SENSITIVITY_L 0x02U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ext_3byte_s : 8; + uint8_t ext_3byte_s : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ext_3byte_s : 8; + uint8_t ext_3byte_s : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ext_3byte_sensitivity_l_t; -#define LSM6DSV16X_EXT_3BYTE_SENSITIVITY_H 0x03U +#define LSM6DSV16X_EXT_3BYTE_SENSITIVITY_H 0x03U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ext_3byte_s : 8; + uint8_t ext_3byte_s : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ext_3byte_s : 8; + uint8_t ext_3byte_s : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ext_3byte_sensitivity_h_t; -#define LSM6DSV16X_EXT_3BYTE_OFFSET_XL 0x06U +#define LSM6DSV16X_EXT_3BYTE_OFFSET_XL 0x06U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ext_3byte_off : 8; + uint8_t ext_3byte_off : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ext_3byte_off : 8; + uint8_t ext_3byte_off : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ext_3byte_offset_xl_t; -#define LSM6DSV16X_EXT_3BYTE_OFFSET_L 0x07U +#define LSM6DSV16X_EXT_3BYTE_OFFSET_L 0x07U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ext_3byte_off : 8; + uint8_t ext_3byte_off : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ext_3byte_off : 8; + uint8_t ext_3byte_off : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ext_3byte_offset_l_t; -#define LSM6DSV16X_EXT_3BYTE_OFFSET_H 0x08U +#define LSM6DSV16X_EXT_3BYTE_OFFSET_H 0x08U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t ext_3byte_off : 8; + uint8_t ext_3byte_off : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t ext_3byte_off : 8; + uint8_t ext_3byte_off : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_ext_3byte_offset_h_t; @@ -2938,350 +2999,350 @@ typedef struct { * */ -#define LSM6DSV16X_SENSOR_HUB_1 0x2U +#define LSM6DSV16X_SENSOR_HUB_1 0x2U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub1 : 8; + uint8_t sensorhub1 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub1 : 8; + uint8_t sensorhub1 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_1_t; -#define LSM6DSV16X_SENSOR_HUB_2 0x3U +#define LSM6DSV16X_SENSOR_HUB_2 0x3U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub2 : 8; + uint8_t sensorhub2 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub2 : 8; + uint8_t sensorhub2 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_2_t; -#define LSM6DSV16X_SENSOR_HUB_3 0x4U +#define LSM6DSV16X_SENSOR_HUB_3 0x4U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub3 : 8; + uint8_t sensorhub3 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub3 : 8; + uint8_t sensorhub3 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_3_t; -#define LSM6DSV16X_SENSOR_HUB_4 0x5U +#define LSM6DSV16X_SENSOR_HUB_4 0x5U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub4 : 8; + uint8_t sensorhub4 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub4 : 8; + uint8_t sensorhub4 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_4_t; -#define LSM6DSV16X_SENSOR_HUB_5 0x6U +#define LSM6DSV16X_SENSOR_HUB_5 0x6U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub5 : 8; + uint8_t sensorhub5 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub5 : 8; + uint8_t sensorhub5 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_5_t; -#define LSM6DSV16X_SENSOR_HUB_6 0x7U +#define LSM6DSV16X_SENSOR_HUB_6 0x7U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub6 : 8; + uint8_t sensorhub6 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub6 : 8; + uint8_t sensorhub6 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_6_t; -#define LSM6DSV16X_SENSOR_HUB_7 0x8U +#define LSM6DSV16X_SENSOR_HUB_7 0x8U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub7 : 8; + uint8_t sensorhub7 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub7 : 8; + uint8_t sensorhub7 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_7_t; -#define LSM6DSV16X_SENSOR_HUB_8 0x9U +#define LSM6DSV16X_SENSOR_HUB_8 0x9U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub8 : 8; + uint8_t sensorhub8 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub8 : 8; + uint8_t sensorhub8 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_8_t; -#define LSM6DSV16X_SENSOR_HUB_9 0x0AU +#define LSM6DSV16X_SENSOR_HUB_9 0x0AU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub9 : 8; + uint8_t sensorhub9 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub9 : 8; + uint8_t sensorhub9 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_9_t; -#define LSM6DSV16X_SENSOR_HUB_10 0x0BU +#define LSM6DSV16X_SENSOR_HUB_10 0x0BU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub10 : 8; + uint8_t sensorhub10 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub10 : 8; + uint8_t sensorhub10 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_10_t; -#define LSM6DSV16X_SENSOR_HUB_11 0x0CU +#define LSM6DSV16X_SENSOR_HUB_11 0x0CU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub11 : 8; + uint8_t sensorhub11 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub11 : 8; + uint8_t sensorhub11 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_11_t; -#define LSM6DSV16X_SENSOR_HUB_12 0x0DU +#define LSM6DSV16X_SENSOR_HUB_12 0x0DU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub12 : 8; + uint8_t sensorhub12 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub12 : 8; + uint8_t sensorhub12 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_12_t; -#define LSM6DSV16X_SENSOR_HUB_13 0x0EU +#define LSM6DSV16X_SENSOR_HUB_13 0x0EU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub13 : 8; + uint8_t sensorhub13 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub13 : 8; + uint8_t sensorhub13 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_13_t; -#define LSM6DSV16X_SENSOR_HUB_14 0x0FU +#define LSM6DSV16X_SENSOR_HUB_14 0x0FU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub14 : 8; + uint8_t sensorhub14 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub14 : 8; + uint8_t sensorhub14 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_14_t; -#define LSM6DSV16X_SENSOR_HUB_15 0x10U +#define LSM6DSV16X_SENSOR_HUB_15 0x10U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub15 : 8; + uint8_t sensorhub15 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub15 : 8; + uint8_t sensorhub15 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_15_t; -#define LSM6DSV16X_SENSOR_HUB_16 0x11U +#define LSM6DSV16X_SENSOR_HUB_16 0x11U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub16 : 8; + uint8_t sensorhub16 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub16 : 8; + uint8_t sensorhub16 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_16_t; -#define LSM6DSV16X_SENSOR_HUB_17 0x12U +#define LSM6DSV16X_SENSOR_HUB_17 0x12U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub17 : 8; + uint8_t sensorhub17 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub17 : 8; + uint8_t sensorhub17 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_17_t; -#define LSM6DSV16X_SENSOR_HUB_18 0x13U +#define LSM6DSV16X_SENSOR_HUB_18 0x13U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sensorhub18 : 8; + uint8_t sensorhub18 : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t sensorhub18 : 8; + uint8_t sensorhub18 : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_sensor_hub_18_t; -#define LSM6DSV16X_MASTER_CONFIG 0x14U +#define LSM6DSV16X_MASTER_CONFIG 0x14U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t aux_sens_on : 2; - uint8_t master_on : 1; - uint8_t not_used0 : 1; - uint8_t pass_through_mode : 1; - uint8_t start_config : 1; - uint8_t write_once : 1; - uint8_t rst_master_regs : 1; + uint8_t aux_sens_on : 2; + uint8_t master_on : 1; + uint8_t not_used0 : 1; + uint8_t pass_through_mode : 1; + uint8_t start_config : 1; + uint8_t write_once : 1; + uint8_t rst_master_regs : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t rst_master_regs : 1; - uint8_t write_once : 1; - uint8_t start_config : 1; - uint8_t pass_through_mode : 1; - uint8_t not_used0 : 1; - uint8_t master_on : 1; - uint8_t aux_sens_on : 2; + uint8_t rst_master_regs : 1; + uint8_t write_once : 1; + uint8_t start_config : 1; + uint8_t pass_through_mode : 1; + uint8_t not_used0 : 1; + uint8_t master_on : 1; + uint8_t aux_sens_on : 2; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_master_config_t; -#define LSM6DSV16X_SLV0_ADD 0x15U +#define LSM6DSV16X_SLV0_ADD 0x15U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t rw_0 : 1; - uint8_t slave0_add : 7; + uint8_t rw_0 : 1; + uint8_t slave0_add : 7; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t slave0_add : 7; - uint8_t rw_0 : 1; + uint8_t slave0_add : 7; + uint8_t rw_0 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_slv0_add_t; -#define LSM6DSV16X_SLV0_SUBADD 0x16U +#define LSM6DSV16X_SLV0_SUBADD 0x16U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t slave0_reg : 8; + uint8_t slave0_reg : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t slave0_reg : 8; + uint8_t slave0_reg : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_slv0_subadd_t; -#define LSM6DSV16X_SLV0_CONFIG 0x17U +#define LSM6DSV16X_SLV0_CONFIG 0x17U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t slave0_numop : 3; + uint8_t slave0_numop : 3; uint8_t batch_ext_sens_0_en : 1; - uint8_t not_used0 : 1; - uint8_t shub_odr : 3; + uint8_t not_used0 : 1; + uint8_t shub_odr : 3; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t shub_odr : 3; - uint8_t not_used0 : 1; + uint8_t shub_odr : 3; + uint8_t not_used0 : 1; uint8_t batch_ext_sens_0_en : 1; - uint8_t slave0_numop : 3; + uint8_t slave0_numop : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_slv0_config_t; -#define LSM6DSV16X_SLV1_ADD 0x18U +#define LSM6DSV16X_SLV1_ADD 0x18U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t r_1 : 1; - uint8_t slave1_add : 7; + uint8_t r_1 : 1; + uint8_t slave1_add : 7; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t slave1_add : 7; - uint8_t r_1 : 1; + uint8_t slave1_add : 7; + uint8_t r_1 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_slv1_add_t; -#define LSM6DSV16X_SLV1_SUBADD 0x19U +#define LSM6DSV16X_SLV1_SUBADD 0x19U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t slave1_reg : 8; + uint8_t slave1_reg : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t slave1_reg : 8; + uint8_t slave1_reg : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_slv1_subadd_t; -#define LSM6DSV16X_SLV1_CONFIG 0x1AU +#define LSM6DSV16X_SLV1_CONFIG 0x1AU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t slave1_numop : 3; + uint8_t slave1_numop : 3; uint8_t batch_ext_sens_1_en : 1; - uint8_t not_used0 : 4; + uint8_t not_used0 : 4; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 4; + uint8_t not_used0 : 4; uint8_t batch_ext_sens_1_en : 1; - uint8_t slave1_numop : 3; + uint8_t slave1_numop : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_slv1_config_t; -#define LSM6DSV16X_SLV2_ADD 0x1BU +#define LSM6DSV16X_SLV2_ADD 0x1BU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t r_2 : 1; - uint8_t slave2_add : 7; + uint8_t r_2 : 1; + uint8_t slave2_add : 7; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t slave2_add : 7; - uint8_t r_2 : 1; + uint8_t slave2_add : 7; + uint8_t r_2 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_slv2_add_t; -#define LSM6DSV16X_SLV2_SUBADD 0x1CU +#define LSM6DSV16X_SLV2_SUBADD 0x1CU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t slave2_reg : 8; + uint8_t slave2_reg : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t slave2_reg : 8; + uint8_t slave2_reg : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_slv2_subadd_t; -#define LSM6DSV16X_SLV2_CONFIG 0x1DU +#define LSM6DSV16X_SLV2_CONFIG 0x1DU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t slave2_numop : 3; + uint8_t slave2_numop : 3; uint8_t batch_ext_sens_2_en : 1; - uint8_t not_used0 : 4; + uint8_t not_used0 : 4; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 4; + uint8_t not_used0 : 4; uint8_t batch_ext_sens_2_en : 1; - uint8_t slave2_numop : 3; + uint8_t slave2_numop : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_slv2_config_t; -#define LSM6DSV16X_SLV3_ADD 0x1EU +#define LSM6DSV16X_SLV3_ADD 0x1EU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t r_3 : 1; - uint8_t slave3_add : 7; + uint8_t r_3 : 1; + uint8_t slave3_add : 7; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t slave3_add : 7; - uint8_t r_3 : 1; + uint8_t slave3_add : 7; + uint8_t r_3 : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_slv3_add_t; -#define LSM6DSV16X_SLV3_SUBADD 0x1FU +#define LSM6DSV16X_SLV3_SUBADD 0x1FU typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t slave3_reg : 8; + uint8_t slave3_reg : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t slave3_reg : 8; + uint8_t slave3_reg : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_slv3_subadd_t; -#define LSM6DSV16X_SLV3_CONFIG 0x20U +#define LSM6DSV16X_SLV3_CONFIG 0x20U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t slave3_numop : 3; + uint8_t slave3_numop : 3; uint8_t batch_ext_sens_3_en : 1; - uint8_t not_used0 : 4; + uint8_t not_used0 : 4; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t not_used0 : 4; + uint8_t not_used0 : 4; uint8_t batch_ext_sens_3_en : 1; - uint8_t slave3_numop : 3; + uint8_t slave3_numop : 3; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_slv3_config_t; -#define LSM6DSV16X_DATAWRITE_SLV0 0x21U +#define LSM6DSV16X_DATAWRITE_SLV0 0x21U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t slave0_dataw : 8; + uint8_t slave0_dataw : 8; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t slave0_dataw : 8; + uint8_t slave0_dataw : 8; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_datawrite_slv0_t; -#define LSM6DSV16X_STATUS_MASTER 0x22U +#define LSM6DSV16X_STATUS_MASTER 0x22U typedef struct { #if DRV_BYTE_ORDER == DRV_LITTLE_ENDIAN - uint8_t sens_hub_endop : 1; - uint8_t not_used0 : 2; - uint8_t slave0_nack : 1; - uint8_t slave1_nack : 1; - uint8_t slave2_nack : 1; - uint8_t slave3_nack : 1; - uint8_t wr_once_done : 1; + uint8_t sens_hub_endop : 1; + uint8_t not_used0 : 2; + uint8_t slave0_nack : 1; + uint8_t slave1_nack : 1; + uint8_t slave2_nack : 1; + uint8_t slave3_nack : 1; + uint8_t wr_once_done : 1; #elif DRV_BYTE_ORDER == DRV_BIG_ENDIAN - uint8_t wr_once_done : 1; - uint8_t slave3_nack : 1; - uint8_t slave2_nack : 1; - uint8_t slave1_nack : 1; - uint8_t slave0_nack : 1; - uint8_t not_used0 : 2; - uint8_t sens_hub_endop : 1; + uint8_t wr_once_done : 1; + uint8_t slave3_nack : 1; + uint8_t slave2_nack : 1; + uint8_t slave1_nack : 1; + uint8_t slave0_nack : 1; + uint8_t not_used0 : 2; + uint8_t sens_hub_endop : 1; #endif /* DRV_BYTE_ORDER */ } lsm6dsv16x_status_master_t; @@ -3290,279 +3351,275 @@ typedef struct { * */ +/** + * @defgroup LSM6DSO_Register_Union + * @brief This union group all the registers having a bit-field + * description. + * This union is useful but it's not needed by the driver. + * + * REMOVING this union you are compliant with: + * MISRA-C 2012 [Rule 19.2] -> " Union are not allowed " + * + * @{ + * + */ typedef union { - lsm6dsv16x_func_cfg_access_t func_cfg_access; - lsm6dsv16x_pin_ctrl_t pin_ctrl; - lsm6dsv16x_if_cfg_t if_cfg; - lsm6dsv16x_s4s_tph_l_t s4s_tph_l; - lsm6dsv16x_s4s_tph_h_t s4s_tph_h; - lsm6dsv16x_s4s_rr_t s4s_rr; - lsm6dsv16x_fifo_ctrl1_t fifo_ctrl1; - lsm6dsv16x_fifo_ctrl2_t fifo_ctrl2; - lsm6dsv16x_fifo_ctrl3_t fifo_ctrl3; - lsm6dsv16x_fifo_ctrl4_t fifo_ctrl4; - lsm6dsv16x_counter_bdr_reg1_t counter_bdr_reg1; - lsm6dsv16x_counter_bdr_reg2_t counter_bdr_reg2; - lsm6dsv16x_int1_ctrl_t int1_ctrl; - lsm6dsv16x_int2_ctrl_t int2_ctrl; - lsm6dsv16x_who_am_i_t who_am_i; - lsm6dsv16x_ctrl1_t ctrl1; - lsm6dsv16x_ctrl2_t ctrl2; - lsm6dsv16x_ctrl3_t ctrl3; - lsm6dsv16x_ctrl4_t ctrl4; - lsm6dsv16x_ctrl5_t ctrl5; - lsm6dsv16x_ctrl6_t ctrl6; - lsm6dsv16x_ctrl7_t ctrl7; - lsm6dsv16x_ctrl8_t ctrl8; - lsm6dsv16x_ctrl9_t ctrl9; - lsm6dsv16x_ctrl10_t ctrl10; - lsm6dsv16x_ctrl_status_t ctrl_status; - lsm6dsv16x_fifo_status1_t fifo_status1; - lsm6dsv16x_fifo_status2_t fifo_status2; - lsm6dsv16x_all_int_src_t all_int_src; - lsm6dsv16x_status_reg_t status_reg; - lsm6dsv16x_out_temp_l_t out_temp_l; - lsm6dsv16x_out_temp_h_t out_temp_h; - lsm6dsv16x_outx_l_g_t outx_l_g; - lsm6dsv16x_outx_h_g_t outx_h_g; - lsm6dsv16x_outy_l_g_t outy_l_g; - lsm6dsv16x_outy_h_g_t outy_h_g; - lsm6dsv16x_outz_l_g_t outz_l_g; - lsm6dsv16x_outz_h_g_t outz_h_g; - lsm6dsv16x_outx_l_a_t outx_l_a; - lsm6dsv16x_outx_h_a_t outx_h_a; - lsm6dsv16x_outy_l_a_t outy_l_a; - lsm6dsv16x_outy_h_a_t outy_h_a; - lsm6dsv16x_outz_l_a_t outz_l_a; - lsm6dsv16x_outz_h_a_t outz_h_a; - lsm6dsv16x_ui_outx_l_g_ois_eis_t ui_outx_l_g_ois_eis; - lsm6dsv16x_ui_outx_h_g_ois_eis_t ui_outx_h_g_ois_eis; - lsm6dsv16x_ui_outy_l_g_ois_eis_t ui_outy_l_g_ois_eis; - lsm6dsv16x_ui_outy_h_g_ois_eis_t ui_outy_h_g_ois_eis; - lsm6dsv16x_ui_outz_l_g_ois_eis_t ui_outz_l_g_ois_eis; - lsm6dsv16x_ui_outz_h_g_ois_eis_t ui_outz_h_g_ois_eis; + lsm6dsv16x_func_cfg_access_t func_cfg_access; + lsm6dsv16x_pin_ctrl_t pin_ctrl; + lsm6dsv16x_if_cfg_t if_cfg; + lsm6dsv16x_odr_trig_cfg_t odr_trig_cfg; + lsm6dsv16x_fifo_ctrl1_t fifo_ctrl1; + lsm6dsv16x_fifo_ctrl2_t fifo_ctrl2; + lsm6dsv16x_fifo_ctrl3_t fifo_ctrl3; + lsm6dsv16x_fifo_ctrl4_t fifo_ctrl4; + lsm6dsv16x_counter_bdr_reg1_t counter_bdr_reg1; + lsm6dsv16x_counter_bdr_reg2_t counter_bdr_reg2; + lsm6dsv16x_int1_ctrl_t int1_ctrl; + lsm6dsv16x_int2_ctrl_t int2_ctrl; + lsm6dsv16x_who_am_i_t who_am_i; + lsm6dsv16x_ctrl1_t ctrl1; + lsm6dsv16x_ctrl2_t ctrl2; + lsm6dsv16x_ctrl3_t ctrl3; + lsm6dsv16x_ctrl4_t ctrl4; + lsm6dsv16x_ctrl5_t ctrl5; + lsm6dsv16x_ctrl6_t ctrl6; + lsm6dsv16x_ctrl7_t ctrl7; + lsm6dsv16x_ctrl8_t ctrl8; + lsm6dsv16x_ctrl9_t ctrl9; + lsm6dsv16x_ctrl10_t ctrl10; + lsm6dsv16x_ctrl_status_t ctrl_status; + lsm6dsv16x_fifo_status1_t fifo_status1; + lsm6dsv16x_fifo_status2_t fifo_status2; + lsm6dsv16x_all_int_src_t all_int_src; + lsm6dsv16x_status_reg_t status_reg; + lsm6dsv16x_out_temp_l_t out_temp_l; + lsm6dsv16x_out_temp_h_t out_temp_h; + lsm6dsv16x_outx_l_g_t outx_l_g; + lsm6dsv16x_outx_h_g_t outx_h_g; + lsm6dsv16x_outy_l_g_t outy_l_g; + lsm6dsv16x_outy_h_g_t outy_h_g; + lsm6dsv16x_outz_l_g_t outz_l_g; + lsm6dsv16x_outz_h_g_t outz_h_g; + lsm6dsv16x_outx_l_a_t outx_l_a; + lsm6dsv16x_outx_h_a_t outx_h_a; + lsm6dsv16x_outy_l_a_t outy_l_a; + lsm6dsv16x_outy_h_a_t outy_h_a; + lsm6dsv16x_outz_l_a_t outz_l_a; + lsm6dsv16x_outz_h_a_t outz_h_a; + lsm6dsv16x_ui_outx_l_g_ois_eis_t ui_outx_l_g_ois_eis; + lsm6dsv16x_ui_outx_h_g_ois_eis_t ui_outx_h_g_ois_eis; + lsm6dsv16x_ui_outy_l_g_ois_eis_t ui_outy_l_g_ois_eis; + lsm6dsv16x_ui_outy_h_g_ois_eis_t ui_outy_h_g_ois_eis; + lsm6dsv16x_ui_outz_l_g_ois_eis_t ui_outz_l_g_ois_eis; + lsm6dsv16x_ui_outz_h_g_ois_eis_t ui_outz_h_g_ois_eis; lsm6dsv16x_ui_outx_l_a_ois_dualc_t ui_outx_l_a_ois_dualc; lsm6dsv16x_ui_outx_h_a_ois_dualc_t ui_outx_h_a_ois_dualc; lsm6dsv16x_ui_outy_l_a_ois_dualc_t ui_outy_l_a_ois_dualc; lsm6dsv16x_ui_outy_h_a_ois_dualc_t ui_outy_h_a_ois_dualc; lsm6dsv16x_ui_outz_l_a_ois_dualc_t ui_outz_l_a_ois_dualc; lsm6dsv16x_ui_outz_h_a_ois_dualc_t ui_outz_h_a_ois_dualc; - lsm6dsv16x_ah_qvar_out_l_t ah_qvar_out_l; - lsm6dsv16x_ah_qvar_out_h_t ah_qvar_out_h; - lsm6dsv16x_timestamp0_t timestamp0; - lsm6dsv16x_timestamp1_t timestamp1; - lsm6dsv16x_timestamp2_t timestamp2; - lsm6dsv16x_timestamp3_t timestamp3; - lsm6dsv16x_ui_status_reg_ois_t ui_status_reg_ois; - lsm6dsv16x_wake_up_src_t wake_up_src; - lsm6dsv16x_tap_src_t tap_src; - lsm6dsv16x_d6d_src_t d6d_src; - lsm6dsv16x_status_master_mainpage_t status_master_mainpage; - lsm6dsv16x_emb_func_status_mainpage_t emb_func_status_mainpage; - lsm6dsv16x_fsm_status_mainpage_t fsm_status_mainpage; - lsm6dsv16x_mlc_status_mainpage_t mlc_status_mainpage; - lsm6dsv16x_internal_freq_t internal_freq; - lsm6dsv16x_functions_enable_t functions_enable; - lsm6dsv16x_den_t den; - lsm6dsv16x_inactivity_dur_t inactivity_dur; - lsm6dsv16x_inactivity_ths_t inactivity_ths; - lsm6dsv16x_tap_cfg0_t tap_cfg0; - lsm6dsv16x_tap_cfg1_t tap_cfg1; - lsm6dsv16x_tap_cfg2_t tap_cfg2; - lsm6dsv16x_tap_ths_6d_t tap_ths_6d; - lsm6dsv16x_int_dur2_t int_dur2; - lsm6dsv16x_wake_up_ths_t wake_up_ths; - lsm6dsv16x_wake_up_dur_t wake_up_dur; - lsm6dsv16x_free_fall_t free_fall; - lsm6dsv16x_md1_cfg_t md1_cfg; - lsm6dsv16x_md2_cfg_t md2_cfg; - lsm6dsv16x_s4s_st_cmd_code_t s4s_st_cmd_code; - lsm6dsv16x_s4s_dt_reg_t s4s_dt_reg; - lsm6dsv16x_emb_func_cfg_t emb_func_cfg; - lsm6dsv16x_ui_handshake_ctrl_t ui_handshake_ctrl; - lsm6dsv16x_ui_spi2_shared_0_t ui_spi2_shared_0; - lsm6dsv16x_ui_spi2_shared_1_t ui_spi2_shared_1; - lsm6dsv16x_ui_spi2_shared_2_t ui_spi2_shared_2; - lsm6dsv16x_ui_spi2_shared_3_t ui_spi2_shared_3; - lsm6dsv16x_ui_spi2_shared_4_t ui_spi2_shared_4; - lsm6dsv16x_ui_spi2_shared_5_t ui_spi2_shared_5; - lsm6dsv16x_ctrl_eis_t ctrl_eis; - lsm6dsv16x_ui_int_ois_t ui_int_ois; - lsm6dsv16x_ui_ctrl1_ois_t ui_ctrl1_ois; - lsm6dsv16x_ui_ctrl2_ois_t ui_ctrl2_ois; - lsm6dsv16x_ui_ctrl3_ois_t ui_ctrl3_ois; - lsm6dsv16x_x_ofs_usr_t x_ofs_usr; - lsm6dsv16x_y_ofs_usr_t y_ofs_usr; - lsm6dsv16x_z_ofs_usr_t z_ofs_usr; - lsm6dsv16x_fifo_data_out_tag_t fifo_data_out_tag; - lsm6dsv16x_fifo_data_out_x_l_t fifo_data_out_x_l; - lsm6dsv16x_fifo_data_out_x_h_t fifo_data_out_x_h; - lsm6dsv16x_fifo_data_out_y_l_t fifo_data_out_y_l; - lsm6dsv16x_fifo_data_out_y_h_t fifo_data_out_y_h; - lsm6dsv16x_fifo_data_out_z_l_t fifo_data_out_z_l; - lsm6dsv16x_fifo_data_out_z_h_t fifo_data_out_z_h; - bitwise_t bitwise; - uint8_t byte; -} prefix_lowmain_t; - -typedef union { - lsm6dsv16x_spi2_who_am_i_t spi2_who_am_i; - lsm6dsv16x_spi2_status_reg_ois_t spi2_status_reg_ois; - lsm6dsv16x_spi2_out_temp_l_t spi2_out_temp_l; - lsm6dsv16x_spi2_out_temp_h_t spi2_out_temp_h; - lsm6dsv16x_spi2_outx_l_g_ois_t spi2_outx_l_g_ois; - lsm6dsv16x_spi2_outx_h_g_ois_t spi2_outx_h_g_ois; - lsm6dsv16x_spi2_outy_l_g_ois_t spi2_outy_l_g_ois; - lsm6dsv16x_spi2_outy_h_g_ois_t spi2_outy_h_g_ois; - lsm6dsv16x_spi2_outz_l_g_ois_t spi2_outz_l_g_ois; - lsm6dsv16x_spi2_outz_h_g_ois_t spi2_outz_h_g_ois; - lsm6dsv16x_spi2_outx_l_a_ois_t spi2_outx_l_a_ois; - lsm6dsv16x_spi2_outx_h_a_ois_t spi2_outx_h_a_ois; - lsm6dsv16x_spi2_outy_l_a_ois_t spi2_outy_l_a_ois; - lsm6dsv16x_spi2_outy_h_a_ois_t spi2_outy_h_a_ois; - lsm6dsv16x_spi2_outz_l_a_ois_t spi2_outz_l_a_ois; - lsm6dsv16x_spi2_outz_h_a_ois_t spi2_outz_h_a_ois; - lsm6dsv16x_spi2_handshake_ctrl_t spi2_handshake_ctrl; - lsm6dsv16x_spi2_int_ois_t spi2_int_ois; - lsm6dsv16x_spi2_ctrl1_ois_t spi2_ctrl1_ois; - lsm6dsv16x_spi2_ctrl2_ois_t spi2_ctrl2_ois; - lsm6dsv16x_spi2_ctrl3_ois_t spi2_ctrl3_ois; - bitwise_t bitwise; - uint8_t byte; -} prefix_lowspi2_t; - -typedef union { - lsm6dsv16x_page_sel_t page_sel; - lsm6dsv16x_emb_func_en_a_t emb_func_en_a; - lsm6dsv16x_emb_func_en_b_t emb_func_en_b; - lsm6dsv16x_emb_func_exec_status_t emb_func_exec_status; - lsm6dsv16x_page_address_t page_address; - lsm6dsv16x_page_value_t page_value; - lsm6dsv16x_emb_func_int1_t emb_func_int1; - lsm6dsv16x_fsm_int1_t fsm_int1; - lsm6dsv16x_mlc_int1_t mlc_int1; - lsm6dsv16x_emb_func_int2_t emb_func_int2; - lsm6dsv16x_fsm_int2_t fsm_int2; - lsm6dsv16x_mlc_int2_t mlc_int2; - lsm6dsv16x_emb_func_status_t emb_func_status; - lsm6dsv16x_fsm_status_t fsm_status; - lsm6dsv16x_mlc_status_t mlc_status; - lsm6dsv16x_page_rw_t page_rw; - lsm6dsv16x_emb_func_fifo_en_a_t emb_func_fifo_en_a; - lsm6dsv16x_emb_func_fifo_en_b_t emb_func_fifo_en_b; - lsm6dsv16x_fsm_enable_t fsm_enable; - lsm6dsv16x_fsm_long_counter_l_t fsm_long_counter_l; - lsm6dsv16x_fsm_long_counter_h_t fsm_long_counter_h; - lsm6dsv16x_int_ack_mask_t int_ack_mask; - lsm6dsv16x_fsm_outs1_t fsm_outs1; - lsm6dsv16x_fsm_outs2_t fsm_outs2; - lsm6dsv16x_fsm_outs3_t fsm_outs3; - lsm6dsv16x_fsm_outs4_t fsm_outs4; - lsm6dsv16x_fsm_outs5_t fsm_outs5; - lsm6dsv16x_fsm_outs6_t fsm_outs6; - lsm6dsv16x_fsm_outs7_t fsm_outs7; - lsm6dsv16x_fsm_outs8_t fsm_outs8; - lsm6dsv16x_fsm_odr_t fsm_odr; - lsm6dsv16x_mlc_odr_t mlc_odr; - lsm6dsv16x_step_counter_l_t step_counter_l; - lsm6dsv16x_step_counter_h_t step_counter_h; - lsm6dsv16x_emb_func_src_t emb_func_src; - lsm6dsv16x_emb_func_init_a_t emb_func_init_a; - lsm6dsv16x_emb_func_init_b_t emb_func_init_b; - lsm6dsv16x_mlc1_src_t mlc1_src; - lsm6dsv16x_mlc2_src_t mlc2_src; - lsm6dsv16x_mlc3_src_t mlc3_src; - lsm6dsv16x_mlc4_src_t mlc4_src; - bitwise_t bitwise; - uint8_t byte; -} prefix_lowembedded_t; - -typedef union { + lsm6dsv16x_ah_qvar_out_l_t ah_qvar_out_l; + lsm6dsv16x_ah_qvar_out_h_t ah_qvar_out_h; + lsm6dsv16x_timestamp0_t timestamp0; + lsm6dsv16x_timestamp1_t timestamp1; + lsm6dsv16x_timestamp2_t timestamp2; + lsm6dsv16x_timestamp3_t timestamp3; + lsm6dsv16x_ui_status_reg_ois_t ui_status_reg_ois; + lsm6dsv16x_wake_up_src_t wake_up_src; + lsm6dsv16x_tap_src_t tap_src; + lsm6dsv16x_d6d_src_t d6d_src; + lsm6dsv16x_status_master_mainpage_t status_master_mainpage; + lsm6dsv16x_emb_func_status_mainpage_t emb_func_status_mainpage; + lsm6dsv16x_fsm_status_mainpage_t fsm_status_mainpage; + lsm6dsv16x_mlc_status_mainpage_t mlc_status_mainpage; + lsm6dsv16x_internal_freq_t internal_freq; + lsm6dsv16x_functions_enable_t functions_enable; + lsm6dsv16x_den_t den; + lsm6dsv16x_inactivity_dur_t inactivity_dur; + lsm6dsv16x_inactivity_ths_t inactivity_ths; + lsm6dsv16x_tap_cfg0_t tap_cfg0; + lsm6dsv16x_tap_cfg1_t tap_cfg1; + lsm6dsv16x_tap_cfg2_t tap_cfg2; + lsm6dsv16x_tap_ths_6d_t tap_ths_6d; + lsm6dsv16x_tap_dur_t tap_dur; + lsm6dsv16x_wake_up_ths_t wake_up_ths; + lsm6dsv16x_wake_up_dur_t wake_up_dur; + lsm6dsv16x_free_fall_t free_fall; + lsm6dsv16x_md1_cfg_t md1_cfg; + lsm6dsv16x_md2_cfg_t md2_cfg; + lsm6dsv16x_emb_func_cfg_t emb_func_cfg; + lsm6dsv16x_ui_handshake_ctrl_t ui_handshake_ctrl; + lsm6dsv16x_ui_spi2_shared_0_t ui_spi2_shared_0; + lsm6dsv16x_ui_spi2_shared_1_t ui_spi2_shared_1; + lsm6dsv16x_ui_spi2_shared_2_t ui_spi2_shared_2; + lsm6dsv16x_ui_spi2_shared_3_t ui_spi2_shared_3; + lsm6dsv16x_ui_spi2_shared_4_t ui_spi2_shared_4; + lsm6dsv16x_ui_spi2_shared_5_t ui_spi2_shared_5; + lsm6dsv16x_ctrl_eis_t ctrl_eis; + lsm6dsv16x_ui_int_ois_t ui_int_ois; + lsm6dsv16x_ui_ctrl1_ois_t ui_ctrl1_ois; + lsm6dsv16x_ui_ctrl2_ois_t ui_ctrl2_ois; + lsm6dsv16x_ui_ctrl3_ois_t ui_ctrl3_ois; + lsm6dsv16x_x_ofs_usr_t x_ofs_usr; + lsm6dsv16x_y_ofs_usr_t y_ofs_usr; + lsm6dsv16x_z_ofs_usr_t z_ofs_usr; + lsm6dsv16x_fifo_data_out_tag_t fifo_data_out_tag; + lsm6dsv16x_fifo_data_out_x_l_t fifo_data_out_x_l; + lsm6dsv16x_fifo_data_out_x_h_t fifo_data_out_x_h; + lsm6dsv16x_fifo_data_out_y_l_t fifo_data_out_y_l; + lsm6dsv16x_fifo_data_out_y_h_t fifo_data_out_y_h; + lsm6dsv16x_fifo_data_out_z_l_t fifo_data_out_z_l; + lsm6dsv16x_fifo_data_out_z_h_t fifo_data_out_z_h; + lsm6dsv16x_spi2_who_am_i_t spi2_who_am_i; + lsm6dsv16x_spi2_status_reg_ois_t spi2_status_reg_ois; + lsm6dsv16x_spi2_out_temp_l_t spi2_out_temp_l; + lsm6dsv16x_spi2_out_temp_h_t spi2_out_temp_h; + lsm6dsv16x_spi2_outx_l_g_ois_t spi2_outx_l_g_ois; + lsm6dsv16x_spi2_outx_h_g_ois_t spi2_outx_h_g_ois; + lsm6dsv16x_spi2_outy_l_g_ois_t spi2_outy_l_g_ois; + lsm6dsv16x_spi2_outy_h_g_ois_t spi2_outy_h_g_ois; + lsm6dsv16x_spi2_outz_l_g_ois_t spi2_outz_l_g_ois; + lsm6dsv16x_spi2_outz_h_g_ois_t spi2_outz_h_g_ois; + lsm6dsv16x_spi2_outx_l_a_ois_t spi2_outx_l_a_ois; + lsm6dsv16x_spi2_outx_h_a_ois_t spi2_outx_h_a_ois; + lsm6dsv16x_spi2_outy_l_a_ois_t spi2_outy_l_a_ois; + lsm6dsv16x_spi2_outy_h_a_ois_t spi2_outy_h_a_ois; + lsm6dsv16x_spi2_outz_l_a_ois_t spi2_outz_l_a_ois; + lsm6dsv16x_spi2_outz_h_a_ois_t spi2_outz_h_a_ois; + lsm6dsv16x_spi2_handshake_ctrl_t spi2_handshake_ctrl; + lsm6dsv16x_spi2_int_ois_t spi2_int_ois; + lsm6dsv16x_spi2_ctrl1_ois_t spi2_ctrl1_ois; + lsm6dsv16x_spi2_ctrl2_ois_t spi2_ctrl2_ois; + lsm6dsv16x_spi2_ctrl3_ois_t spi2_ctrl3_ois; + lsm6dsv16x_page_sel_t page_sel; + lsm6dsv16x_emb_func_en_a_t emb_func_en_a; + lsm6dsv16x_emb_func_en_b_t emb_func_en_b; + lsm6dsv16x_emb_func_exec_status_t emb_func_exec_status; + lsm6dsv16x_page_address_t page_address; + lsm6dsv16x_page_value_t page_value; + lsm6dsv16x_emb_func_int1_t emb_func_int1; + lsm6dsv16x_fsm_int1_t fsm_int1; + lsm6dsv16x_mlc_int1_t mlc_int1; + lsm6dsv16x_emb_func_int2_t emb_func_int2; + lsm6dsv16x_fsm_int2_t fsm_int2; + lsm6dsv16x_mlc_int2_t mlc_int2; + lsm6dsv16x_emb_func_status_t emb_func_status; + lsm6dsv16x_fsm_status_t fsm_status; + lsm6dsv16x_mlc_status_t mlc_status; + lsm6dsv16x_page_rw_t page_rw; + lsm6dsv16x_emb_func_fifo_en_a_t emb_func_fifo_en_a; + lsm6dsv16x_emb_func_fifo_en_b_t emb_func_fifo_en_b; + lsm6dsv16x_fsm_enable_t fsm_enable; + lsm6dsv16x_fsm_long_counter_l_t fsm_long_counter_l; + lsm6dsv16x_fsm_long_counter_h_t fsm_long_counter_h; + lsm6dsv16x_int_ack_mask_t int_ack_mask; + lsm6dsv16x_fsm_outs1_t fsm_outs1; + lsm6dsv16x_fsm_outs2_t fsm_outs2; + lsm6dsv16x_fsm_outs3_t fsm_outs3; + lsm6dsv16x_fsm_outs4_t fsm_outs4; + lsm6dsv16x_fsm_outs5_t fsm_outs5; + lsm6dsv16x_fsm_outs6_t fsm_outs6; + lsm6dsv16x_fsm_outs7_t fsm_outs7; + lsm6dsv16x_fsm_outs8_t fsm_outs8; + lsm6dsv16x_fsm_odr_t fsm_odr; + lsm6dsv16x_mlc_odr_t mlc_odr; + lsm6dsv16x_step_counter_l_t step_counter_l; + lsm6dsv16x_step_counter_h_t step_counter_h; + lsm6dsv16x_emb_func_src_t emb_func_src; + lsm6dsv16x_emb_func_init_a_t emb_func_init_a; + lsm6dsv16x_emb_func_init_b_t emb_func_init_b; + lsm6dsv16x_mlc1_src_t mlc1_src; + lsm6dsv16x_mlc2_src_t mlc2_src; + lsm6dsv16x_mlc3_src_t mlc3_src; + lsm6dsv16x_mlc4_src_t mlc4_src; lsm6dsv16x_fsm_ext_sensitivity_l_t fsm_ext_sensitivity_l; lsm6dsv16x_fsm_ext_sensitivity_h_t fsm_ext_sensitivity_h; - lsm6dsv16x_fsm_ext_offx_l_t fsm_ext_offx_l; - lsm6dsv16x_fsm_ext_offx_h_t fsm_ext_offx_h; - lsm6dsv16x_fsm_ext_offy_l_t fsm_ext_offy_l; - lsm6dsv16x_fsm_ext_offy_h_t fsm_ext_offy_h; - lsm6dsv16x_fsm_ext_offz_l_t fsm_ext_offz_l; - lsm6dsv16x_fsm_ext_offz_h_t fsm_ext_offz_h; - lsm6dsv16x_fsm_ext_matrix_xx_l_t fsm_ext_matrix_xx_l; - lsm6dsv16x_fsm_ext_matrix_xx_h_t fsm_ext_matrix_xx_h; - lsm6dsv16x_fsm_ext_matrix_xy_l_t fsm_ext_matrix_xy_l; - lsm6dsv16x_fsm_ext_matrix_xy_h_t fsm_ext_matrix_xy_h; - lsm6dsv16x_fsm_ext_matrix_xz_l_t fsm_ext_matrix_xz_l; - lsm6dsv16x_fsm_ext_matrix_xz_h_t fsm_ext_matrix_xz_h; - lsm6dsv16x_fsm_ext_matrix_yy_l_t fsm_ext_matrix_yy_l; - lsm6dsv16x_fsm_ext_matrix_yy_h_t fsm_ext_matrix_yy_h; - lsm6dsv16x_fsm_ext_matrix_yz_l_t fsm_ext_matrix_yz_l; - lsm6dsv16x_fsm_ext_matrix_yz_h_t fsm_ext_matrix_yz_h; - lsm6dsv16x_fsm_ext_matrix_zz_l_t fsm_ext_matrix_zz_l; - lsm6dsv16x_fsm_ext_matrix_zz_h_t fsm_ext_matrix_zz_h; - lsm6dsv16x_ext_cfg_a_t ext_cfg_a; - lsm6dsv16x_ext_cfg_b_t ext_cfg_b; - bitwise_t bitwise; - uint8_t byte; -} prefix_lowpg0_emb_adv_t; - -typedef union { - lsm6dsv16x_fsm_lc_timeout_l_t fsm_lc_timeout_l; - lsm6dsv16x_fsm_lc_timeout_h_t fsm_lc_timeout_h; - lsm6dsv16x_fsm_programs_t fsm_programs; - lsm6dsv16x_fsm_start_add_l_t fsm_start_add_l; - lsm6dsv16x_fsm_start_add_h_t fsm_start_add_h; - lsm6dsv16x_pedo_cmd_reg_t pedo_cmd_reg; - lsm6dsv16x_pedo_deb_steps_conf_t pedo_deb_steps_conf; - lsm6dsv16x_pedo_sc_deltat_l_t pedo_sc_deltat_l; - lsm6dsv16x_pedo_sc_deltat_h_t pedo_sc_deltat_h; + lsm6dsv16x_fsm_ext_offx_l_t fsm_ext_offx_l; + lsm6dsv16x_fsm_ext_offx_h_t fsm_ext_offx_h; + lsm6dsv16x_fsm_ext_offy_l_t fsm_ext_offy_l; + lsm6dsv16x_fsm_ext_offy_h_t fsm_ext_offy_h; + lsm6dsv16x_fsm_ext_offz_l_t fsm_ext_offz_l; + lsm6dsv16x_fsm_ext_offz_h_t fsm_ext_offz_h; + lsm6dsv16x_fsm_ext_matrix_xx_l_t fsm_ext_matrix_xx_l; + lsm6dsv16x_fsm_ext_matrix_xx_h_t fsm_ext_matrix_xx_h; + lsm6dsv16x_fsm_ext_matrix_xy_l_t fsm_ext_matrix_xy_l; + lsm6dsv16x_fsm_ext_matrix_xy_h_t fsm_ext_matrix_xy_h; + lsm6dsv16x_fsm_ext_matrix_xz_l_t fsm_ext_matrix_xz_l; + lsm6dsv16x_fsm_ext_matrix_xz_h_t fsm_ext_matrix_xz_h; + lsm6dsv16x_fsm_ext_matrix_yy_l_t fsm_ext_matrix_yy_l; + lsm6dsv16x_fsm_ext_matrix_yy_h_t fsm_ext_matrix_yy_h; + lsm6dsv16x_fsm_ext_matrix_yz_l_t fsm_ext_matrix_yz_l; + lsm6dsv16x_fsm_ext_matrix_yz_h_t fsm_ext_matrix_yz_h; + lsm6dsv16x_fsm_ext_matrix_zz_l_t fsm_ext_matrix_zz_l; + lsm6dsv16x_fsm_ext_matrix_zz_h_t fsm_ext_matrix_zz_h; + lsm6dsv16x_ext_cfg_a_t ext_cfg_a; + lsm6dsv16x_ext_cfg_b_t ext_cfg_b; + lsm6dsv16x_fsm_lc_timeout_l_t fsm_lc_timeout_l; + lsm6dsv16x_fsm_lc_timeout_h_t fsm_lc_timeout_h; + lsm6dsv16x_fsm_programs_t fsm_programs; + lsm6dsv16x_fsm_start_add_l_t fsm_start_add_l; + lsm6dsv16x_fsm_start_add_h_t fsm_start_add_h; + lsm6dsv16x_pedo_cmd_reg_t pedo_cmd_reg; + lsm6dsv16x_pedo_deb_steps_conf_t pedo_deb_steps_conf; + lsm6dsv16x_pedo_sc_deltat_l_t pedo_sc_deltat_l; + lsm6dsv16x_pedo_sc_deltat_h_t pedo_sc_deltat_h; lsm6dsv16x_mlc_ext_sensitivity_l_t mlc_ext_sensitivity_l; lsm6dsv16x_mlc_ext_sensitivity_h_t mlc_ext_sensitivity_h; - bitwise_t bitwise; - uint8_t byte; -} prefix_lowpg1_emb_adv_t; - -typedef union { - lsm6dsv16x_sensor_hub_1_t sensor_hub_1; - lsm6dsv16x_sensor_hub_2_t sensor_hub_2; - lsm6dsv16x_sensor_hub_3_t sensor_hub_3; - lsm6dsv16x_sensor_hub_4_t sensor_hub_4; - lsm6dsv16x_sensor_hub_5_t sensor_hub_5; - lsm6dsv16x_sensor_hub_6_t sensor_hub_6; - lsm6dsv16x_sensor_hub_7_t sensor_hub_7; - lsm6dsv16x_sensor_hub_8_t sensor_hub_8; - lsm6dsv16x_sensor_hub_9_t sensor_hub_9; - lsm6dsv16x_sensor_hub_10_t sensor_hub_10; - lsm6dsv16x_sensor_hub_11_t sensor_hub_11; - lsm6dsv16x_sensor_hub_12_t sensor_hub_12; - lsm6dsv16x_sensor_hub_13_t sensor_hub_13; - lsm6dsv16x_sensor_hub_14_t sensor_hub_14; - lsm6dsv16x_sensor_hub_15_t sensor_hub_15; - lsm6dsv16x_sensor_hub_16_t sensor_hub_16; - lsm6dsv16x_sensor_hub_17_t sensor_hub_17; - lsm6dsv16x_sensor_hub_18_t sensor_hub_18; - lsm6dsv16x_master_config_t master_config; - lsm6dsv16x_slv0_add_t slv0_add; - lsm6dsv16x_slv0_subadd_t slv0_subadd; - lsm6dsv16x_slv0_config_t slv0_config; - lsm6dsv16x_slv1_add_t slv1_add; - lsm6dsv16x_slv1_subadd_t slv1_subadd; - lsm6dsv16x_slv1_config_t slv1_config; - lsm6dsv16x_slv2_add_t slv2_add; - lsm6dsv16x_slv2_subadd_t slv2_subadd; - lsm6dsv16x_slv2_config_t slv2_config; - lsm6dsv16x_slv3_add_t slv3_add; - lsm6dsv16x_slv3_subadd_t slv3_subadd; - lsm6dsv16x_slv3_config_t slv3_config; - lsm6dsv16x_datawrite_slv0_t datawrite_slv0; - lsm6dsv16x_status_master_t status_master; - bitwise_t bitwise; - uint8_t byte; -} prefix_lowsensor_hub_t; + lsm6dsv16x_sensor_hub_1_t sensor_hub_1; + lsm6dsv16x_sensor_hub_2_t sensor_hub_2; + lsm6dsv16x_sensor_hub_3_t sensor_hub_3; + lsm6dsv16x_sensor_hub_4_t sensor_hub_4; + lsm6dsv16x_sensor_hub_5_t sensor_hub_5; + lsm6dsv16x_sensor_hub_6_t sensor_hub_6; + lsm6dsv16x_sensor_hub_7_t sensor_hub_7; + lsm6dsv16x_sensor_hub_8_t sensor_hub_8; + lsm6dsv16x_sensor_hub_9_t sensor_hub_9; + lsm6dsv16x_sensor_hub_10_t sensor_hub_10; + lsm6dsv16x_sensor_hub_11_t sensor_hub_11; + lsm6dsv16x_sensor_hub_12_t sensor_hub_12; + lsm6dsv16x_sensor_hub_13_t sensor_hub_13; + lsm6dsv16x_sensor_hub_14_t sensor_hub_14; + lsm6dsv16x_sensor_hub_15_t sensor_hub_15; + lsm6dsv16x_sensor_hub_16_t sensor_hub_16; + lsm6dsv16x_sensor_hub_17_t sensor_hub_17; + lsm6dsv16x_sensor_hub_18_t sensor_hub_18; + lsm6dsv16x_master_config_t master_config; + lsm6dsv16x_slv0_add_t slv0_add; + lsm6dsv16x_slv0_subadd_t slv0_subadd; + lsm6dsv16x_slv0_config_t slv0_config; + lsm6dsv16x_slv1_add_t slv1_add; + lsm6dsv16x_slv1_subadd_t slv1_subadd; + lsm6dsv16x_slv1_config_t slv1_config; + lsm6dsv16x_slv2_add_t slv2_add; + lsm6dsv16x_slv2_subadd_t slv2_subadd; + lsm6dsv16x_slv2_config_t slv2_config; + lsm6dsv16x_slv3_add_t slv3_add; + lsm6dsv16x_slv3_subadd_t slv3_subadd; + lsm6dsv16x_slv3_config_t slv3_config; + lsm6dsv16x_datawrite_slv0_t datawrite_slv0; + lsm6dsv16x_status_master_t status_master; + bitwise_t bitwise; + uint8_t byte; +} lsm6dsv16x_reg_t; /** * @} * */ +#ifndef __weak +#define __weak __attribute__((weak)) +#endif /* __weak */ + +/* + * These are the basic platform dependent I/O routines to read + * and write device registers connected on a standard bus. + * The driver keeps offering a default implementation based on function + * pointers to read/write routines for backward compatibility. + * The __weak directive allows the final application to overwrite + * them with a custom implementation. + */ + int32_t lsm6dsv16x_read_reg(lsm6dsv16x_ctx_t *ctx, uint8_t reg, uint8_t *data, uint16_t len); @@ -3570,36 +3627,39 @@ int32_t lsm6dsv16x_write_reg(lsm6dsv16x_ctx_t *ctx, uint8_t reg, uint8_t *data, uint16_t len); -float lsm6dsv16x_from_fs2_to_mg(int16_t lsb); -float lsm6dsv16x_from_fs4_to_mg(int16_t lsb); -float lsm6dsv16x_from_fs8_to_mg(int16_t lsb); -float lsm6dsv16x_from_fs16_to_mg(int16_t lsb); +float_t lsm6dsv16x_from_sflp_to_mg(int16_t lsb); +float_t lsm6dsv16x_from_fs2_to_mg(int16_t lsb); +float_t lsm6dsv16x_from_fs4_to_mg(int16_t lsb); +float_t lsm6dsv16x_from_fs8_to_mg(int16_t lsb); +float_t lsm6dsv16x_from_fs16_to_mg(int16_t lsb); -float lsm6dsv16x_from_fs125_to_mdps(int16_t lsb); -float lsm6dsv16x_from_fs500_to_mdps(int16_t lsb); -float lsm6dsv16x_from_fs250_to_mdps(int16_t lsb); -float lsm6dsv16x_from_fs1000_to_mdps(int16_t lsb); -float lsm6dsv16x_from_fs2000_to_mdps(int16_t lsb); -float lsm6dsv16x_from_fs4000_to_mdps(int16_t lsb); +float_t lsm6dsv16x_from_fs125_to_mdps(int16_t lsb); +float_t lsm6dsv16x_from_fs500_to_mdps(int16_t lsb); +float_t lsm6dsv16x_from_fs250_to_mdps(int16_t lsb); +float_t lsm6dsv16x_from_fs1000_to_mdps(int16_t lsb); +float_t lsm6dsv16x_from_fs2000_to_mdps(int16_t lsb); +float_t lsm6dsv16x_from_fs4000_to_mdps(int16_t lsb); -float lsm6dsv16x_from_lsb_to_celsius(int16_t lsb); +float_t lsm6dsv16x_from_lsb_to_celsius(int16_t lsb); -float lsm6dsv16x_from_lsb_to_nsec(uint32_t lsb); +float_t lsm6dsv16x_from_lsb_to_nsec(uint32_t lsb); int32_t lsm6dsv16x_xl_offset_on_out_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_xl_offset_on_out_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef struct { - float z_mg; - float y_mg; - float x_mg; + float_t z_mg; + float_t y_mg; + float_t x_mg; } lsm6dsv16x_xl_offset_mg_t; -int32_t lsm6dsv16x_xl_offset_mg_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_offset_mg_t val); -int32_t lsm6dsv16x_xl_offset_mg_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_offset_mg_t *val); +int32_t lsm6dsv16x_xl_offset_mg_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_offset_mg_t val); +int32_t lsm6dsv16x_xl_offset_mg_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_offset_mg_t *val); typedef enum { - LSM6DSV16X_READY = 0x0, - LSM6DSV16X_GLOBAL_RST = 0x1, + LSM6DSV16X_READY = 0x0, + LSM6DSV16X_GLOBAL_RST = 0x1, LSM6DSV16X_RESTORE_CAL_PARAM = 0x2, LSM6DSV16X_RESTORE_CTRL_REGS = 0x4, } lsm6dsv16x_reset_t; @@ -3607,7 +3667,7 @@ int32_t lsm6dsv16x_reset_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_reset_t val); int32_t lsm6dsv16x_reset_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_reset_t *val); typedef enum { - LSM6DSV16X_MAIN_MEM_BANK = 0x0, + LSM6DSV16X_MAIN_MEM_BANK = 0x0, LSM6DSV16X_EMBED_FUNC_MEM_BANK = 0x1, LSM6DSV16X_SENSOR_HUB_MEM_BANK = 0x2, } lsm6dsv16x_mem_bank_t; @@ -3617,56 +3677,67 @@ int32_t lsm6dsv16x_mem_bank_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mem_bank_t *va int32_t lsm6dsv16x_device_id_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef enum { - LSM6DSV16X_XL_ODR_OFF = 0x0, - LSM6DSV16X_XL_ODR_AT_1Hz875 = 0x1, - LSM6DSV16X_XL_ODR_AT_7Hz5 = 0x2, - LSM6DSV16X_XL_ODR_AT_15Hz = 0x3, - LSM6DSV16X_XL_ODR_AT_30Hz = 0x4, - LSM6DSV16X_XL_ODR_AT_60Hz = 0x5, - LSM6DSV16X_XL_ODR_AT_120Hz = 0x6, - LSM6DSV16X_XL_ODR_AT_240Hz = 0x7, - LSM6DSV16X_XL_ODR_AT_480Hz = 0x8, - LSM6DSV16X_XL_ODR_AT_960Hz = 0x9, - LSM6DSV16X_XL_ODR_AT_1920Hz = 0xA, - LSM6DSV16X_XL_ODR_AT_3840Hz = 0xB, - LSM6DSV16X_XL_ODR_AT_7680Hz = 0xC, -} lsm6dsv16x_xl_data_rate_t; -int32_t lsm6dsv16x_xl_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_data_rate_t val); -int32_t lsm6dsv16x_xl_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_data_rate_t *val); + LSM6DSV16X_ODR_OFF = 0x0, + LSM6DSV16X_ODR_AT_1Hz875 = 0x1, + LSM6DSV16X_ODR_AT_7Hz5 = 0x2, + LSM6DSV16X_ODR_AT_15Hz = 0x3, + LSM6DSV16X_ODR_AT_30Hz = 0x4, + LSM6DSV16X_ODR_AT_60Hz = 0x5, + LSM6DSV16X_ODR_AT_120Hz = 0x6, + LSM6DSV16X_ODR_AT_240Hz = 0x7, + LSM6DSV16X_ODR_AT_480Hz = 0x8, + LSM6DSV16X_ODR_AT_960Hz = 0x9, + LSM6DSV16X_ODR_AT_1920Hz = 0xA, + LSM6DSV16X_ODR_AT_3840Hz = 0xB, + LSM6DSV16X_ODR_AT_7680Hz = 0xC, + LSM6DSV16X_ODR_HA01_AT_15Hz625 = 0x13, + LSM6DSV16X_ODR_HA01_AT_31Hz25 = 0x14, + LSM6DSV16X_ODR_HA01_AT_62Hz5 = 0x15, + LSM6DSV16X_ODR_HA01_AT_125Hz = 0x16, + LSM6DSV16X_ODR_HA01_AT_250Hz = 0x17, + LSM6DSV16X_ODR_HA01_AT_500Hz = 0x18, + LSM6DSV16X_ODR_HA01_AT_1000Hz = 0x19, + LSM6DSV16X_ODR_HA01_AT_2000Hz = 0x1A, + LSM6DSV16X_ODR_HA01_AT_4000Hz = 0x1B, + LSM6DSV16X_ODR_HA01_AT_8000Hz = 0x1C, + LSM6DSV16X_ODR_HA02_AT_12Hz5 = 0x23, + LSM6DSV16X_ODR_HA02_AT_25Hz = 0x24, + LSM6DSV16X_ODR_HA02_AT_50Hz = 0x25, + LSM6DSV16X_ODR_HA02_AT_100Hz = 0x26, + LSM6DSV16X_ODR_HA02_AT_200Hz = 0x27, + LSM6DSV16X_ODR_HA02_AT_400Hz = 0x28, + LSM6DSV16X_ODR_HA02_AT_800Hz = 0x29, + LSM6DSV16X_ODR_HA02_AT_1600Hz = 0x2A, + LSM6DSV16X_ODR_HA02_AT_3200Hz = 0x2B, + LSM6DSV16X_ODR_HA02_AT_6400Hz = 0x2C, +} lsm6dsv16x_data_rate_t; +int32_t lsm6dsv16x_xl_data_rate_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_data_rate_t val); +int32_t lsm6dsv16x_xl_data_rate_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_data_rate_t *val); +int32_t lsm6dsv16x_gy_data_rate_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_data_rate_t val); +int32_t lsm6dsv16x_gy_data_rate_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_data_rate_t *val); + typedef enum { - LSM6DSV16X_XL_HIGH_PERFORMANCE_MD = 0x0, - LSM6DSV16X_XL_HIGH_ACCURANCY_ODR_MD = 0x1, - LSM6DSV16X_XL_LOW_POWER_2_AVG_MD = 0x4, - LSM6DSV16X_XL_LOW_POWER_4_AVG_MD = 0x5, - LSM6DSV16X_XL_LOW_POWER_8_AVG_MD = 0x6, - LSM6DSV16X_XL_NORMAL_MD = 0x7, + LSM6DSV16X_XL_HIGH_PERFORMANCE_MD = 0x0, + LSM6DSV16X_XL_HIGH_ACCURACY_ODR_MD = 0x1, + LSM6DSV16X_XL_ODR_TRIGGERED_MD = 0x3, + LSM6DSV16X_XL_LOW_POWER_2_AVG_MD = 0x4, + LSM6DSV16X_XL_LOW_POWER_4_AVG_MD = 0x5, + LSM6DSV16X_XL_LOW_POWER_8_AVG_MD = 0x6, + LSM6DSV16X_XL_NORMAL_MD = 0x7, } lsm6dsv16x_xl_mode_t; int32_t lsm6dsv16x_xl_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_mode_t val); int32_t lsm6dsv16x_xl_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_mode_t *val); typedef enum { - LSM6DSV16X_GY_ODR_OFF = 0x0, - LSM6DSV16X_GY_ODR_AT_7Hz5 = 0x2, - LSM6DSV16X_GY_ODR_AT_15Hz = 0x3, - LSM6DSV16X_GY_ODR_AT_30Hz = 0x4, - LSM6DSV16X_GY_ODR_AT_60Hz = 0x5, - LSM6DSV16X_GY_ODR_AT_120Hz = 0x6, - LSM6DSV16X_GY_ODR_AT_240Hz = 0x7, - LSM6DSV16X_GY_ODR_AT_480Hz = 0x8, - LSM6DSV16X_GY_ODR_AT_960Hz = 0x9, - LSM6DSV16X_GY_ODR_AT_1920Hz = 0xa, - LSM6DSV16X_GY_ODR_AT_3840Hz = 0xb, - LSM6DSV16X_GY_ODR_AT_7680Hz = 0xc, -} lsm6dsv16x_gy_data_rate_t; -int32_t lsm6dsv16x_gy_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_data_rate_t val); -int32_t lsm6dsv16x_gy_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_data_rate_t *val); - -typedef enum { - LSM6DSV16X_GY_HIGH_PERFORMANCE_MD = 0x0, - LSM6DSV16X_GY_HIGH_ACCURANCY_ODR_MD = 0x1, - LSM6DSV16X_GY_SLEEP_MD = 0x4, - LSM6DSV16X_GY_LOW_POWER_MD = 0x5, + LSM6DSV16X_GY_HIGH_PERFORMANCE_MD = 0x0, + LSM6DSV16X_GY_HIGH_ACCURACY_ODR_MD = 0x1, + LSM6DSV16X_GY_SLEEP_MD = 0x4, + LSM6DSV16X_GY_LOW_POWER_MD = 0x5, } lsm6dsv16x_gy_mode_t; int32_t lsm6dsv16x_gy_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_mode_t val); int32_t lsm6dsv16x_gy_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_mode_t *val); @@ -3677,134 +3748,197 @@ int32_t lsm6dsv16x_auto_increment_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); int32_t lsm6dsv16x_block_data_update_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_block_data_update_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); +int32_t lsm6dsv16x_odr_trig_cfg_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); +int32_t lsm6dsv16x_odr_trig_cfg_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); + typedef enum { LSM6DSV16X_DRDY_LATCHED = 0x0, - LSM6DSV16X_DRDY_PULSED = 0x1, + LSM6DSV16X_DRDY_PULSED = 0x1, } lsm6dsv16x_data_ready_mode_t; -int32_t lsm6dsv16x_data_ready_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_data_ready_mode_t val); -int32_t lsm6dsv16x_data_ready_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_data_ready_mode_t *val); +int32_t lsm6dsv16x_data_ready_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_data_ready_mode_t val); +int32_t lsm6dsv16x_data_ready_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_data_ready_mode_t *val); + +typedef struct { + uint8_t enable : 1; /* interrupt enable */ + uint8_t lir : 1; /* interrupt pulsed or latched */ +} lsm6dsv16x_interrupt_mode_t; +int32_t lsm6dsv16x_interrupt_enable_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_interrupt_mode_t val); +int32_t lsm6dsv16x_interrupt_enable_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_interrupt_mode_t *val); typedef enum { - LSM6DSV16X_125dps = 0x0, - LSM6DSV16X_250dps = 0x1, - LSM6DSV16X_500dps = 0x2, + LSM6DSV16X_125dps = 0x0, + LSM6DSV16X_250dps = 0x1, + LSM6DSV16X_500dps = 0x2, LSM6DSV16X_1000dps = 0x3, LSM6DSV16X_2000dps = 0x4, LSM6DSV16X_4000dps = 0x5, } lsm6dsv16x_gy_full_scale_t; -int32_t lsm6dsv16x_gy_full_scale_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_full_scale_t val); -int32_t lsm6dsv16x_gy_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_full_scale_t *val); +int32_t lsm6dsv16x_gy_full_scale_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_gy_full_scale_t val); +int32_t lsm6dsv16x_gy_full_scale_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_gy_full_scale_t *val); typedef enum { - LSM6DSV16X_2g = 0x0, - LSM6DSV16X_4g = 0x1, - LSM6DSV16X_8g = 0x2, + LSM6DSV16X_2g = 0x0, + LSM6DSV16X_4g = 0x1, + LSM6DSV16X_8g = 0x2, LSM6DSV16X_16g = 0x3, } lsm6dsv16x_xl_full_scale_t; -int32_t lsm6dsv16x_xl_full_scale_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_full_scale_t val); -int32_t lsm6dsv16x_xl_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_full_scale_t *val); +int32_t lsm6dsv16x_xl_full_scale_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_full_scale_t val); +int32_t lsm6dsv16x_xl_full_scale_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_full_scale_t *val); int32_t lsm6dsv16x_xl_dual_channel_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_xl_dual_channel_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef enum { - LSM6DSV16X_XL_ST_DISABLE = 0x0, + LSM6DSV16X_XL_ST_DISABLE = 0x0, LSM6DSV16X_XL_ST_POSITIVE = 0x1, LSM6DSV16X_XL_ST_NEGATIVE = 0x2, } lsm6dsv16x_xl_self_test_t; -int32_t lsm6dsv16x_xl_self_test_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_self_test_t val); -int32_t lsm6dsv16x_xl_self_test_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_self_test_t *val); +int32_t lsm6dsv16x_xl_self_test_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_self_test_t val); +int32_t lsm6dsv16x_xl_self_test_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_self_test_t *val); typedef enum { - LSM6DSV16X_OIS_XL_ST_DISABLE = 0x0, + LSM6DSV16X_OIS_XL_ST_DISABLE = 0x0, LSM6DSV16X_OIS_XL_ST_POSITIVE = 0x1, LSM6DSV16X_OIS_XL_ST_NEGATIVE = 0x2, } lsm6dsv16x_ois_xl_self_test_t; -int32_t lsm6dsv16x_ois_xl_self_test_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_xl_self_test_t val); -int32_t lsm6dsv16x_ois_xl_self_test_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_xl_self_test_t *val); +int32_t lsm6dsv16x_ois_xl_self_test_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_xl_self_test_t val); +int32_t lsm6dsv16x_ois_xl_self_test_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_xl_self_test_t *val); typedef enum { - LSM6DSV16X_GY_ST_DISABLE = 0x0, + LSM6DSV16X_GY_ST_DISABLE = 0x0, LSM6DSV16X_GY_ST_POSITIVE = 0x1, LSM6DSV16X_GY_ST_NEGATIVE = 0x2, } lsm6dsv16x_gy_self_test_t; -int32_t lsm6dsv16x_gy_self_test_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_self_test_t val); -int32_t lsm6dsv16x_gy_self_test_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_self_test_t *val); +int32_t lsm6dsv16x_gy_self_test_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_gy_self_test_t val); +int32_t lsm6dsv16x_gy_self_test_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_gy_self_test_t *val); typedef enum { - LSM6DSV16X_OIS_GY_ST_DISABLE = 0x0, - LSM6DSV16X_OIS_GY_ST_POSITIVE = 0x1, - LSM6DSV16X_OIS_GY_ST_NEGATIVE = 0x2, + LSM6DSV16X_OIS_GY_ST_DISABLE = 0x0, + LSM6DSV16X_OIS_GY_ST_POSITIVE = 0x1, + LSM6DSV16X_OIS_GY_ST_NEGATIVE = 0x2, LSM6DSV16X_OIS_GY_ST_CLAMP_POS = 0x5, LSM6DSV16X_OIS_GY_ST_CLAMP_NEG = 0x6, } lsm6dsv16x_ois_gy_self_test_t; -int32_t lsm6dsv16x_ois_gy_self_test_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_gy_self_test_t val); -int32_t lsm6dsv16x_ois_gy_self_test_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_gy_self_test_t *val); - -typedef struct { - uint8_t drdy_xl : 1; - uint8_t drdy_gy : 1; - uint8_t drdy_temp : 1; - uint8_t drdy_ah_qvar : 1; - uint8_t drdy_eis : 1; - uint8_t drdy_ois : 1; - uint8_t gy_settling : 1; - uint8_t timestamp : 1; - uint8_t free_fall : 1; - uint8_t wake_up : 1; - uint8_t wake_up_z : 1; - uint8_t wake_up_y : 1; - uint8_t wake_up_x : 1; - uint8_t single_tap : 1; - uint8_t double_tap : 1; - uint8_t tap_z : 1; - uint8_t tap_y : 1; - uint8_t tap_x : 1; - uint8_t tap_sign : 1; - uint8_t six_d : 1; - uint8_t six_d_xl : 1; - uint8_t six_d_xh : 1; - uint8_t six_d_yl : 1; - uint8_t six_d_yh : 1; - uint8_t six_d_zl : 1; - uint8_t six_d_zh : 1; - uint8_t sleep_change : 1; - uint8_t sleep_state : 1; - uint8_t step_detector : 1; - uint8_t step_count_inc : 1; - uint8_t step_count_overflow : 1; - uint8_t step_on_delta_time : 1; - uint8_t emb_func_stand_by : 1; +int32_t lsm6dsv16x_ois_gy_self_test_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_gy_self_test_t val); +int32_t lsm6dsv16x_ois_gy_self_test_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_gy_self_test_t *val); + +typedef struct { + uint8_t drdy_xl : 1; + uint8_t drdy_gy : 1; + uint8_t drdy_temp : 1; + uint8_t drdy_ah_qvar : 1; + uint8_t drdy_eis : 1; + uint8_t drdy_ois : 1; + uint8_t gy_settling : 1; + uint8_t timestamp : 1; + uint8_t free_fall : 1; + uint8_t wake_up : 1; + uint8_t wake_up_z : 1; + uint8_t wake_up_y : 1; + uint8_t wake_up_x : 1; + uint8_t single_tap : 1; + uint8_t double_tap : 1; + uint8_t tap_z : 1; + uint8_t tap_y : 1; + uint8_t tap_x : 1; + uint8_t tap_sign : 1; + uint8_t six_d : 1; + uint8_t six_d_xl : 1; + uint8_t six_d_xh : 1; + uint8_t six_d_yl : 1; + uint8_t six_d_yh : 1; + uint8_t six_d_zl : 1; + uint8_t six_d_zh : 1; + uint8_t sleep_change : 1; + uint8_t sleep_state : 1; + uint8_t step_detector : 1; + uint8_t step_count_inc : 1; + uint8_t step_count_overflow : 1; + uint8_t step_on_delta_time : 1; + uint8_t emb_func_stand_by : 1; uint8_t emb_func_time_exceed : 1; - uint8_t tilt : 1; - uint8_t sig_mot : 1; - uint8_t fsm_lc : 1; - uint8_t fsm1 : 1; - uint8_t fsm2 : 1; - uint8_t fsm3 : 1; - uint8_t fsm4 : 1; - uint8_t fsm5 : 1; - uint8_t fsm6 : 1; - uint8_t fsm7 : 1; - uint8_t fsm8 : 1; - uint8_t mlc1 : 1; - uint8_t mlc2 : 1; - uint8_t mlc3 : 1; - uint8_t mlc4 : 1; - uint8_t sh_endop : 1; - uint8_t sh_slave0_nack : 1; - uint8_t sh_slave1_nack : 1; - uint8_t sh_slave2_nack : 1; - uint8_t sh_slave3_nack : 1; - uint8_t sh_wr_once : 1; - uint8_t fifo_bdr : 1; - uint8_t fifo_full : 1; - uint8_t fifo_ovr : 1; - uint8_t fifo_th : 1; + uint8_t tilt : 1; + uint8_t sig_mot : 1; + uint8_t fsm_lc : 1; + uint8_t fsm1 : 1; + uint8_t fsm2 : 1; + uint8_t fsm3 : 1; + uint8_t fsm4 : 1; + uint8_t fsm5 : 1; + uint8_t fsm6 : 1; + uint8_t fsm7 : 1; + uint8_t fsm8 : 1; + uint8_t mlc1 : 1; + uint8_t mlc2 : 1; + uint8_t mlc3 : 1; + uint8_t mlc4 : 1; + uint8_t sh_endop : 1; + uint8_t sh_slave0_nack : 1; + uint8_t sh_slave1_nack : 1; + uint8_t sh_slave2_nack : 1; + uint8_t sh_slave3_nack : 1; + uint8_t sh_wr_once : 1; + uint8_t fifo_bdr : 1; + uint8_t fifo_full : 1; + uint8_t fifo_ovr : 1; + uint8_t fifo_th : 1; } lsm6dsv16x_all_sources_t; -int32_t lsm6dsv16x_all_sources_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_all_sources_t *val); +int32_t lsm6dsv16x_all_sources_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_all_sources_t *val); + +typedef struct { + uint8_t drdy_xl : 1; + uint8_t drdy_g : 1; + uint8_t drdy_g_eis : 1; + uint8_t fifo_th : 1; + uint8_t fifo_ovr : 1; + uint8_t fifo_full : 1; + uint8_t cnt_bdr : 1; + uint8_t emb_func_endop : 1; + uint8_t timestamp : 1; + uint8_t shub : 1; + uint8_t emb_func : 1; + uint8_t sixd : 1; + uint8_t single_tap : 1; + uint8_t double_tap : 1; + uint8_t wakeup : 1; + uint8_t freefall : 1; + uint8_t sleep_change : 1; +} lsm6dsv16x_pin_int_route_t; +int32_t lsm6dsv16x_pin_int1_route_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_pin_int_route_t *val); +int32_t lsm6dsv16x_pin_int1_route_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_pin_int_route_t *val); +int32_t lsm6dsv16x_pin_int2_route_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_pin_int_route_t *val); +int32_t lsm6dsv16x_pin_int2_route_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_pin_int_route_t *val); + +typedef struct { + uint8_t drdy_xl : 1; + uint8_t drdy_gy : 1; + uint8_t drdy_temp : 1; +} lsm6dsv16x_data_ready_t; +int32_t lsm6dsv16x_flag_data_ready_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_data_ready_t *val); int32_t lsm6dsv16x_int_ack_mask_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_int_ack_mask_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); @@ -3815,63 +3949,76 @@ int32_t lsm6dsv16x_angular_rate_raw_get(lsm6dsv16x_ctx_t *ctx, int16_t *val); int32_t lsm6dsv16x_ois_angular_rate_raw_get(lsm6dsv16x_ctx_t *ctx, int16_t *val); -int32_t lsm6dsv16x_ois_eis_angular_rate_raw_get(lsm6dsv16x_ctx_t *ctx, int16_t *val); +int32_t lsm6dsv16x_ois_eis_angular_rate_raw_get(lsm6dsv16x_ctx_t *ctx, + int16_t *val); int32_t lsm6dsv16x_acceleration_raw_get(lsm6dsv16x_ctx_t *ctx, int16_t *val); int32_t lsm6dsv16x_dual_acceleration_raw_get(lsm6dsv16x_ctx_t *ctx, int16_t *val); -int32_t lsm6dsv16x_ois_dual_acceleration_raw_get(lsm6dsv16x_ctx_t *ctx, int16_t *val); +int32_t lsm6dsv16x_ois_dual_acceleration_raw_get(lsm6dsv16x_ctx_t *ctx, + int16_t *val); int32_t lsm6dsv16x_ah_qvar_raw_get(lsm6dsv16x_ctx_t *ctx, int16_t *val); int32_t lsm6dsv16x_odr_cal_reg_get(lsm6dsv16x_ctx_t *ctx, int8_t *val); -int32_t lsm6dsv16x_ln_pg_write(lsm6dsv16x_ctx_t *ctx, uint16_t address, uint8_t *buf, uint8_t len); -int32_t lsm6dsv16x_ln_pg_read(lsm6dsv16x_ctx_t *ctx, uint16_t address, uint8_t *buf, uint8_t len); +int32_t lsm6dsv16x_ln_pg_write(lsm6dsv16x_ctx_t *ctx, uint16_t address, + uint8_t *buf, uint8_t len); +int32_t lsm6dsv16x_ln_pg_read(lsm6dsv16x_ctx_t *ctx, uint16_t address, uint8_t *buf, + uint8_t len); + +int32_t lsm6dsv16x_emb_function_dbg_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); +int32_t lsm6dsv16x_emb_function_dbg_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef enum { - LSM6DSV16X_DEN_ACT_LOW = 0x0, + LSM6DSV16X_DEN_ACT_LOW = 0x0, LSM6DSV16X_DEN_ACT_HIGH = 0x1, } lsm6dsv16x_den_polarity_t; -int32_t lsm6dsv16x_den_polarity_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_den_polarity_t val); -int32_t lsm6dsv16x_den_polarity_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_den_polarity_t *val); +int32_t lsm6dsv16x_den_polarity_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_den_polarity_t val); +int32_t lsm6dsv16x_den_polarity_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_den_polarity_t *val); typedef struct { - uint8_t stamp_in_gy_data : 1; - uint8_t stamp_in_xl_data : 1; - uint8_t den_x : 1; - uint8_t den_y : 1; - uint8_t den_z : 1; + uint8_t stamp_in_gy_data : 1; + uint8_t stamp_in_xl_data : 1; + uint8_t den_x : 1; + uint8_t den_y : 1; + uint8_t den_z : 1; enum { DEN_NOT_DEFINED = 0x00, - LEVEL_TRIGGER = 0x02, - LEVEL_LETCHED = 0x03, + LEVEL_TRIGGER = 0x02, + LEVEL_LATCHED = 0x03, } mode; } lsm6dsv16x_den_conf_t; int32_t lsm6dsv16x_den_conf_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_den_conf_t val); int32_t lsm6dsv16x_den_conf_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_den_conf_t *val); typedef enum { - LSM6DSV16X_EIS_125dps = 0x0, - LSM6DSV16X_EIS_250dps = 0x1, - LSM6DSV16X_EIS_500dps = 0x2, + LSM6DSV16X_EIS_125dps = 0x0, + LSM6DSV16X_EIS_250dps = 0x1, + LSM6DSV16X_EIS_500dps = 0x2, LSM6DSV16X_EIS_1000dps = 0x3, LSM6DSV16X_EIS_2000dps = 0x4, } lsm6dsv16x_eis_gy_full_scale_t; -int32_t lsm6dsv16x_eis_gy_full_scale_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_eis_gy_full_scale_t val); -int32_t lsm6dsv16x_eis_gy_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_eis_gy_full_scale_t *val); +int32_t lsm6dsv16x_eis_gy_full_scale_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_eis_gy_full_scale_t val); +int32_t lsm6dsv16x_eis_gy_full_scale_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_eis_gy_full_scale_t *val); int32_t lsm6dsv16x_eis_gy_on_spi2_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_eis_gy_on_spi2_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef enum { LSM6DSV16X_EIS_ODR_OFF = 0x0, - LSM6DSV16X_EIS_1920Hz = 0x1, - LSM6DSV16X_EIS_960Hz = 0x2, + LSM6DSV16X_EIS_1920Hz = 0x1, + LSM6DSV16X_EIS_960Hz = 0x2, } lsm6dsv16x_gy_eis_data_rate_t; -int32_t lsm6dsv16x_gy_eis_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_eis_data_rate_t val); -int32_t lsm6dsv16x_gy_eis_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_gy_eis_data_rate_t *val); +int32_t lsm6dsv16x_gy_eis_data_rate_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_gy_eis_data_rate_t val); +int32_t lsm6dsv16x_gy_eis_data_rate_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_gy_eis_data_rate_t *val); int32_t lsm6dsv16x_fifo_watermark_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_fifo_watermark_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); @@ -3881,136 +4028,168 @@ int32_t lsm6dsv16x_fifo_xl_dual_fsm_batch_get(lsm6dsv16x_ctx_t *ctx, uint8_t *va typedef enum { LSM6DSV16X_CMP_DISABLE = 0x0, - LSM6DSV16X_CMP_8_TO_1 = 0x1, + LSM6DSV16X_CMP_8_TO_1 = 0x1, LSM6DSV16X_CMP_16_TO_1 = 0x2, LSM6DSV16X_CMP_32_TO_1 = 0x3, } lsm6dsv16x_fifo_compress_algo_t; -int32_t lsm6dsv16x_fifo_compress_algo_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_compress_algo_t val); -int32_t lsm6dsv16x_fifo_compress_algo_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_compress_algo_t *val); +int32_t lsm6dsv16x_fifo_compress_algo_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_compress_algo_t val); +int32_t lsm6dsv16x_fifo_compress_algo_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_compress_algo_t *val); -int32_t lsm6dsv16x_fifo_virtual_sens_odr_chg_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); -int32_t lsm6dsv16x_fifo_virtual_sens_odr_chg_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); +int32_t lsm6dsv16x_fifo_virtual_sens_odr_chg_set(lsm6dsv16x_ctx_t *ctx, + uint8_t val); +int32_t lsm6dsv16x_fifo_virtual_sens_odr_chg_get(lsm6dsv16x_ctx_t *ctx, + uint8_t *val); -int32_t lsm6dsv16x_fifo_compress_algo_real_time_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); -int32_t lsm6dsv16x_fifo_compress_algo_real_time_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); +int32_t lsm6dsv16x_fifo_compress_algo_real_time_set(lsm6dsv16x_ctx_t *ctx, + uint8_t val); +int32_t lsm6dsv16x_fifo_compress_algo_real_time_get(lsm6dsv16x_ctx_t *ctx, + uint8_t *val); int32_t lsm6dsv16x_fifo_stop_on_wtm_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_fifo_stop_on_wtm_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef enum { - LSM6DSV16X_XL_NOT_BATCHED = 0x0, + LSM6DSV16X_XL_NOT_BATCHED = 0x0, LSM6DSV16X_XL_BATCHED_AT_1Hz875 = 0x1, - LSM6DSV16X_XL_BATCHED_AT_7Hz5 = 0x2, - LSM6DSV16X_XL_BATCHED_AT_15Hz = 0x3, - LSM6DSV16X_XL_BATCHED_AT_30Hz = 0x4, - LSM6DSV16X_XL_BATCHED_AT_60Hz = 0x5, - LSM6DSV16X_XL_BATCHED_AT_120Hz = 0x6, - LSM6DSV16X_XL_BATCHED_AT_240Hz = 0x7, - LSM6DSV16X_XL_BATCHED_AT_480Hz = 0x8, - LSM6DSV16X_XL_BATCHED_AT_960Hz = 0x9, + LSM6DSV16X_XL_BATCHED_AT_7Hz5 = 0x2, + LSM6DSV16X_XL_BATCHED_AT_15Hz = 0x3, + LSM6DSV16X_XL_BATCHED_AT_30Hz = 0x4, + LSM6DSV16X_XL_BATCHED_AT_60Hz = 0x5, + LSM6DSV16X_XL_BATCHED_AT_120Hz = 0x6, + LSM6DSV16X_XL_BATCHED_AT_240Hz = 0x7, + LSM6DSV16X_XL_BATCHED_AT_480Hz = 0x8, + LSM6DSV16X_XL_BATCHED_AT_960Hz = 0x9, LSM6DSV16X_XL_BATCHED_AT_1920Hz = 0xa, LSM6DSV16X_XL_BATCHED_AT_3840Hz = 0xb, LSM6DSV16X_XL_BATCHED_AT_7680Hz = 0xc, } lsm6dsv16x_fifo_xl_batch_t; -int32_t lsm6dsv16x_fifo_xl_batch_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_xl_batch_t val); -int32_t lsm6dsv16x_fifo_xl_batch_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_xl_batch_t *val); +int32_t lsm6dsv16x_fifo_xl_batch_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_xl_batch_t val); +int32_t lsm6dsv16x_fifo_xl_batch_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_xl_batch_t *val); typedef enum { - LSM6DSV16X_GY_NOT_BATCHED = 0x0, + LSM6DSV16X_GY_NOT_BATCHED = 0x0, LSM6DSV16X_GY_BATCHED_AT_1Hz875 = 0x1, - LSM6DSV16X_GY_BATCHED_AT_7Hz5 = 0x2, - LSM6DSV16X_GY_BATCHED_AT_15Hz = 0x3, - LSM6DSV16X_GY_BATCHED_AT_30Hz = 0x4, - LSM6DSV16X_GY_BATCHED_AT_60Hz = 0x5, - LSM6DSV16X_GY_BATCHED_AT_120Hz = 0x6, - LSM6DSV16X_GY_BATCHED_AT_240Hz = 0x7, - LSM6DSV16X_GY_BATCHED_AT_480Hz = 0x8, - LSM6DSV16X_GY_BATCHED_AT_960Hz = 0x9, + LSM6DSV16X_GY_BATCHED_AT_7Hz5 = 0x2, + LSM6DSV16X_GY_BATCHED_AT_15Hz = 0x3, + LSM6DSV16X_GY_BATCHED_AT_30Hz = 0x4, + LSM6DSV16X_GY_BATCHED_AT_60Hz = 0x5, + LSM6DSV16X_GY_BATCHED_AT_120Hz = 0x6, + LSM6DSV16X_GY_BATCHED_AT_240Hz = 0x7, + LSM6DSV16X_GY_BATCHED_AT_480Hz = 0x8, + LSM6DSV16X_GY_BATCHED_AT_960Hz = 0x9, LSM6DSV16X_GY_BATCHED_AT_1920Hz = 0xa, LSM6DSV16X_GY_BATCHED_AT_3840Hz = 0xb, LSM6DSV16X_GY_BATCHED_AT_7680Hz = 0xc, } lsm6dsv16x_fifo_gy_batch_t; -int32_t lsm6dsv16x_fifo_gy_batch_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_gy_batch_t val); -int32_t lsm6dsv16x_fifo_gy_batch_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_gy_batch_t *val); +int32_t lsm6dsv16x_fifo_gy_batch_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_gy_batch_t val); +int32_t lsm6dsv16x_fifo_gy_batch_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_gy_batch_t *val); typedef enum { - LSM6DSV16X_BYPASS_MODE = 0x0, - LSM6DSV16X_FIFO_MODE = 0x1, + LSM6DSV16X_BYPASS_MODE = 0x0, + LSM6DSV16X_FIFO_MODE = 0x1, LSM6DSV16X_STREAM_WTM_TO_FULL_MODE = 0x2, - LSM6DSV16X_STREAM_TO_FIFO_MODE = 0x3, - LSM6DSV16X_BYPASS_TO_STREAM_MODE = 0x4, - LSM6DSV16X_STREAM_MODE = 0x6, - LSM6DSV16X_BYPASS_TO_FIFO_MODE = 0x7, + LSM6DSV16X_STREAM_TO_FIFO_MODE = 0x3, + LSM6DSV16X_BYPASS_TO_STREAM_MODE = 0x4, + LSM6DSV16X_STREAM_MODE = 0x6, + LSM6DSV16X_BYPASS_TO_FIFO_MODE = 0x7, } lsm6dsv16x_fifo_mode_t; int32_t lsm6dsv16x_fifo_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_mode_t val); -int32_t lsm6dsv16x_fifo_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_mode_t *val); +int32_t lsm6dsv16x_fifo_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_mode_t *val); int32_t lsm6dsv16x_fifo_gy_eis_batch_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_fifo_gy_eis_batch_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef enum { - LSM6DSV16X_TEMP_NOT_BATCHED = 0x0, + LSM6DSV16X_TEMP_NOT_BATCHED = 0x0, LSM6DSV16X_TEMP_BATCHED_AT_1Hz875 = 0x1, - LSM6DSV16X_TEMP_BATCHED_AT_15Hz = 0x2, - LSM6DSV16X_TEMP_BATCHED_AT_60Hz = 0x3, + LSM6DSV16X_TEMP_BATCHED_AT_15Hz = 0x2, + LSM6DSV16X_TEMP_BATCHED_AT_60Hz = 0x3, } lsm6dsv16x_fifo_temp_batch_t; -int32_t lsm6dsv16x_fifo_temp_batch_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_temp_batch_t val); -int32_t lsm6dsv16x_fifo_temp_batch_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_temp_batch_t *val); +int32_t lsm6dsv16x_fifo_temp_batch_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_temp_batch_t val); +int32_t lsm6dsv16x_fifo_temp_batch_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_temp_batch_t *val); typedef enum { LSM6DSV16X_TMSTMP_NOT_BATCHED = 0x0, - LSM6DSV16X_TMSTMP_DEC_1 = 0x1, - LSM6DSV16X_TMSTMP_DEC_8 = 0x2, - LSM6DSV16X_TMSTMP_DEC_32 = 0x3, + LSM6DSV16X_TMSTMP_DEC_1 = 0x1, + LSM6DSV16X_TMSTMP_DEC_8 = 0x2, + LSM6DSV16X_TMSTMP_DEC_32 = 0x3, } lsm6dsv16x_fifo_timestamp_batch_t; -int32_t lsm6dsv16x_fifo_timestamp_batch_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_timestamp_batch_t val); -int32_t lsm6dsv16x_fifo_timestamp_batch_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_timestamp_batch_t *val); +int32_t lsm6dsv16x_fifo_timestamp_batch_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_timestamp_batch_t val); +int32_t lsm6dsv16x_fifo_timestamp_batch_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_timestamp_batch_t *val); -int32_t lsm6dsv16x_fifo_batch_counter_threshold_set(lsm6dsv16x_ctx_t *ctx, uint16_t val); -int32_t lsm6dsv16x_fifo_batch_counter_threshold_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val); +int32_t lsm6dsv16x_fifo_batch_counter_threshold_set(lsm6dsv16x_ctx_t *ctx, + uint16_t val); +int32_t lsm6dsv16x_fifo_batch_counter_threshold_get(lsm6dsv16x_ctx_t *ctx, + uint16_t *val); typedef enum { - LSM6DSV16X_XL_BATCH_EVENT = 0x0, - LSM6DSV16X_GY_BATCH_EVENT = 0x1, + LSM6DSV16X_XL_BATCH_EVENT = 0x0, + LSM6DSV16X_GY_BATCH_EVENT = 0x1, LSM6DSV16X_GY_EIS_BATCH_EVENT = 0x2, } lsm6dsv16x_fifo_batch_cnt_event_t; -int32_t lsm6dsv16x_fifo_batch_cnt_event_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_batch_cnt_event_t val); -int32_t lsm6dsv16x_fifo_batch_cnt_event_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_batch_cnt_event_t *val); +int32_t lsm6dsv16x_fifo_batch_cnt_event_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_batch_cnt_event_t val); +int32_t lsm6dsv16x_fifo_batch_cnt_event_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_batch_cnt_event_t *val); + +typedef struct { + uint16_t fifo_level : 9; + uint8_t fifo_bdr : 1; + uint8_t fifo_full : 1; + uint8_t fifo_ovr : 1; + uint8_t fifo_th : 1; +} lsm6dsv16x_fifo_status_t; -int32_t lsm6dsv16x_fifo_data_level_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val); +int32_t lsm6dsv16x_fifo_status_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_status_t *val); typedef struct { enum { - LSM6DSV16X_FIFO_EMPTY = 0x0, - LSM6DSV16X_GY_NC_TAG = 0x1, - LSM6DSV16X_XL_NC_TAG = 0x2, - LSM6DSV16X_TEMPERATURE_TAG = 0x3, - LSM6DSV16X_TIMESTAMP_TAG = 0x4, - LSM6DSV16X_CFG_CHANGE_TAG = 0x5, - LSM6DSV16X_XL_NC_T_2_TAG = 0x6, - LSM6DSV16X_XL_NC_T_1_TAG = 0x7, - LSM6DSV16X_XL_2XC_TAG = 0x8, - LSM6DSV16X_XL_3XC_TAG = 0x9, - LSM6DSV16X_GY_NC_T_2_TAG = 0xA, - LSM6DSV16X_GY_NC_T_1_TAG = 0xB, - LSM6DSV16X_GY_2XC_TAG = 0xC, - LSM6DSV16X_GY_3XC_TAG = 0xD, - LSM6DSV16X_SENSORHUB_SLAVE0_TAG = 0xE, - LSM6DSV16X_SENSORHUB_SLAVE1_TAG = 0xF, - LSM6DSV16X_SENSORHUB_SLAVE2_TAG = 0x10, - LSM6DSV16X_SENSORHUB_SLAVE3_TAG = 0x11, - LSM6DSV16X_STEP_CPUNTER_TAG = 0x12, - LSM6DSV16X_SENSORHUB_NACK_TAG = 0x19, - LSM6DSV16X_MLC_RESULT_TAG = 0x1A, - LSM6DSV16X_MLC_FILTER = 0x1B, - LSM6DSV16X_MLC_FEATURE = 0x1C, - LSM6DSV16X_XL_DUAL_CORE = 0x1D, - LSM6DSV16X_AH_QVAR = 0x1F, + LSM6DSV16X_FIFO_EMPTY = 0x0, + LSM6DSV16X_GY_NC_TAG = 0x1, + LSM6DSV16X_XL_NC_TAG = 0x2, + LSM6DSV16X_TEMPERATURE_TAG = 0x3, + LSM6DSV16X_TIMESTAMP_TAG = 0x4, + LSM6DSV16X_CFG_CHANGE_TAG = 0x5, + LSM6DSV16X_XL_NC_T_2_TAG = 0x6, + LSM6DSV16X_XL_NC_T_1_TAG = 0x7, + LSM6DSV16X_XL_2XC_TAG = 0x8, + LSM6DSV16X_XL_3XC_TAG = 0x9, + LSM6DSV16X_GY_NC_T_2_TAG = 0xA, + LSM6DSV16X_GY_NC_T_1_TAG = 0xB, + LSM6DSV16X_GY_2XC_TAG = 0xC, + LSM6DSV16X_GY_3XC_TAG = 0xD, + LSM6DSV16X_SENSORHUB_SLAVE0_TAG = 0xE, + LSM6DSV16X_SENSORHUB_SLAVE1_TAG = 0xF, + LSM6DSV16X_SENSORHUB_SLAVE2_TAG = 0x10, + LSM6DSV16X_SENSORHUB_SLAVE3_TAG = 0x11, + LSM6DSV16X_STEP_COUNTER_TAG = 0x12, + LSM6DSV16X_SFLP_GAME_ROTATION_VECTOR_TAG = 0x13, + LSM6DSV16X_SFLP_GYROSCOPE_BIAS_TAG = 0x16, + LSM6DSV16X_SFLP_GRAVITY_VECTOR_TAG = 0x17, + LSM6DSV16X_SENSORHUB_NACK_TAG = 0x19, + LSM6DSV16X_MLC_RESULT_TAG = 0x1A, + LSM6DSV16X_MLC_FILTER = 0x1B, + LSM6DSV16X_MLC_FEATURE = 0x1C, + LSM6DSV16X_XL_DUAL_CORE = 0x1D, + LSM6DSV16X_GY_ENHANCED_EIS = 0x1E, } tag; uint8_t cnt; uint8_t data[6]; } lsm6dsv16x_fifo_out_raw_t; -int32_t lsm6dsv16x_fifo_out_raw_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fifo_out_raw_t *val); +int32_t lsm6dsv16x_fifo_out_raw_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_out_raw_t *val); int32_t lsm6dsv16x_fifo_stpcnt_batch_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_fifo_stpcnt_batch_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); @@ -4021,68 +4200,79 @@ int32_t lsm6dsv16x_fifo_mlc_batch_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); int32_t lsm6dsv16x_fifo_mlc_filt_batch_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_fifo_mlc_filt_batch_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); -int32_t lsm6dsv16x_fifo_batch_sh_slave_0_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); -int32_t lsm6dsv16x_fifo_batch_sh_slave_0_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); +int32_t lsm6dsv16x_fifo_sh_batch_slave_set(lsm6dsv16x_ctx_t *ctx, uint8_t idx, uint8_t val); +int32_t lsm6dsv16x_fifo_sh_batch_slave_get(lsm6dsv16x_ctx_t *ctx, uint8_t idx, uint8_t *val); -int32_t lsm6dsv16x_fifo_batch_sh_slave_1_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); -int32_t lsm6dsv16x_fifo_batch_sh_slave_1_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); - -int32_t lsm6dsv16x_fifo_batch_sh_slave_2_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); -int32_t lsm6dsv16x_fifo_batch_sh_slave_2_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); - -int32_t lsm6dsv16x_fifo_batch_sh_slave_3_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); -int32_t lsm6dsv16x_fifo_batch_sh_slave_3_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); +typedef struct { + uint8_t game_rotation : 1; + uint8_t gravity : 1; + uint8_t gbias : 1; +} lsm6dsv16x_fifo_sflp_raw_t; +int32_t lsm6dsv16x_fifo_sflp_batch_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_sflp_raw_t val); +int32_t lsm6dsv16x_fifo_sflp_batch_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fifo_sflp_raw_t *val); typedef enum { - LSM6DSV16X_AUTO = 0x0, + LSM6DSV16X_AUTO = 0x0, LSM6DSV16X_ALWAYS_ACTIVE = 0x1, } lsm6dsv16x_filt_anti_spike_t; -int32_t lsm6dsv16x_filt_anti_spike_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_anti_spike_t val); -int32_t lsm6dsv16x_filt_anti_spike_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_anti_spike_t *val); +int32_t lsm6dsv16x_filt_anti_spike_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_anti_spike_t val); +int32_t lsm6dsv16x_filt_anti_spike_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_anti_spike_t *val); typedef struct { - uint8_t drdy : 1; - uint8_t ois_drdy : 1; - uint8_t irq_xl : 1; - uint8_t irq_g : 1; + uint8_t drdy : 1; + uint8_t ois_drdy : 1; + uint8_t irq_xl : 1; + uint8_t irq_g : 1; } lsm6dsv16x_filt_settling_mask_t; -int32_t lsm6dsv16x_filt_settling_mask_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_settling_mask_t val); -int32_t lsm6dsv16x_filt_settling_mask_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_settling_mask_t *val); +int32_t lsm6dsv16x_filt_settling_mask_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_settling_mask_t val); +int32_t lsm6dsv16x_filt_settling_mask_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_settling_mask_t *val); typedef struct { - uint8_t ois_drdy : 1; + uint8_t ois_drdy : 1; } lsm6dsv16x_filt_ois_settling_mask_t; -int32_t lsm6dsv16x_filt_ois_settling_mask_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_ois_settling_mask_t val); -int32_t lsm6dsv16x_filt_ois_settling_mask_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_ois_settling_mask_t *val); +int32_t lsm6dsv16x_filt_ois_settling_mask_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_ois_settling_mask_t val); +int32_t lsm6dsv16x_filt_ois_settling_mask_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_ois_settling_mask_t *val); typedef enum { - LSM6DSV16X_GY_ULTRA_LIGHT = 0x0, - LSM6DSV16X_GY_VERY_LIGHT = 0x1, - LSM6DSV16X_GY_LIGHT = 0x2, - LSM6DSV16X_GY_MEDIUM = 0x3, - LSM6DSV16X_GY_STRONG = 0x4, - LSM6DSV16X_GY_VERY_STRONG = 0x5, - LSM6DSV16X_GY_AGGRESSIVE = 0x6, - LSM6DSV16X_GY_XTREME = 0x7, + LSM6DSV16X_GY_ULTRA_LIGHT = 0x0, + LSM6DSV16X_GY_VERY_LIGHT = 0x1, + LSM6DSV16X_GY_LIGHT = 0x2, + LSM6DSV16X_GY_MEDIUM = 0x3, + LSM6DSV16X_GY_STRONG = 0x4, + LSM6DSV16X_GY_VERY_STRONG = 0x5, + LSM6DSV16X_GY_AGGRESSIVE = 0x6, + LSM6DSV16X_GY_XTREME = 0x7, } lsm6dsv16x_filt_gy_lp1_bandwidth_t; -int32_t lsm6dsv16x_filt_gy_lp1_bandwidth_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_gy_lp1_bandwidth_t val); -int32_t lsm6dsv16x_filt_gy_lp1_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_gy_lp1_bandwidth_t *val); +int32_t lsm6dsv16x_filt_gy_lp1_bandwidth_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_gy_lp1_bandwidth_t val); +int32_t lsm6dsv16x_filt_gy_lp1_bandwidth_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_gy_lp1_bandwidth_t *val); int32_t lsm6dsv16x_filt_gy_lp1_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_filt_gy_lp1_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef enum { LSM6DSV16X_XL_ULTRA_LIGHT = 0x0, - LSM6DSV16X_XL_VERY_LIGHT = 0x1, - LSM6DSV16X_XL_LIGHT = 0x2, - LSM6DSV16X_XL_MEDIUM = 0x3, - LSM6DSV16X_XL_STRONG = 0x4, + LSM6DSV16X_XL_VERY_LIGHT = 0x1, + LSM6DSV16X_XL_LIGHT = 0x2, + LSM6DSV16X_XL_MEDIUM = 0x3, + LSM6DSV16X_XL_STRONG = 0x4, LSM6DSV16X_XL_VERY_STRONG = 0x5, - LSM6DSV16X_XL_AGGRESSIVE = 0x6, - LSM6DSV16X_XL_XTREME = 0x7, + LSM6DSV16X_XL_AGGRESSIVE = 0x6, + LSM6DSV16X_XL_XTREME = 0x7, } lsm6dsv16x_filt_xl_lp2_bandwidth_t; -int32_t lsm6dsv16x_filt_xl_lp2_bandwidth_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_xl_lp2_bandwidth_t val); -int32_t lsm6dsv16x_filt_xl_lp2_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_xl_lp2_bandwidth_t *val); +int32_t lsm6dsv16x_filt_xl_lp2_bandwidth_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_xl_lp2_bandwidth_t val); +int32_t lsm6dsv16x_filt_xl_lp2_bandwidth_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_xl_lp2_bandwidth_t *val); int32_t lsm6dsv16x_filt_xl_lp2_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_filt_xl_lp2_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); @@ -4094,73 +4284,90 @@ int32_t lsm6dsv16x_filt_xl_fast_settling_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) int32_t lsm6dsv16x_filt_xl_fast_settling_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef enum { - LSM6DSV16X_HP_MD_NORMAL = 0x0, + LSM6DSV16X_HP_MD_NORMAL = 0x0, LSM6DSV16X_HP_MD_REFERENCE = 0x1, } lsm6dsv16x_filt_xl_hp_mode_t; -int32_t lsm6dsv16x_filt_xl_hp_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_xl_hp_mode_t val); -int32_t lsm6dsv16x_filt_xl_hp_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_xl_hp_mode_t *val); +int32_t lsm6dsv16x_filt_xl_hp_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_xl_hp_mode_t val); +int32_t lsm6dsv16x_filt_xl_hp_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_xl_hp_mode_t *val); typedef enum { - LSM6DSV16X_WK_FEED_SLOPE = 0x0, - LSM6DSV16X_WK_FEED_HIGH_PASS = 0x1, + LSM6DSV16X_WK_FEED_SLOPE = 0x0, + LSM6DSV16X_WK_FEED_HIGH_PASS = 0x1, LSM6DSV16X_WK_FEED_LP_WITH_OFFSET = 0x2, } lsm6dsv16x_filt_wkup_act_feed_t; -int32_t lsm6dsv16x_filt_wkup_act_feed_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_wkup_act_feed_t val); -int32_t lsm6dsv16x_filt_wkup_act_feed_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_wkup_act_feed_t *val); +int32_t lsm6dsv16x_filt_wkup_act_feed_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_wkup_act_feed_t val); +int32_t lsm6dsv16x_filt_wkup_act_feed_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_wkup_act_feed_t *val); + +int32_t lsm6dsv16x_mask_trigger_xl_settl_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); +int32_t lsm6dsv16x_mask_trigger_xl_settl_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef enum { LSM6DSV16X_SIXD_FEED_ODR_DIV_2 = 0x0, - LSM6DSV16X_SIXD_FEED_LOW_PASS = 0x1, + LSM6DSV16X_SIXD_FEED_LOW_PASS = 0x1, } lsm6dsv16x_filt_sixd_feed_t; -int32_t lsm6dsv16x_filt_sixd_feed_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_sixd_feed_t val); -int32_t lsm6dsv16x_filt_sixd_feed_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_sixd_feed_t *val); +int32_t lsm6dsv16x_filt_sixd_feed_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_sixd_feed_t val); +int32_t lsm6dsv16x_filt_sixd_feed_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_sixd_feed_t *val); typedef enum { LSM6DSV16X_EIS_LP_NORMAL = 0x0, - LSM6DSV16X_EIS_LP_LIGHT = 0x1, + LSM6DSV16X_EIS_LP_LIGHT = 0x1, } lsm6dsv16x_filt_gy_eis_lp_bandwidth_t; -int32_t lsm6dsv16x_filt_gy_eis_lp_bandwidth_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_gy_eis_lp_bandwidth_t val); -int32_t lsm6dsv16x_filt_gy_eis_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_gy_eis_lp_bandwidth_t *val); +int32_t lsm6dsv16x_filt_gy_eis_lp_bandwidth_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_gy_eis_lp_bandwidth_t val); +int32_t lsm6dsv16x_filt_gy_eis_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_gy_eis_lp_bandwidth_t *val); typedef enum { - LSM6DSV16X_OIS_GY_LP_NORMAL = 0x0, - LSM6DSV16X_OIS_GY_LP_STRONG = 0x1, + LSM6DSV16X_OIS_GY_LP_NORMAL = 0x0, + LSM6DSV16X_OIS_GY_LP_STRONG = 0x1, LSM6DSV16X_OIS_GY_LP_AGGRESSIVE = 0x2, - LSM6DSV16X_OIS_GY_LP_LIGHT = 0x3, + LSM6DSV16X_OIS_GY_LP_LIGHT = 0x3, } lsm6dsv16x_filt_gy_ois_lp_bandwidth_t; -int32_t lsm6dsv16x_filt_gy_ois_lp_bandwidth_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_gy_ois_lp_bandwidth_t val); -int32_t lsm6dsv16x_filt_gy_ois_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_gy_ois_lp_bandwidth_t *val); +int32_t lsm6dsv16x_filt_gy_ois_lp_bandwidth_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_gy_ois_lp_bandwidth_t val); +int32_t lsm6dsv16x_filt_gy_ois_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_gy_ois_lp_bandwidth_t *val); typedef enum { LSM6DSV16X_OIS_XL_LP_ULTRA_LIGHT = 0x0, - LSM6DSV16X_OIS_XL_LP_VERY_LIGHT = 0x1, - LSM6DSV16X_OIS_XL_LP_LIGHT = 0x2, - LSM6DSV16X_OIS_XL_LP_NORMAL = 0x3, - LSM6DSV16X_OIS_XL_LP_STRONG = 0x4, + LSM6DSV16X_OIS_XL_LP_VERY_LIGHT = 0x1, + LSM6DSV16X_OIS_XL_LP_LIGHT = 0x2, + LSM6DSV16X_OIS_XL_LP_NORMAL = 0x3, + LSM6DSV16X_OIS_XL_LP_STRONG = 0x4, LSM6DSV16X_OIS_XL_LP_VERY_STRONG = 0x5, - LSM6DSV16X_OIS_XL_LP_AGGRESSIVE = 0x6, - LSM6DSV16X_OIS_XL_LP_XTREME = 0x7, + LSM6DSV16X_OIS_XL_LP_AGGRESSIVE = 0x6, + LSM6DSV16X_OIS_XL_LP_XTREME = 0x7, } lsm6dsv16x_filt_xl_ois_lp_bandwidth_t; -int32_t lsm6dsv16x_filt_xl_ois_lp_bandwidth_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_xl_ois_lp_bandwidth_t val); -int32_t lsm6dsv16x_filt_xl_ois_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_filt_xl_ois_lp_bandwidth_t *val); +int32_t lsm6dsv16x_filt_xl_ois_lp_bandwidth_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_xl_ois_lp_bandwidth_t val); +int32_t lsm6dsv16x_filt_xl_ois_lp_bandwidth_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_filt_xl_ois_lp_bandwidth_t *val); typedef enum { LSM6DSV16X_PROTECT_CTRL_REGS = 0x0, - LSM6DSV16X_WRITE_CTRL_REG = 0x1, + LSM6DSV16X_WRITE_CTRL_REG = 0x1, } lsm6dsv16x_fsm_permission_t; -int32_t lsm6dsv16x_fsm_permission_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_permission_t val); -int32_t lsm6dsv16x_fsm_permission_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_permission_t *val); +int32_t lsm6dsv16x_fsm_permission_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_permission_t val); +int32_t lsm6dsv16x_fsm_permission_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_permission_t *val); int32_t lsm6dsv16x_fsm_permission_status(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef struct { - uint8_t fsm1_en : 1; - uint8_t fsm2_en : 1; - uint8_t fsm3_en : 1; - uint8_t fsm4_en : 1; - uint8_t fsm5_en : 1; - uint8_t fsm6_en : 1; - uint8_t fsm7_en : 1; - uint8_t fsm8_en : 1; + uint8_t fsm1_en : 1; + uint8_t fsm2_en : 1; + uint8_t fsm3_en : 1; + uint8_t fsm4_en : 1; + uint8_t fsm5_en : 1; + uint8_t fsm6_en : 1; + uint8_t fsm7_en : 1; + uint8_t fsm8_en : 1; } lsm6dsv16x_fsm_mode_t; int32_t lsm6dsv16x_fsm_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_mode_t val); int32_t lsm6dsv16x_fsm_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_mode_t *val); @@ -4170,39 +4377,45 @@ int32_t lsm6dsv16x_fsm_long_cnt_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val); typedef struct { - lsm6dsv16x_fsm_outs1_t fsm_outs1; - lsm6dsv16x_fsm_outs2_t fsm_outs2; - lsm6dsv16x_fsm_outs3_t fsm_outs3; - lsm6dsv16x_fsm_outs4_t fsm_outs4; - lsm6dsv16x_fsm_outs5_t fsm_outs5; - lsm6dsv16x_fsm_outs6_t fsm_outs6; - lsm6dsv16x_fsm_outs7_t fsm_outs7; - lsm6dsv16x_fsm_outs8_t fsm_outs8; + uint8_t fsm_outs1; + uint8_t fsm_outs2; + uint8_t fsm_outs3; + uint8_t fsm_outs4; + uint8_t fsm_outs5; + uint8_t fsm_outs6; + uint8_t fsm_outs7; + uint8_t fsm_outs8; } lsm6dsv16x_fsm_out_t; int32_t lsm6dsv16x_fsm_out_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_out_t *val); typedef enum { - LSM6DSV16X_FSM_15Hz = 0x0, - LSM6DSV16X_FSM_30Hz = 0x1, - LSM6DSV16X_FSM_60Hz = 0x2, + LSM6DSV16X_FSM_15Hz = 0x0, + LSM6DSV16X_FSM_30Hz = 0x1, + LSM6DSV16X_FSM_60Hz = 0x2, LSM6DSV16X_FSM_120Hz = 0x3, LSM6DSV16X_FSM_240Hz = 0x4, LSM6DSV16X_FSM_480Hz = 0x5, LSM6DSV16X_FSM_960Hz = 0x6, } lsm6dsv16x_fsm_data_rate_t; -int32_t lsm6dsv16x_fsm_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_data_rate_t val); -int32_t lsm6dsv16x_fsm_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_data_rate_t *val); +int32_t lsm6dsv16x_fsm_data_rate_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_data_rate_t val); +int32_t lsm6dsv16x_fsm_data_rate_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_data_rate_t *val); -int32_t lsm6dsv16x_fsm_ext_sens_sensitivity_set(lsm6dsv16x_ctx_t *ctx, uint16_t val); -int32_t lsm6dsv16x_fsm_ext_sens_sensitivity_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val); +int32_t lsm6dsv16x_fsm_ext_sens_sensitivity_set(lsm6dsv16x_ctx_t *ctx, + uint16_t val); +int32_t lsm6dsv16x_fsm_ext_sens_sensitivity_get(lsm6dsv16x_ctx_t *ctx, + uint16_t *val); typedef struct { uint16_t z; uint16_t y; uint16_t x; } lsm6dsv16x_xl_fsm_ext_sens_offset_t; -int32_t lsm6dsv16x_fsm_ext_sens_offset_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_fsm_ext_sens_offset_t val); -int32_t lsm6dsv16x_fsm_ext_sens_offset_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_fsm_ext_sens_offset_t *val); +int32_t lsm6dsv16x_fsm_ext_sens_offset_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_fsm_ext_sens_offset_t val); +int32_t lsm6dsv16x_fsm_ext_sens_offset_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_fsm_ext_sens_offset_t *val); typedef struct { uint16_t xx; @@ -4212,41 +4425,49 @@ typedef struct { uint16_t yz; uint16_t zz; } lsm6dsv16x_xl_fsm_ext_sens_matrix_t; -int32_t lsm6dsv16x_fsm_ext_sens_matrix_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_fsm_ext_sens_matrix_t val); -int32_t lsm6dsv16x_fsm_ext_sens_matrix_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_xl_fsm_ext_sens_matrix_t *val); +int32_t lsm6dsv16x_fsm_ext_sens_matrix_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_fsm_ext_sens_matrix_t val); +int32_t lsm6dsv16x_fsm_ext_sens_matrix_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_xl_fsm_ext_sens_matrix_t *val); typedef enum { - LSM6DSV16X_Z_EQ_Y = 0x0, + LSM6DSV16X_Z_EQ_Y = 0x0, LSM6DSV16X_Z_EQ_MIN_Y = 0x1, - LSM6DSV16X_Z_EQ_X = 0x2, + LSM6DSV16X_Z_EQ_X = 0x2, LSM6DSV16X_Z_EQ_MIN_X = 0x3, LSM6DSV16X_Z_EQ_MIN_Z = 0x4, - LSM6DSV16X_Z_EQ_Z = 0x5, + LSM6DSV16X_Z_EQ_Z = 0x5, } lsm6dsv16x_fsm_ext_sens_z_orient_t; -int32_t lsm6dsv16x_fsm_ext_sens_z_orient_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_ext_sens_z_orient_t val); -int32_t lsm6dsv16x_fsm_ext_sens_z_orient_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_ext_sens_z_orient_t *val); +int32_t lsm6dsv16x_fsm_ext_sens_z_orient_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_ext_sens_z_orient_t val); +int32_t lsm6dsv16x_fsm_ext_sens_z_orient_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_ext_sens_z_orient_t *val); typedef enum { - LSM6DSV16X_Y_EQ_Y = 0x0, + LSM6DSV16X_Y_EQ_Y = 0x0, LSM6DSV16X_Y_EQ_MIN_Y = 0x1, - LSM6DSV16X_Y_EQ_X = 0x2, + LSM6DSV16X_Y_EQ_X = 0x2, LSM6DSV16X_Y_EQ_MIN_X = 0x3, LSM6DSV16X_Y_EQ_MIN_Z = 0x4, - LSM6DSV16X_Y_EQ_Z = 0x5, + LSM6DSV16X_Y_EQ_Z = 0x5, } lsm6dsv16x_fsm_ext_sens_y_orient_t; -int32_t lsm6dsv16x_fsm_ext_sens_y_orient_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_ext_sens_y_orient_t val); -int32_t lsm6dsv16x_fsm_ext_sens_y_orient_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_ext_sens_y_orient_t *val); +int32_t lsm6dsv16x_fsm_ext_sens_y_orient_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_ext_sens_y_orient_t val); +int32_t lsm6dsv16x_fsm_ext_sens_y_orient_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_ext_sens_y_orient_t *val); typedef enum { - LSM6DSV16X_X_EQ_Y = 0x0, + LSM6DSV16X_X_EQ_Y = 0x0, LSM6DSV16X_X_EQ_MIN_Y = 0x1, - LSM6DSV16X_X_EQ_X = 0x2, + LSM6DSV16X_X_EQ_X = 0x2, LSM6DSV16X_X_EQ_MIN_X = 0x3, LSM6DSV16X_X_EQ_MIN_Z = 0x4, - LSM6DSV16X_X_EQ_Z = 0x5, + LSM6DSV16X_X_EQ_Z = 0x5, } lsm6dsv16x_fsm_ext_sens_x_orient_t; -int32_t lsm6dsv16x_fsm_ext_sens_x_orient_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_ext_sens_x_orient_t val); -int32_t lsm6dsv16x_fsm_ext_sens_x_orient_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_fsm_ext_sens_x_orient_t *val); +int32_t lsm6dsv16x_fsm_ext_sens_x_orient_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_ext_sens_x_orient_t val); +int32_t lsm6dsv16x_fsm_ext_sens_x_orient_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_fsm_ext_sens_x_orient_t *val); int32_t lsm6dsv16x_fsm_long_cnt_timeout_set(lsm6dsv16x_ctx_t *ctx, uint16_t val); int32_t lsm6dsv16x_fsm_long_cnt_timeout_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val); @@ -4270,28 +4491,32 @@ typedef enum { LSM6DSV16X_469_mg = 0x6, LSM6DSV16X_500_mg = 0x7, } lsm6dsv16x_ff_thresholds_t; -int32_t lsm6dsv16x_ff_thresholds_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ff_thresholds_t val); -int32_t lsm6dsv16x_ff_thresholds_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ff_thresholds_t *val); +int32_t lsm6dsv16x_ff_thresholds_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ff_thresholds_t val); +int32_t lsm6dsv16x_ff_thresholds_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ff_thresholds_t *val); typedef enum { - LSM6DSV16X_DISABLE = 0x0, - LSM6DSV16X_MLC_BEFORE_FSM = 0x1, - LSM6DSV16X_MLC_AFTER_FSM = 0x2, + LSM6DSV16X_MLC_OFF = 0x0, + LSM6DSV16X_MLC_ON = 0x1, + LSM6DSV16X_MLC_ON_BEFORE_FSM = 0x2, } lsm6dsv16x_mlc_mode_t; -int32_t lsm6dsv16x_mlc_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_mode_t val); -int32_t lsm6dsv16x_mlc_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_mode_t *val); +int32_t lsm6dsv16x_mlc_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_mode_t val); +int32_t lsm6dsv16x_mlc_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_mode_t *val); typedef enum { - LSM6DSV16X_MLC_15Hz = 0x0, - LSM6DSV16X_MLC_30Hz = 0x1, - LSM6DSV16X_MLC_60Hz = 0x2, + LSM6DSV16X_MLC_15Hz = 0x0, + LSM6DSV16X_MLC_30Hz = 0x1, + LSM6DSV16X_MLC_60Hz = 0x2, LSM6DSV16X_MLC_120Hz = 0x3, LSM6DSV16X_MLC_240Hz = 0x4, LSM6DSV16X_MLC_480Hz = 0x5, LSM6DSV16X_MLC_960Hz = 0x6, } lsm6dsv16x_mlc_data_rate_t; -int32_t lsm6dsv16x_mlc_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_data_rate_t val); -int32_t lsm6dsv16x_mlc_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_data_rate_t *val); +int32_t lsm6dsv16x_mlc_data_rate_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_mlc_data_rate_t val); +int32_t lsm6dsv16x_mlc_data_rate_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_mlc_data_rate_t *val); typedef struct { uint8_t mlc1_src; @@ -4301,15 +4526,19 @@ typedef struct { } lsm6dsv16x_mlc_out_t; int32_t lsm6dsv16x_mlc_out_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_mlc_out_t *val); -int32_t lsm6dsv16x_mlc_ext_sens_sensitivity_set(lsm6dsv16x_ctx_t *ctx, uint16_t val); -int32_t lsm6dsv16x_mlc_ext_sens_sensitivity_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val); +int32_t lsm6dsv16x_mlc_ext_sens_sensitivity_set(lsm6dsv16x_ctx_t *ctx, + uint16_t val); +int32_t lsm6dsv16x_mlc_ext_sens_sensitivity_get(lsm6dsv16x_ctx_t *ctx, + uint16_t *val); typedef enum { LSM6DSV16X_OIS_CTRL_FROM_OIS = 0x0, - LSM6DSV16X_OIS_CTRL_FROM_UI = 0x1, + LSM6DSV16X_OIS_CTRL_FROM_UI = 0x1, } lsm6dsv16x_ois_ctrl_mode_t; -int32_t lsm6dsv16x_ois_ctrl_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_ctrl_mode_t val); -int32_t lsm6dsv16x_ois_ctrl_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_ctrl_mode_t *val); +int32_t lsm6dsv16x_ois_ctrl_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_ctrl_mode_t val); +int32_t lsm6dsv16x_ois_ctrl_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_ctrl_mode_t *val); int32_t lsm6dsv16x_ois_reset_set(lsm6dsv16x_ctx_t *ctx, int8_t val); int32_t lsm6dsv16x_ois_reset_get(lsm6dsv16x_ctx_t *ctx, int8_t *val); @@ -4318,13 +4547,17 @@ int32_t lsm6dsv16x_ois_interface_pull_up_set(lsm6dsv16x_ctx_t *ctx, uint8_t val) int32_t lsm6dsv16x_ois_interface_pull_up_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef struct { - uint8_t ack : 1; - uint8_t req : 1; + uint8_t ack : 1; + uint8_t req : 1; } lsm6dsv16x_ois_handshake_t; -int32_t lsm6dsv16x_ois_handshake_from_ui_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_handshake_t val); -int32_t lsm6dsv16x_ois_handshake_from_ui_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_handshake_t *val); -int32_t lsm6dsv16x_ois_handshake_from_ois_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_handshake_t val); -int32_t lsm6dsv16x_ois_handshake_from_ois_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_handshake_t *val); +int32_t lsm6dsv16x_ois_handshake_from_ui_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_handshake_t val); +int32_t lsm6dsv16x_ois_handshake_from_ui_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_handshake_t *val); +int32_t lsm6dsv16x_ois_handshake_from_ois_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_handshake_t val); +int32_t lsm6dsv16x_ois_handshake_from_ois_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_handshake_t *val); int32_t lsm6dsv16x_ois_shared_set(lsm6dsv16x_ctx_t *ctx, uint8_t val[6]); int32_t lsm6dsv16x_ois_shared_get(lsm6dsv16x_ctx_t *ctx, uint8_t val[6]); @@ -4333,30 +4566,35 @@ int32_t lsm6dsv16x_ois_on_spi2_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_ois_on_spi2_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef struct { - uint8_t gy : 1; - uint8_t xl : 1; + uint8_t gy : 1; + uint8_t xl : 1; } lsm6dsv16x_ois_chain_t; int32_t lsm6dsv16x_ois_chain_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_chain_t val); -int32_t lsm6dsv16x_ois_chain_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_chain_t *val); +int32_t lsm6dsv16x_ois_chain_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_chain_t *val); typedef enum { - LSM6DSV16X_OIS_125dps = 0x0, - LSM6DSV16X_OIS_250dps = 0x1, - LSM6DSV16X_OIS_500dps = 0x2, + LSM6DSV16X_OIS_125dps = 0x0, + LSM6DSV16X_OIS_250dps = 0x1, + LSM6DSV16X_OIS_500dps = 0x2, LSM6DSV16X_OIS_1000dps = 0x3, LSM6DSV16X_OIS_2000dps = 0x4, } lsm6dsv16x_ois_gy_full_scale_t; -int32_t lsm6dsv16x_ois_gy_full_scale_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_gy_full_scale_t val); -int32_t lsm6dsv16x_ois_gy_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_gy_full_scale_t *val); +int32_t lsm6dsv16x_ois_gy_full_scale_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_gy_full_scale_t val); +int32_t lsm6dsv16x_ois_gy_full_scale_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_gy_full_scale_t *val); typedef enum { - LSM6DSV16X_OIS_2g = 0x0, - LSM6DSV16X_OIS_4g = 0x1, - LSM6DSV16X_OIS_8g = 0x2, + LSM6DSV16X_OIS_2g = 0x0, + LSM6DSV16X_OIS_4g = 0x1, + LSM6DSV16X_OIS_8g = 0x2, LSM6DSV16X_OIS_16g = 0x3, } lsm6dsv16x_ois_xl_full_scale_t; -int32_t lsm6dsv16x_ois_xl_full_scale_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_xl_full_scale_t val); -int32_t lsm6dsv16x_ois_xl_full_scale_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ois_xl_full_scale_t *val); +int32_t lsm6dsv16x_ois_xl_full_scale_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_xl_full_scale_t val); +int32_t lsm6dsv16x_ois_xl_full_scale_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ois_xl_full_scale_t *val); typedef enum { LSM6DSV16X_DEG_80 = 0x0, @@ -4364,8 +4602,10 @@ typedef enum { LSM6DSV16X_DEG_60 = 0x2, LSM6DSV16X_DEG_50 = 0x3, } lsm6dsv16x_6d_threshold_t; -int32_t lsm6dsv16x_6d_threshold_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_6d_threshold_t val); -int32_t lsm6dsv16x_6d_threshold_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_6d_threshold_t *val); +int32_t lsm6dsv16x_6d_threshold_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_6d_threshold_t val); +int32_t lsm6dsv16x_6d_threshold_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_6d_threshold_t *val); int32_t lsm6dsv16x_4d_mode_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_4d_mode_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); @@ -4376,66 +4616,57 @@ typedef enum { LSM6DSV16X_300MOhm = 0x2, LSM6DSV16X_255MOhm = 0x3, } lsm6dsv16x_ah_qvar_zin_t; -int32_t lsm6dsv16x_ah_qvar_zin_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ah_qvar_zin_t val); -int32_t lsm6dsv16x_ah_qvar_zin_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ah_qvar_zin_t *val); +int32_t lsm6dsv16x_ah_qvar_zin_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ah_qvar_zin_t val); +int32_t lsm6dsv16x_ah_qvar_zin_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ah_qvar_zin_t *val); typedef struct { - uint8_t ah_qvar_en : 1; + uint8_t ah_qvar_en : 1; } lsm6dsv16x_ah_qvar_mode_t; -int32_t lsm6dsv16x_ah_qvar_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ah_qvar_mode_t val); -int32_t lsm6dsv16x_ah_qvar_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ah_qvar_mode_t *val); +int32_t lsm6dsv16x_ah_qvar_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ah_qvar_mode_t val); +int32_t lsm6dsv16x_ah_qvar_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ah_qvar_mode_t *val); typedef enum { LSM6DSV16X_SW_RST_DYN_ADDRESS_RST = 0x0, - LSM6DSV16X_I3C_GLOBAL_RST = 0x1, + LSM6DSV16X_I3C_GLOBAL_RST = 0x1, } lsm6dsv16x_i3c_reset_mode_t; -int32_t lsm6dsv16x_i3c_reset_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_i3c_reset_mode_t val); -int32_t lsm6dsv16x_i3c_reset_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_i3c_reset_mode_t *val); +int32_t lsm6dsv16x_i3c_reset_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_i3c_reset_mode_t val); +int32_t lsm6dsv16x_i3c_reset_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_i3c_reset_mode_t *val); typedef enum { - LSM6DSV16X_IBI_2us = 0x0, + LSM6DSV16X_IBI_2us = 0x0, LSM6DSV16X_IBI_50us = 0x1, - LSM6DSV16X_IBI_1ms = 0x2, + LSM6DSV16X_IBI_1ms = 0x2, LSM6DSV16X_IBI_25ms = 0x3, } lsm6dsv16x_i3c_ibi_time_t; -int32_t lsm6dsv16x_i3c_ibi_time_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_i3c_ibi_time_t val); -int32_t lsm6dsv16x_i3c_ibi_time_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_i3c_ibi_time_t *val); - -int32_t lsm6dsv16x_sh_master_interface_pull_up_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); -int32_t lsm6dsv16x_sh_master_interface_pull_up_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); - -typedef struct { - lsm6dsv16x_sensor_hub_1_t sh_byte_1; - lsm6dsv16x_sensor_hub_2_t sh_byte_2; - lsm6dsv16x_sensor_hub_3_t sh_byte_3; - lsm6dsv16x_sensor_hub_4_t sh_byte_4; - lsm6dsv16x_sensor_hub_5_t sh_byte_5; - lsm6dsv16x_sensor_hub_6_t sh_byte_6; - lsm6dsv16x_sensor_hub_7_t sh_byte_7; - lsm6dsv16x_sensor_hub_8_t sh_byte_8; - lsm6dsv16x_sensor_hub_9_t sh_byte_9; - lsm6dsv16x_sensor_hub_10_t sh_byte_10; - lsm6dsv16x_sensor_hub_11_t sh_byte_11; - lsm6dsv16x_sensor_hub_12_t sh_byte_12; - lsm6dsv16x_sensor_hub_13_t sh_byte_13; - lsm6dsv16x_sensor_hub_14_t sh_byte_14; - lsm6dsv16x_sensor_hub_15_t sh_byte_15; - lsm6dsv16x_sensor_hub_16_t sh_byte_16; - lsm6dsv16x_sensor_hub_17_t sh_byte_17; - lsm6dsv16x_sensor_hub_18_t sh_byte_18; -} lsm6dsv16x_emb_sh_read_t; -int32_t lsm6dsv16x_sh_read_data_raw_get(lsm6dsv16x_ctx_t *ctx, - lsm6dsv16x_emb_sh_read_t *val, +int32_t lsm6dsv16x_i3c_ibi_time_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_i3c_ibi_time_t val); +int32_t lsm6dsv16x_i3c_ibi_time_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_i3c_ibi_time_t *val); + +int32_t lsm6dsv16x_sh_master_interface_pull_up_set(lsm6dsv16x_ctx_t *ctx, + uint8_t val); +int32_t lsm6dsv16x_sh_master_interface_pull_up_get(lsm6dsv16x_ctx_t *ctx, + uint8_t *val); + +int32_t lsm6dsv16x_sh_read_data_raw_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val, uint8_t len); typedef enum { - LSM6DSV16X_SLV_0 = 0x0, - LSM6DSV16X_SLV_0_1 = 0x1, - LSM6DSV16X_SLV_0_1_2 = 0x2, + LSM6DSV16X_SLV_0 = 0x0, + LSM6DSV16X_SLV_0_1 = 0x1, + LSM6DSV16X_SLV_0_1_2 = 0x2, LSM6DSV16X_SLV_0_1_2_3 = 0x3, } lsm6dsv16x_sh_slave_connected_t; -int32_t lsm6dsv16x_sh_slave_connected_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_slave_connected_t val); -int32_t lsm6dsv16x_sh_slave_connected_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_slave_connected_t *val); +int32_t lsm6dsv16x_sh_slave_connected_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sh_slave_connected_t val); +int32_t lsm6dsv16x_sh_slave_connected_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sh_slave_connected_t *val); int32_t lsm6dsv16x_sh_master_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_sh_master_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); @@ -4445,17 +4676,21 @@ int32_t lsm6dsv16x_sh_pass_through_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef enum { LSM6DSV16X_SH_TRG_XL_GY_DRDY = 0x0, - LSM6DSV16X_SH_TRIG_INT2 = 0x1, + LSM6DSV16X_SH_TRIG_INT2 = 0x1, } lsm6dsv16x_sh_syncro_mode_t; -int32_t lsm6dsv16x_sh_syncro_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_syncro_mode_t val); -int32_t lsm6dsv16x_sh_syncro_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_syncro_mode_t *val); +int32_t lsm6dsv16x_sh_syncro_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sh_syncro_mode_t val); +int32_t lsm6dsv16x_sh_syncro_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sh_syncro_mode_t *val); typedef enum { - LSM6DSV16X_EACH_SH_CYCLE = 0x0, + LSM6DSV16X_EACH_SH_CYCLE = 0x0, LSM6DSV16X_ONLY_FIRST_CYCLE = 0x1, } lsm6dsv16x_sh_write_mode_t; -int32_t lsm6dsv16x_sh_write_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_write_mode_t val); -int32_t lsm6dsv16x_sh_write_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_write_mode_t *val); +int32_t lsm6dsv16x_sh_write_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sh_write_mode_t val); +int32_t lsm6dsv16x_sh_write_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sh_write_mode_t *val); int32_t lsm6dsv16x_sh_reset_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_sh_reset_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); @@ -4468,57 +4703,40 @@ typedef struct { int32_t lsm6dsv16x_sh_cfg_write(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_cfg_write_t *val); typedef enum { - LSM6DSV16X_SH_15Hz = 0x1, - LSM6DSV16X_SH_30Hz = 0x2, - LSM6DSV16X_SH_60Hz = 0x3, + LSM6DSV16X_SH_15Hz = 0x1, + LSM6DSV16X_SH_30Hz = 0x2, + LSM6DSV16X_SH_60Hz = 0x3, LSM6DSV16X_SH_120Hz = 0x4, LSM6DSV16X_SH_240Hz = 0x5, LSM6DSV16X_SH_480Hz = 0x6, } lsm6dsv16x_sh_data_rate_t; -int32_t lsm6dsv16x_sh_data_rate_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_data_rate_t val); -int32_t lsm6dsv16x_sh_data_rate_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_sh_data_rate_t *val); +int32_t lsm6dsv16x_sh_data_rate_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sh_data_rate_t val); +int32_t lsm6dsv16x_sh_data_rate_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sh_data_rate_t *val); typedef struct { uint8_t slv_add; uint8_t slv_subadd; uint8_t slv_len; } lsm6dsv16x_sh_cfg_read_t; -int32_t lsm6dsv16x_sh_slv0_cfg_read(lsm6dsv16x_ctx_t *ctx, - lsm6dsv16x_sh_cfg_read_t *val); -int32_t lsm6dsv16x_sh_slv1_cfg_read(lsm6dsv16x_ctx_t *ctx, - lsm6dsv16x_sh_cfg_read_t *val); -int32_t lsm6dsv16x_sh_slv2_cfg_read(lsm6dsv16x_ctx_t *ctx, - lsm6dsv16x_sh_cfg_read_t *val); -int32_t lsm6dsv16x_sh_slv3_cfg_read(lsm6dsv16x_ctx_t *ctx, - lsm6dsv16x_sh_cfg_read_t *val); - -int32_t lsm6dsv16x_s4s_sync_samples_set(lsm6dsv16x_ctx_t *ctx, uint16_t val); -int32_t lsm6dsv16x_s4s_sync_samples_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val); +int32_t lsm6dsv16x_sh_slv_cfg_read(lsm6dsv16x_ctx_t *ctx, uint8_t idx, + lsm6dsv16x_sh_cfg_read_t *val); -typedef enum { - LSM6DSV16X_S4S_DT_RES_11 = 0x0, - LSM6DSV16X_S4S_DT_RES_12 = 0x1, - LSM6DSV16X_S4S_DT_RES_13 = 0x2, - LSM6DSV16X_S4S_DT_RES_14 = 0x3, -} lsm6dsv16x_s4s_res_ratio_t; -int32_t lsm6dsv16x_s4s_res_ratio_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_s4s_res_ratio_t val); -int32_t lsm6dsv16x_s4s_res_ratio_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_s4s_res_ratio_t *val); - -int32_t lsm6dsv16x_s4s_command_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); -int32_t lsm6dsv16x_s4s_command_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); - -int32_t lsm6dsv16x_s4s_dt_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); -int32_t lsm6dsv16x_s4s_dt_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); +int32_t lsm6dsv16x_sh_status_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_status_master_t *val); int32_t lsm6dsv16x_ui_sdo_pull_up_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_ui_sdo_pull_up_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef enum { - LSM6DSV16X_I2C_I3C_ENABLE = 0x0, + LSM6DSV16X_I2C_I3C_ENABLE = 0x0, LSM6DSV16X_I2C_I3C_DISABLE = 0x1, } lsm6dsv16x_ui_i2c_i3c_mode_t; -int32_t lsm6dsv16x_ui_i2c_i3c_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ui_i2c_i3c_mode_t val); -int32_t lsm6dsv16x_ui_i2c_i3c_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_ui_i2c_i3c_mode_t *val); +int32_t lsm6dsv16x_ui_i2c_i3c_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ui_i2c_i3c_mode_t val); +int32_t lsm6dsv16x_ui_i2c_i3c_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_ui_i2c_i3c_mode_t *val); typedef enum { LSM6DSV16X_SPI_4_WIRE = 0x0, @@ -4535,17 +4753,20 @@ typedef enum { LSM6DSV16X_SPI2_3_WIRE = 0x1, } lsm6dsv16x_spi2_mode_t; int32_t lsm6dsv16x_spi2_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_spi2_mode_t val); -int32_t lsm6dsv16x_spi2_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_spi2_mode_t *val); +int32_t lsm6dsv16x_spi2_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_spi2_mode_t *val); int32_t lsm6dsv16x_sigmot_mode_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_sigmot_mode_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef struct { - uint8_t step_counter_enable : 1; - uint8_t false_step_rej : 1; + uint8_t step_counter_enable : 1; + uint8_t false_step_rej : 1; } lsm6dsv16x_stpcnt_mode_t; -int32_t lsm6dsv16x_stpcnt_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_stpcnt_mode_t val); -int32_t lsm6dsv16x_stpcnt_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_stpcnt_mode_t *val); +int32_t lsm6dsv16x_stpcnt_mode_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_stpcnt_mode_t val); +int32_t lsm6dsv16x_stpcnt_mode_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_stpcnt_mode_t *val); int32_t lsm6dsv16x_stpcnt_steps_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val); @@ -4558,43 +4779,75 @@ int32_t lsm6dsv16x_stpcnt_debounce_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); int32_t lsm6dsv16x_stpcnt_period_set(lsm6dsv16x_ctx_t *ctx, uint16_t val); int32_t lsm6dsv16x_stpcnt_period_get(lsm6dsv16x_ctx_t *ctx, uint16_t *val); +int32_t lsm6dsv16x_sflp_game_rotation_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); +int32_t lsm6dsv16x_sflp_game_rotation_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); + typedef struct { - uint8_t tap_x_en : 1; - uint8_t tap_y_en : 1; - uint8_t tap_z_en : 1; + float_t gbias_x; /* dps */ + float_t gbias_y; /* dps */ + float_t gbias_z; /* dps */ +} lsm6dsv16x_sflp_gbias_t; +int32_t lsm6dsv16x_sflp_game_gbias_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sflp_gbias_t *val); + +typedef enum { + LSM6DSV16X_SFLP_15Hz = 0x0, + LSM6DSV16X_SFLP_30Hz = 0x1, + LSM6DSV16X_SFLP_60Hz = 0x2, + LSM6DSV16X_SFLP_120Hz = 0x3, + LSM6DSV16X_SFLP_240Hz = 0x4, + LSM6DSV16X_SFLP_480Hz = 0x5, +} lsm6dsv16x_sflp_data_rate_t; +int32_t lsm6dsv16x_sflp_data_rate_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sflp_data_rate_t val); +int32_t lsm6dsv16x_sflp_data_rate_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_sflp_data_rate_t *val); + +typedef struct { + uint8_t tap_x_en : 1; + uint8_t tap_y_en : 1; + uint8_t tap_z_en : 1; } lsm6dsv16x_tap_detection_t; -int32_t lsm6dsv16x_tap_detection_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_detection_t val); -int32_t lsm6dsv16x_tap_detection_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_detection_t *val); +int32_t lsm6dsv16x_tap_detection_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_tap_detection_t val); +int32_t lsm6dsv16x_tap_detection_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_tap_detection_t *val); typedef struct { - uint8_t x : 1; - uint8_t y : 1; - uint8_t z : 1; + uint8_t x : 5; + uint8_t y : 5; + uint8_t z : 5; } lsm6dsv16x_tap_thresholds_t; -int32_t lsm6dsv16x_tap_thresholds_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_thresholds_t val); -int32_t lsm6dsv16x_tap_thresholds_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_thresholds_t *val); +int32_t lsm6dsv16x_tap_thresholds_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_tap_thresholds_t val); +int32_t lsm6dsv16x_tap_thresholds_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_tap_thresholds_t *val); typedef enum { LSM6DSV16X_XYZ = 0x0, LSM6DSV16X_YXZ = 0x1, - LSM6DSV16X_XZY = 0x2, + LSM6DSV16X_XZY = 0x2, LSM6DSV16X_ZYX = 0x3, LSM6DSV16X_YZX = 0x5, LSM6DSV16X_ZXY = 0x6, } lsm6dsv16x_tap_axis_priority_t; -int32_t lsm6dsv16x_tap_axis_priority_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_axis_priority_t val); -int32_t lsm6dsv16x_tap_axis_priority_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_axis_priority_t *val); +int32_t lsm6dsv16x_tap_axis_priority_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_tap_axis_priority_t val); +int32_t lsm6dsv16x_tap_axis_priority_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_tap_axis_priority_t *val); typedef struct { - uint8_t shock : 1; - uint8_t quiet : 1; - uint8_t tap_gap : 1; + uint8_t shock : 2; + uint8_t quiet : 2; + uint8_t tap_gap : 4; } lsm6dsv16x_tap_time_windows_t; -int32_t lsm6dsv16x_tap_time_windows_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_time_windows_t val); -int32_t lsm6dsv16x_tap_time_windows_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_time_windows_t *val); +int32_t lsm6dsv16x_tap_time_windows_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_tap_time_windows_t val); +int32_t lsm6dsv16x_tap_time_windows_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_tap_time_windows_t *val); typedef enum { - LSM6DSV16X_ONLY_SINGLE = 0x0, + LSM6DSV16X_ONLY_SINGLE = 0x0, LSM6DSV16X_BOTH_SINGLE_DOUBLE = 0x1, } lsm6dsv16x_tap_mode_t; int32_t lsm6dsv16x_tap_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_tap_mode_t val); @@ -4609,10 +4862,10 @@ int32_t lsm6dsv16x_timestamp_set(lsm6dsv16x_ctx_t *ctx, uint8_t val); int32_t lsm6dsv16x_timestamp_get(lsm6dsv16x_ctx_t *ctx, uint8_t *val); typedef enum { - LSM6DSV16X_XL_AND_GY_NOT_AFFECTED = 0x0, + LSM6DSV16X_XL_AND_GY_NOT_AFFECTED = 0x0, LSM6DSV16X_XL_LOW_POWER_GY_NOT_AFFECTED = 0x1, - LSM6DSV16X_XL_LOW_POWER_GY_SLEEP = 0x2, - LSM6DSV16X_XL_LOW_POWER_GY_POWER_DOWN = 0x3, + LSM6DSV16X_XL_LOW_POWER_GY_SLEEP = 0x2, + LSM6DSV16X_XL_LOW_POWER_GY_POWER_DOWN = 0x3, } lsm6dsv16x_act_mode_t; int32_t lsm6dsv16x_act_mode_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_mode_t val); int32_t lsm6dsv16x_act_mode_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_mode_t *val); @@ -4623,31 +4876,41 @@ typedef enum { LSM6DSV16X_SLEEP_TO_ACT_AT_3RD_SAMPLE = 0x2, LSM6DSV16X_SLEEP_TO_ACT_AT_4th_SAMPLE = 0x3, } lsm6dsv16x_act_from_sleep_to_act_dur_t; -int32_t lsm6dsv16x_act_from_sleep_to_act_dur_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_from_sleep_to_act_dur_t val); -int32_t lsm6dsv16x_act_from_sleep_to_act_dur_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_from_sleep_to_act_dur_t *val); +int32_t lsm6dsv16x_act_from_sleep_to_act_dur_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_act_from_sleep_to_act_dur_t val); +int32_t lsm6dsv16x_act_from_sleep_to_act_dur_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_act_from_sleep_to_act_dur_t *val); typedef enum { LSM6DSV16X_1Hz875 = 0x0, - LSM6DSV16X_15Hz = 0x1, - LSM6DSV16X_30Hz = 0x2, - LSM6DSV16X_60Hz = 0x3, + LSM6DSV16X_15Hz = 0x1, + LSM6DSV16X_30Hz = 0x2, + LSM6DSV16X_60Hz = 0x3, } lsm6dsv16x_act_sleep_xl_odr_t; -int32_t lsm6dsv16x_act_sleep_xl_odr_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_sleep_xl_odr_t val); -int32_t lsm6dsv16x_act_sleep_xl_odr_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_sleep_xl_odr_t *val); +int32_t lsm6dsv16x_act_sleep_xl_odr_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_act_sleep_xl_odr_t val); +int32_t lsm6dsv16x_act_sleep_xl_odr_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_act_sleep_xl_odr_t *val); typedef struct { - uint32_t wk_ths_mg; - uint32_t inact_ths_mg; + lsm6dsv16x_inactivity_dur_t inactivity_cfg; + uint8_t inactivity_ths; + uint8_t threshold; + uint8_t duration; } lsm6dsv16x_act_thresholds_t; -int32_t lsm6dsv16x_act_thresholds_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_thresholds_t val); -int32_t lsm6dsv16x_act_thresholds_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_thresholds_t *val); +int32_t lsm6dsv16x_act_thresholds_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_act_thresholds_t *val); +int32_t lsm6dsv16x_act_thresholds_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_act_thresholds_t *val); typedef struct { - uint8_t shock : 2; - uint8_t quiet : 4; + uint8_t shock : 2; + uint8_t quiet : 4; } lsm6dsv16x_act_wkup_time_windows_t; -int32_t lsm6dsv16x_act_wkup_time_windows_set(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_wkup_time_windows_t val); -int32_t lsm6dsv16x_act_wkup_time_windows_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_act_wkup_time_windows_t *val); +int32_t lsm6dsv16x_act_wkup_time_windows_set(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_act_wkup_time_windows_t val); +int32_t lsm6dsv16x_act_wkup_time_windows_get(lsm6dsv16x_ctx_t *ctx, + lsm6dsv16x_act_wkup_time_windows_t *val); /** * @} @@ -4660,4 +4923,4 @@ int32_t lsm6dsv16x_act_wkup_time_windows_get(lsm6dsv16x_ctx_t *ctx, lsm6dsv16x_a #endif /*LSM6DSV16X_DRIVER_H */ -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ \ No newline at end of file