diff --git a/Makefile b/Makefile
index 93c6fc0d58..4d07ed0ee4 100644
--- a/Makefile
+++ b/Makefile
@@ -85,6 +85,9 @@ ST_OBJ_CF2 += usbd_ioreq.o usbd_req.o usbd_core.o
# libdw dw1000 driver
VPATH_CF2 += vendor/libdw1000/src
+# vl53l1 driver
+VPATH_CF2 += $(LIB)/vl53l1/core/src
+
# FreeRTOS
VPATH += $(PORT)
PORT_OBJ = port.o
@@ -124,7 +127,7 @@ PROJ_OBJ_CF2 += ak8963.o eeprom.o maxsonar.o piezo.o
PROJ_OBJ_CF2 += uart_syslink.o swd.o uart1.o uart2.o watchdog.o
PROJ_OBJ_CF2 += cppm.o
PROJ_OBJ_CF2 += bmi055_accel.o bmi055_gyro.o bmi160.o bmp280.o bstdr_comm_support.o bmm150.o
-PROJ_OBJ_CF2 += pca9685.o vl53l0x.o pca95x4.o
+PROJ_OBJ_CF2 += pca9685.o vl53l0x.o pca95x4.o vl53l1x.o
# USB Files
PROJ_OBJ_CF2 += usb_bsp.o usblink.o usbd_desc.o usb.o
@@ -136,6 +139,11 @@ PROJ_OBJ_CF2 += sensors_$(SENSORS).o
# libdw
PROJ_OBJ_CF2 += libdw1000.o libdw1000Spi.o
+# vl53l1 lib
+PROJ_OBJ_CF2 += vl53l1_api_core.o vl53l1_api.o vl53l1_core.o vl53l1_silicon_core.o vl53l1_api_strings.o
+PROJ_OBJ_CF2 += vl53l1_api_calibration.o vl53l1_api_debug.o vl53l1_api_preset_modes.o vl53l1_error_strings.o
+PROJ_OBJ_CF2 += vl53l1_register_funcs.o vl53l1_wait.o vl53l1_core_support.o
+
# Modules
PROJ_OBJ += system.o comm.o console.o pid.o crtpservice.o param.o
PROJ_OBJ += log.o worker.o trigger.o sitaw.o queuemonitor.o msp.o
@@ -230,6 +238,8 @@ INCLUDES_CF2 += -I$(LIB)/STM32_USB_OTG_Driver/inc
INCLUDES_CF2 += -Isrc/deck/interface -Isrc/deck/drivers/interface
INCLUDES_CF2 += -Ivendor/libdw1000/inc
INCLUDES_CF2 += -I$(LIB)/FatFS
+INCLUDES_CF2 += -I$(LIB)/vl53l1
+INCLUDES_CF2 += -I$(LIB)/vl53l1/core/inc
ifeq ($(USE_FPU), 1)
PROCESSOR = -mcpu=cortex-m4 -mthumb -mfloat-abi=hard -mfpu=fpv4-sp-d16
diff --git a/src/drivers/interface/vl53l1x.h b/src/drivers/interface/vl53l1x.h
new file mode 100644
index 0000000000..d8b60e9a45
--- /dev/null
+++ b/src/drivers/interface/vl53l1x.h
@@ -0,0 +1,282 @@
+/*******************************************************************************
+ Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ ******************************************************************************/
+
+
+#ifndef _VL53L1X_H_
+#define _VL53L1X_H_
+
+#include "vl53l1_ll_def.h"
+#include "vl53l1_platform_user_data.h"
+#include "vl53l1_api.h"
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+#define VL53L1X_DEFAULT_ADDRESS 0b0101001
+
+#define USE_I2C_2V8
+
+/**
+ * @file vl53l1_platform.h
+ *
+ * @brief All end user OS/platform/application porting
+ */
+
+bool vl53l1xInit(VL53L1_Dev_t *pdev, I2C_Dev *I2Cx);
+
+bool vl53l1xTestConnection(VL53L1_Dev_t* pdev);
+
+VL53L1_Error vl53l1xSetI2CAddress(VL53L1_Dev_t* pdev, uint8_t address);
+
+/**
+ * @brief Writes the supplied byte buffer to the device
+ *
+ * @param[in] pdev : pointer to device structure (device handle)
+ * @param[in] index : uint16_t register index value
+ * @param[in] pdata : pointer to uint8_t (byte) buffer containing the data to be written
+ * @param[in] count : number of bytes in the supplied byte buffer
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_WriteMulti(
+ VL53L1_Dev_t *pdev,
+ uint16_t index,
+ uint8_t *pdata,
+ uint32_t count);
+
+
+/**
+ * @brief Reads the requested number of bytes from the device
+ *
+ * @param[in] pdev : pointer to device structure (device handle)
+ * @param[in] index : uint16_t register index value
+ * @param[out] pdata : pointer to the uint8_t (byte) buffer to store read data
+ * @param[in] count : number of bytes to read
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_ReadMulti(
+ VL53L1_Dev_t *pdev,
+ uint16_t index,
+ uint8_t *pdata,
+ uint32_t count);
+
+
+/**
+ * @brief Writes a single byte to the device
+ *
+ * @param[in] pdev : pointer to device structure (device handle)
+ * @param[in] index : uint16_t register index value
+ * @param[in] data : uint8_t data value to write
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_WrByte(
+ VL53L1_Dev_t *pdev,
+ uint16_t index,
+ uint8_t data);
+
+
+/**
+ * @brief Writes a single word (16-bit unsigned) to the device
+ *
+ * Manages the big-endian nature of the device register map
+ * (first byte written is the MS byte).
+ *
+ * @param[in] pdev : pointer to device structure (device handle)
+ * @param[in] index : uint16_t register index value
+ * @param[in] data : uin16_t data value write
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_WrWord(
+ VL53L1_Dev_t *pdev,
+ uint16_t index,
+ uint16_t data);
+
+
+/**
+ * @brief Writes a single dword (32-bit unsigned) to the device
+ *
+ * Manages the big-endian nature of the device register map
+ * (first byte written is the MS byte).
+ *
+ * @param[in] pdev : pointer to device structure (device handle)
+ * @param[in] index : uint16_t register index value
+ * @param[in] data : uint32_t data value to write
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_WrDWord(
+ VL53L1_Dev_t *pdev,
+ uint16_t index,
+ uint32_t data);
+
+
+
+/**
+ * @brief Reads a single byte from the device
+ *
+ * @param[in] pdev : pointer to device structure (device handle)
+ * @param[in] index : uint16_t register index
+ * @param[out] pdata : pointer to uint8_t data value
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ *
+ */
+
+VL53L1_Error VL53L1_RdByte(
+ VL53L1_Dev_t *pdev,
+ uint16_t index,
+ uint8_t *pdata);
+
+
+/**
+ * @brief Reads a single word (16-bit unsigned) from the device
+ *
+ * Manages the big-endian nature of the device (first byte read is the MS byte).
+ *
+ * @param[in] pdev : pointer to device structure (device handle)
+ * @param[in] index : uint16_t register index value
+ * @param[out] pdata : pointer to uint16_t data value
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_RdWord(
+ VL53L1_Dev_t *pdev,
+ uint16_t index,
+ uint16_t *pdata);
+
+
+/**
+ * @brief Reads a single dword (32-bit unsigned) from the device
+ *
+ * Manages the big-endian nature of the device (first byte read is the MS byte).
+ *
+ * @param[in] pdev : pointer to device structure (device handle)
+ * @param[in] index : uint16_t register index value
+ * @param[out] pdata : pointer to uint32_t data value
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_RdDWord(
+ VL53L1_Dev_t *pdev,
+ uint16_t index,
+ uint32_t *pdata);
+
+
+
+/**
+ * @brief Implements a programmable wait in us
+ *
+ * @param[in] pdev : pointer to device structure (device handle)
+ * @param[in] wait_us : integer wait in micro seconds
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_WaitUs(
+ VL53L1_Dev_t *pdev,
+ int32_t wait_us);
+
+
+/**
+ * @brief Implements a programmable wait in ms
+ *
+ * @param[in] pdev : pointer to device structure (device handle)
+ * @param[in] wait_ms : integer wait in milliseconds
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_WaitMs(
+ VL53L1_Dev_t *pdev,
+ int32_t wait_ms);
+
+/*
+ * @brief Gets current system tick count in [ms]
+ *
+ * @return time_ms : current time in [ms]
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_GetTickCount(
+ uint32_t *ptime_ms);
+
+
+/**
+ * @brief Register "wait for value" polling routine
+ *
+ * Port of the V2WReg Script function WaitValueMaskEx()
+ *
+ * @param[in] pdev : pointer to device structure (device handle)
+ * @param[in] timeout_ms : timeout in [ms]
+ * @param[in] index : uint16_t register index value
+ * @param[in] value : value to wait for
+ * @param[in] mask : mask to be applied before comparison with value
+ * @param[in] poll_delay_ms : polling delay been each read transaction in [ms]
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_WaitValueMaskEx(
+ VL53L1_Dev_t *pdev,
+ uint32_t timeout_ms,
+ uint16_t index,
+ uint8_t value,
+ uint8_t mask,
+ uint32_t poll_delay_ms);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
+
diff --git a/src/drivers/src/vl53l1x.c b/src/drivers/src/vl53l1x.c
new file mode 100644
index 0000000000..e1f85b26e0
--- /dev/null
+++ b/src/drivers/src/vl53l1x.c
@@ -0,0 +1,374 @@
+/*******************************************************************************
+ Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ ******************************************************************************/
+
+/**
+ * @file vl53l1_platform.c
+ * @brief Code function definitions for Crazyflie
+ *
+ */
+#include // sprintf(), vsnprintf(), printf()
+#include
+#include // strncpy(), strnlen()
+
+#include "FreeRTOS.h"
+#include "task.h"
+#include "debug.h"
+#include "i2cdev.h"
+#include "vl53l1x.h"
+
+
+#ifdef PAL_EXTENDED
+ #include "vl53l1_register_strings.h"
+#else
+ #define VL53L1_get_register_name(a,b)
+#endif
+
+// Set the start address 8 step after the VL53L0 dynamic addresses
+static int nextI2CAddress = VL53L1X_DEFAULT_ADDRESS+8;
+
+
+bool vl53l1xInit(VL53L1_Dev_t *pdev, I2C_Dev *I2Cx)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ pdev->I2Cx = I2Cx;
+ pdev->devAddr = VL53L1X_DEFAULT_ADDRESS;
+ i2cdevInit(pdev->I2Cx);
+
+ /* Move initialized sensor to a new I2C address */
+ int newAddress;
+
+ taskENTER_CRITICAL();
+ newAddress = nextI2CAddress++;
+ taskEXIT_CRITICAL();
+
+ status = vl53l1xSetI2CAddress(pdev, newAddress);
+
+ if (status == VL53L1_ERROR_NONE)
+ {
+ status = VL53L1_DataInit(pdev);
+ }
+ if (status == VL53L1_ERROR_NONE)
+ {
+ status = VL53L1_StaticInit(pdev);
+ }
+
+ return status == VL53L1_ERROR_NONE;
+}
+
+bool vl53l1xTestConnection(VL53L1_Dev_t* pdev)
+{
+ VL53L1_DeviceInfo_t info;
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ status = VL53L1_GetDeviceInfo(pdev, &info);
+
+ return status == VL53L1_ERROR_NONE;
+}
+
+/** Set I2C address
+ * Any subsequent communication will be on the new address
+ * The address passed is the 7bit I2C address from LSB (ie. without the
+ * read/write bit)
+ */
+VL53L1_Error vl53l1xSetI2CAddress(VL53L1_Dev_t* pdev, uint8_t address)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ status = VL53L1_SetDeviceAddress(pdev, address);
+ pdev->devAddr = address;
+ return status;
+}
+
+
+/*
+ * ----------------- COMMS FUNCTIONS -----------------
+ */
+
+VL53L1_Error VL53L1_WriteMulti(
+ VL53L1_Dev_t *pdev,
+ uint16_t index,
+ uint8_t *pdata,
+ uint32_t count)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ if (!i2cdevWrite16(pdev->I2Cx, pdev->devAddr, index, count, pdata))
+ {
+ status = VL53L1_ERROR_CONTROL_INTERFACE;
+ }
+
+ return status;
+}
+
+VL53L1_Error VL53L1_ReadMulti(
+ VL53L1_Dev_t *pdev,
+ uint16_t index,
+ uint8_t *pdata,
+ uint32_t count)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ if (!i2cdevRead16(pdev->I2Cx, pdev->devAddr, index, count, pdata))
+ {
+ status = VL53L1_ERROR_CONTROL_INTERFACE;
+ }
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_WrByte(
+ VL53L1_Dev_t *pdev,
+ uint16_t index,
+ uint8_t data)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ if (!i2cdevWrite16(pdev->I2Cx, pdev->devAddr, index, 1, &data))
+ {
+ status = VL53L1_ERROR_CONTROL_INTERFACE;
+ }
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_WrWord(
+ VL53L1_Dev_t *pdev,
+ uint16_t index,
+ uint16_t data)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ if (!i2cdevWrite16(pdev->I2Cx, pdev->devAddr, index, 2, (uint8_t *)&data))
+ {
+ status = VL53L1_ERROR_CONTROL_INTERFACE;
+ }
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_WrDWord(
+ VL53L1_Dev_t *pdev,
+ uint16_t index,
+ uint32_t data)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ if (!i2cdevWrite16(pdev->I2Cx, pdev->devAddr, index, 4, (uint8_t *)&data))
+ {
+ status = VL53L1_ERROR_CONTROL_INTERFACE;
+ }
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_RdByte(
+ VL53L1_Dev_t *pdev,
+ uint16_t index,
+ uint8_t *pdata)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ if (!i2cdevRead16(pdev->I2Cx, pdev->devAddr, index, 1, pdata))
+ {
+ status = VL53L1_ERROR_CONTROL_INTERFACE;
+ }
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_RdWord(
+ VL53L1_Dev_t *pdev,
+ uint16_t index,
+ uint16_t *pdata)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ if (!i2cdevRead16(pdev->I2Cx, pdev->devAddr, index, 2, (uint8_t *)pdata))
+ {
+ status = VL53L1_ERROR_CONTROL_INTERFACE;
+ }
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_RdDWord(
+ VL53L1_Dev_t *pdev,
+ uint16_t index,
+ uint32_t *pdata)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ if (!i2cdevRead16(pdev->I2Cx, pdev->devAddr, index, 4, (uint8_t *)pdata))
+ {
+ status = VL53L1_ERROR_CONTROL_INTERFACE;
+ }
+
+ return status;
+}
+
+/*
+ * ----------------- HOST TIMING FUNCTIONS -----------------
+ */
+
+VL53L1_Error VL53L1_WaitUs(
+ VL53L1_Dev_t *pdev,
+ int32_t wait_us)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint32_t delay_ms = (wait_us + 900) / 1000;
+
+ if(delay_ms == 0)
+ {
+ delay_ms = 1;
+ }
+
+ vTaskDelay(M2T(delay_ms));
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_WaitMs(
+ VL53L1_Dev_t *pdev,
+ int32_t wait_ms)
+{
+ vTaskDelay(M2T(wait_ms));
+
+ return VL53L1_ERROR_NONE;
+}
+
+/*
+ * ----------------- DEVICE TIMING FUNCTIONS -----------------
+ */
+
+VL53L1_Error VL53L1_GetTickCount(
+ uint32_t *ptick_count_ms)
+{
+ /* Returns current tick count in [ms] */
+ *ptick_count_ms = xTaskGetTickCount();
+
+ return VL53L1_ERROR_NONE;
+}
+
+
+VL53L1_Error VL53L1_WaitValueMaskEx(
+ VL53L1_Dev_t *pdev,
+ uint32_t timeout_ms,
+ uint16_t index,
+ uint8_t value,
+ uint8_t mask,
+ uint32_t poll_delay_ms)
+{
+ /*
+ * Platform implementation of WaitValueMaskEx V2WReg script command
+ *
+ * WaitValueMaskEx(
+ * duration_ms,
+ * index,
+ * value,
+ * mask,
+ * poll_delay_ms);
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint32_t start_time_ms = 0;
+ uint32_t current_time_ms = 0;
+ uint8_t byte_value = 0;
+ uint8_t found = 0;
+#ifdef VL53L1_LOG_ENABLE
+ uint32_t trace_functions = 0;
+#endif
+
+ SUPPRESS_UNUSED_WARNING(poll_delay_ms);
+
+#ifdef VL53L1_LOG_ENABLE
+ /* look up register name */
+ VL53L1_get_register_name(
+ index,
+ register_name);
+
+ /* Output to I2C logger for FMT/DFT */
+ trace_i2c("WaitValueMaskEx(%5d, %s, 0x%02X, 0x%02X, %5d);\n",
+ timeout_ms, register_name, value, mask, poll_delay_ms);
+#endif // VL53L1_LOG_ENABLE
+
+ /* calculate time limit in absolute time */
+
+ VL53L1_GetTickCount(&start_time_ms);
+ pdev->new_data_ready_poll_duration_ms = 0;
+
+ /* remember current trace functions and temporarily disable
+ * function logging
+ */
+
+#ifdef VL53L1_LOG_ENABLE
+ trace_functions = _LOG_GET_TRACE_FUNCTIONS();
+#endif
+
+ /* wait until value is found, timeout reached on error occurred */
+
+ while ((status == VL53L1_ERROR_NONE) &&
+ (pdev->new_data_ready_poll_duration_ms < timeout_ms) &&
+ (found == 0))
+ {
+ status = VL53L1_RdByte(
+ pdev,
+ index,
+ &byte_value);
+
+ if ((byte_value & mask) == value)
+ {
+ found = 1;
+ }
+
+ if (status == VL53L1_ERROR_NONE &&
+ found == 0 &&
+ poll_delay_ms > 0)
+ status = VL53L1_WaitMs(
+ pdev,
+ poll_delay_ms);
+
+ /* Update polling time (Compare difference rather than absolute to
+ negate 32bit wrap around issue) */
+ VL53L1_GetTickCount(¤t_time_ms);
+ pdev->new_data_ready_poll_duration_ms = current_time_ms - start_time_ms;
+ }
+
+ if (found == 0 && status == VL53L1_ERROR_NONE)
+ status = VL53L1_ERROR_TIME_OUT;
+
+ return status;
+}
+
diff --git a/src/lib/vl53l1/core/inc/vl53l1_api.h b/src/lib/vl53l1/core/inc/vl53l1_api.h
new file mode 100644
index 0000000000..47dfc4a6ee
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_api.h
@@ -0,0 +1,1148 @@
+/*
+* Copyright (c) 2017, STMicroelectronics - All Rights Reserved
+*
+* This file is part of VL53L1 Core and is dual licensed, either
+* 'STMicroelectronics Proprietary license'
+* or 'BSD 3-clause "New" or "Revised" License' , at your option.
+*
+********************************************************************************
+*
+* 'STMicroelectronics Proprietary license'
+*
+********************************************************************************
+*
+* License terms: STMicroelectronics Proprietary in accordance with licensing
+* terms at www.st.com/sla0044
+*
+* STMicroelectronics confidential
+* Reproduction and Communication of this document is strictly prohibited unless
+* specifically authorized in writing by STMicroelectronics.
+*
+*
+********************************************************************************
+*
+* Alternatively, VL53L1 Core may be distributed under the terms of
+* 'BSD 3-clause "New" or "Revised" License', in which case the following
+* provisions apply instead of the ones
+* mentioned above :
+*
+********************************************************************************
+*
+* License terms: BSD 3-clause "New" or "Revised" License.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions are met:
+*
+* 1. Redistributions of source code must retain the above copyright notice, this
+* list of conditions and the following disclaimer.
+*
+* 2. Redistributions in binary form must reproduce the above copyright notice,
+* this list of conditions and the following disclaimer in the documentation
+* and/or other materials provided with the distribution.
+*
+* 3. Neither the name of the copyright holder nor the names of its contributors
+* may be used to endorse or promote products derived from this software
+* without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*
+********************************************************************************
+*
+*/
+
+#ifndef _VL53L1_API_H_
+#define _VL53L1_API_H_
+
+#include "vl53l1_api_strings.h"
+#include "vl53l1_api_core.h"
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/** @defgroup VL53L1_cut11_group VL53L1 cut1.1 Function Definition
+ * @brief VL53L1 cut1.1 Function Definition
+ * @{
+ */
+
+/** @defgroup VL53L1_general_group VL53L1 General Functions
+ * @brief General functions and definitions
+ * @{
+ */
+
+/**
+ * @brief Return the VL53L1 driver Version
+ *
+ * @note This function doesn't access to the device
+ *
+ * @param pVersion Rer to current driver Version
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetVersion(VL53L1_Version_t *pVersion);
+
+/**
+ * @brief Reads the Product Revision for a for given Device
+ * This function can be used to distinguish cut1.0 from cut1.1.
+ *
+ * @param Dev Device Handle
+ * @param pProductRevisionMajor Pointer to Product Revision Major
+ * for a given Device
+ * @param pProductRevisionMinor Pointer to Product Revision Minor
+ * for a given Device
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetProductRevision(VL53L1_DEV Dev,
+ uint8_t *pProductRevisionMajor, uint8_t *pProductRevisionMinor);
+
+/**
+ * @brief Reads the Device information for given Device
+ *
+ * @note This function Access to the device
+ *
+ * @param Dev Device Handle
+ * @param pVL53L1_DeviceInfo Pointer to current device info for a given
+ * Device
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetDeviceInfo(VL53L1_DEV Dev,
+ VL53L1_DeviceInfo_t *pVL53L1_DeviceInfo);
+
+/**
+ * @brief Human readable Range Status string for a given RangeStatus
+ *
+ * @note This function doesn't access to the device
+ *
+ * @param RangeStatus The RangeStatus code as stored on
+ * @a VL53L1_RangingMeasurementData_t
+ * @param pRangeStatusString The returned RangeStatus string. Shall be
+ * defined as char buf[VL53L1_MAX_STRING_LENGTH]
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetRangeStatusString(uint8_t RangeStatus,
+ char *pRangeStatusString);
+
+/**
+ * @brief Human readable error string for driver error status
+ *
+ * @note This function doesn't access to the device
+ *
+ * @param PalErrorCode The error code as stored on @a VL53L1_Error
+ * @param pPalErrorString The error string corresponding to the
+ * PalErrorCode. Shall be defined as char buf[VL53L1_MAX_STRING_LENGTH]
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetPalErrorString(VL53L1_Error PalErrorCode,
+ char *pPalErrorString);
+
+/**
+ * @brief Human readable driver State string
+ *
+ * @note This function doesn't access to the device
+ *
+ * @param PalStateCode The State code as stored on @a VL53L1_State
+ * @param pPalStateString The State string corresponding to the
+ * PalStateCode. Shall be defined as char buf[VL53L1_MAX_STRING_LENGTH]
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetPalStateString(VL53L1_State PalStateCode,
+ char *pPalStateString);
+
+/**
+ * @brief Reads the internal state of the driver for a given Device
+ *
+ * @note This function doesn't access to the device
+ *
+ * @param Dev Device Handle
+ * @param pPalState Pointer to current state of the PAL for a
+ * given Device
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetPalState(VL53L1_DEV Dev,
+ VL53L1_State *pPalState);
+
+
+
+/** @} VL53L1_general_group */
+
+/** @defgroup VL53L1_init_group VL53L1 Init Functions
+ * @brief VL53L1 Init Functions
+ * @{
+ */
+
+/**
+ * @brief Set new device address
+ *
+ * After completion the device will answer to the new address programmed.
+ * This function should be called when several devices are used in parallel
+ * before start programming the sensor.
+ * When a single device us used, there is no need to call this function.
+ *
+ * @note This function Access to the device
+ *
+ * @param Dev Device Handle
+ * @param DeviceAddress The new Device address
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_SetDeviceAddress(VL53L1_DEV Dev,
+ uint8_t DeviceAddress);
+
+/**
+ *
+ * @brief One time device initialization
+ *
+ * To be called once and only once after device is brought out of reset
+ * (Chip enable) and booted see @a VL53L1_WaitDeviceBooted()
+ *
+ * @par Function Description
+ * When not used after a fresh device "power up" or reset, it may return
+ * @a #VL53L1_ERROR_CALIBRATION_WARNING meaning wrong calibration data
+ * may have been fetched from device that can result in ranging offset error\n
+ * If application cannot execute device reset or need to run VL53L1_DataInit
+ * multiple time then it must ensure proper offset calibration saving and
+ * restore on its own by using @a VL53L1_GetOffsetCalibrationData() on first
+ * power up and then @a VL53L1_SetOffsetCalibrationData() in all subsequent init
+ * This function will change the VL53L1_State from VL53L1_STATE_POWERDOWN to
+ * VL53L1_STATE_WAIT_STATICINIT.
+ *
+ * @note This function Access to the device
+ *
+ * @param Dev Device Handle
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_DataInit(VL53L1_DEV Dev);
+
+
+/**
+ * @brief Do basic device init (and eventually patch loading)
+ * This function will change the VL53L1_State from
+ * VL53L1_STATE_WAIT_STATICINIT to VL53L1_STATE_IDLE.
+ * In this stage all default setting will be applied.
+ *
+ * @note This function Access to the device
+ *
+ * @param Dev Device Handle
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_StaticInit(VL53L1_DEV Dev);
+
+/**
+ * @brief Wait for device booted after chip enable (hardware standby)
+ * This function can be run only when VL53L1_State is VL53L1_STATE_POWERDOWN.
+ *
+ * @param Dev Device Handle
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ *
+ */
+VL53L1_Error VL53L1_WaitDeviceBooted(VL53L1_DEV Dev);
+
+
+/** @} VL53L1_init_group */
+
+/** @defgroup VL53L1_parameters_group VL53L1 Parameters Functions
+ * @brief Functions used to prepare and setup the device
+ * @{
+ */
+
+/**
+ * @brief Set a new Preset Mode
+ * @par Function Description
+ * Set device to a new Operating Mode (High speed ranging, Multi objects ...)
+ *
+ * @note This function doesn't Access to the device
+ *
+ * @warning This function change the timing budget to 16 ms and the inter-
+ * measurement period to 1000 ms. Also the VL53L1_DISTANCEMODE_LONG is used.
+ *
+ * @param Dev Device Handle
+ * @param PresetMode New Preset mode to apply
+ *
Valid values are:
+ */
+/**
+ * @li VL53L1_PRESETMODE_LITE_RANGING
+ * @li VL53L1_PRESETMODE_AUTONOMOUS
+ * @li VL53L1_PRESETMODE_LOWPOWER_AUTONOMOUS
+ */
+/**
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return VL53L1_ERROR_MODE_NOT_SUPPORTED This error occurs when PresetMode is
+ * not in the supported list
+ */
+VL53L1_Error VL53L1_SetPresetMode(VL53L1_DEV Dev,
+ VL53L1_PresetModes PresetMode);
+
+/**
+ * @brief Get current Preset Mode
+ * @par Function Description
+ * Get actual mode of the device(ranging, histogram ...)
+ *
+ * @note This function doesn't Access to the device
+ *
+ * @param Dev Device Handle
+ * @param pPresetMode Pointer to current apply mode value
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return VL53L1_ERROR_MODE_NOT_SUPPORTED This error occurs when
+ * DeviceMode is not in the supported list
+ */
+VL53L1_Error VL53L1_GetPresetMode(VL53L1_DEV Dev,
+ VL53L1_PresetModes *pPresetMode);
+
+
+/**
+ * @brief Set the distance mode
+ * @par Function Description
+ * Set the distance mode to be used for the next ranging.
+ * The modes Short, Medium and Long are used to optimize the ranging accuracy
+ * in a specific range of distance.
The user select one of these modes to
+ * select the distance range.
+ * @note This function doesn't Access to the device
+ *
+ * @warning This function should be called after @a VL53L1_SetPresetMode().
+
+ * @param Dev Device Handle
+ * @param DistanceMode Distance mode to apply, valid values are:
+ * @li VL53L1_DISTANCEMODE_SHORT
+ * @li VL53L1_DISTANCEMODE_MEDIUM
+ * @li VL53L1_DISTANCEMODE_LONG
+ * @return VL53L1_ERROR_NONE Success
+ * @return VL53L1_ERROR_MODE_NOT_SUPPORTED This error occurs when DistanceMode
+ * is not in the supported list
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_SetDistanceMode(VL53L1_DEV Dev,
+ VL53L1_DistanceModes DistanceMode);
+
+/**
+ * @brief Get the distance mode
+ * @par Function Description
+ * Get the distance mode used for the next ranging.
+ *
+ * @param Dev Device Handle
+ * @param *pDistanceMode Pointer to Distance mode
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetDistanceMode(VL53L1_DEV Dev,
+ VL53L1_DistanceModes *pDistanceMode);
+
+
+
+
+/**
+ * @brief Set Ranging Timing Budget in microseconds
+ *
+ * @par Function Description
+ * Defines the maximum time allowed by the user to the device to run a
+ * full ranging sequence for the current mode (ranging, histogram, ASL ...)
+ *
+ * @param Dev Device Handle
+ * @param MeasurementTimingBudgetMicroSeconds Max measurement time in
+ * microseconds.
+ * @return VL53L1_ERROR_NONE Success
+ * @return VL53L1_ERROR_INVALID_PARAMS Error timing parameter not
+ * supported.
+ * The maximum accepted value for the
+ * computed timing budget is 10 seconds
+ * the minimum value depends on the preset
+ * mode selected.
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_SetMeasurementTimingBudgetMicroSeconds(
+ VL53L1_DEV Dev, uint32_t MeasurementTimingBudgetMicroSeconds);
+
+/**
+ * @brief Get Ranging Timing Budget in microseconds
+ *
+ * @par Function Description
+ * Returns the programmed the maximum time allowed by the user to the
+ * device to run a full ranging sequence for the current mode
+ * (ranging, histogram, ASL ...)
+ *
+ * @param Dev Device Handle
+ * @param pMeasurementTimingBudgetMicroSeconds Max measurement time in
+ * microseconds.
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetMeasurementTimingBudgetMicroSeconds(
+ VL53L1_DEV Dev, uint32_t *pMeasurementTimingBudgetMicroSeconds);
+
+
+/**
+ * Program continuous mode Inter-Measurement period in milliseconds
+ *
+ * @par Function Description
+ * When trying to set too short time return INVALID_PARAMS minimal value
+ *
+ * @param Dev Device Handle
+ * @param InterMeasurementPeriodMilliSeconds Inter-Measurement Period in ms.
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_SetInterMeasurementPeriodMilliSeconds(
+ VL53L1_DEV Dev, uint32_t InterMeasurementPeriodMilliSeconds);
+
+/**
+ * Get continuous mode Inter-Measurement period in milliseconds
+ *
+ * @par Function Description
+ *
+ * @param Dev Device Handle
+ * @param pInterMeasurementPeriodMilliSeconds Pointer to programmed
+ * Inter-Measurement Period in milliseconds.
+ * @return VL53L1_ERROR_NONE
+ */
+VL53L1_Error VL53L1_GetInterMeasurementPeriodMilliSeconds(
+ VL53L1_DEV Dev, uint32_t *pInterMeasurementPeriodMilliSeconds);
+
+
+/** @} VL53L1_parameters_group */
+
+
+/** @defgroup VL53L1_limitcheck_group VL53L1 Limit Check Functions
+ * @brief Functions used for the Limit checks
+ * @{
+ */
+
+
+
+/**
+ * @brief Get the number of the check limit managed by a given Device
+ *
+ * @par Function Description
+ * This function give the number of the check limit managed by the Device
+ *
+ * @param pNumberOfLimitCheck Pointer to the number of check limit.
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetNumberOfLimitCheck(
+ uint16_t *pNumberOfLimitCheck);
+
+/**
+ * @brief Return a description string for a given limit check number
+ *
+ * @par Function Description
+ * This function returns a description string for a given limit check number.
+ * The limit check is identified with the LimitCheckId.
+ *
+ * @param LimitCheckId Limit Check ID
+ (0<= LimitCheckId < VL53L1_GetNumberOfLimitCheck() ).
+ * @param pLimitCheckString Pointer to the description string of
+ * the given check limit. Shall be defined as char buf[VL53L1_MAX_STRING_LENGTH]
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetLimitCheckInfo(uint16_t LimitCheckId,
+ char *pLimitCheckString);
+
+/**
+ * @brief Return a the Status of the specified check limit
+ *
+ * @par Function Description
+ * This function returns the Status of the specified check limit.
+ * The value indicate if the check is fail or not.
+ * The limit check is identified with the LimitCheckId.
+ *
+ * @param Dev Device Handle
+ * @param LimitCheckId Limit Check ID
+ (0<= LimitCheckId < VL53L1_GetNumberOfLimitCheck() ).
+ * @param pLimitCheckStatus Pointer to the
+ Limit Check Status of the given check limit.
+ * LimitCheckStatus :
+ * 0 the check is not fail or not enabled
+ * 1 the check if fail
+ *
+ *
+ * - VL53L1_CHECKENABLE_SIGMA_FINAL_RANGE: the sigma indicate the quality
+ * of the measure. The more it is little the better it is.
+ * The status is 1 when current sigma is greater then the limit.
+ * - VL53L1_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE: the signal rate indicate
+ * the strength of the returned signal. The more it is big the better it is.
+ * The status is 1 when current signal is lower then the limit.
+ *
+ *
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetLimitCheckStatus(VL53L1_DEV Dev,
+ uint16_t LimitCheckId, uint8_t *pLimitCheckStatus);
+
+/**
+ * @brief Enable/Disable a specific limit check
+ *
+ * @par Function Description
+ * This function Enable/Disable a specific limit check.
+ * The limit check is identified with the LimitCheckId.
+ *
+ * @note This function doesn't Access to the device
+ *
+ * @param Dev Device Handle
+ * @param LimitCheckId Limit Check ID
+ * (0<= LimitCheckId < VL53L1_GetNumberOfLimitCheck() ).
+ * @param LimitCheckEnable
+ * @li set LimitCheckEnable=1 enables the LimitCheckId limit
+ * @li set LimitCheckEnable=0 disables the LimitCheckId limit
+ * @return VL53L1_ERROR_NONE Success
+ * @return VL53L1_ERROR_INVALID_PARAMS This error is returned
+ * when LimitCheckId value is out of range.
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_SetLimitCheckEnable(VL53L1_DEV Dev,
+ uint16_t LimitCheckId, uint8_t LimitCheckEnable);
+
+/**
+ * @brief Get specific limit check enable state
+ *
+ * @par Function Description
+ * This function get the enable state of a specific limit check.
+ * The limit check is identified with the LimitCheckId.
+ *
+ * @note This function Access to the device
+ *
+ * @param Dev Device Handle
+ * @param LimitCheckId Limit Check ID
+ * (0<= LimitCheckId < VL53L1_GetNumberOfLimitCheck() ).
+ * @param pLimitCheckEnable Pointer to the check limit enable
+ * value.
+ * @li if 1 the check limit corresponding to LimitCheckId is Enabled
+ * @li if 0 the check limit corresponding to LimitCheckId is disabled
+ * @return VL53L1_ERROR_NONE Success
+ * @return VL53L1_ERROR_INVALID_PARAMS This error is returned
+ * when LimitCheckId value is out of range.
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetLimitCheckEnable(VL53L1_DEV Dev,
+ uint16_t LimitCheckId, uint8_t *pLimitCheckEnable);
+
+/**
+ * @brief Set a specific limit check value
+ *
+ * @par Function Description
+ * This function set a specific limit check value.
+ * The limit check is identified with the LimitCheckId.
+ *
+ * @note Note that the value written with that function will not be applied if
+ * the limit is not enabled. In other words this function will not enable the
+ * limit but change only the value. In case the limit is not enabled the value
+ * is saved internally and applied with VL53L1_SetLimitCheckEnable.
+ *
+ * @param Dev Device Handle
+ * @param LimitCheckId Limit Check ID
+ * (0<= LimitCheckId < VL53L1_GetNumberOfLimitCheck() ).
+ * @param LimitCheckValue Limit check Value for a given
+ * LimitCheckId
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_SetLimitCheckValue(VL53L1_DEV Dev,
+ uint16_t LimitCheckId, FixPoint1616_t LimitCheckValue);
+
+/**
+ * @brief Get a specific limit check value
+ *
+ * @par Function Description
+ * This function get a specific limit check value from device then it updates
+ * internal values and check enables.
+ * The limit check is identified with the LimitCheckId.
+ *
+ * @note This function get the current value from device if zero then the value
+ * returned is the one stored by the user, but in that case the check is store
+ * as disabled. If the value from device is not zero, this is returned and set
+ * into the memory at the same way that user call VL53L1_SetLimitCheckValue()
+ *
+ * @param Dev Device Handle
+ * @param LimitCheckId Limit Check ID
+ * (0<= LimitCheckId < VL53L1_GetNumberOfLimitCheck() ).
+ * @param pLimitCheckValue Pointer to Limit
+ * check Value for a given LimitCheckId.
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetLimitCheckValue(VL53L1_DEV Dev,
+ uint16_t LimitCheckId, FixPoint1616_t *pLimitCheckValue);
+
+/**
+ * @brief Get the current value of the signal used for the limit check
+ *
+ * @par Function Description
+ * This function get a the current value of the signal used for the limit check.
+ * To obtain the latest value you should run a valid ranging before.
+ * The value reported is linked to the limit check identified with the
+ * LimitCheckId.
+ *
+ * @param Dev Device Handle
+ * @param LimitCheckId Limit Check ID
+ * (0<= LimitCheckId < VL53L1_GetNumberOfLimitCheck() ).
+ * @param pLimitCheckCurrent Pointer to current Value for a
+ * given LimitCheckId.
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetLimitCheckCurrent(VL53L1_DEV Dev,
+ uint16_t LimitCheckId, FixPoint1616_t *pLimitCheckCurrent);
+
+/** @} VL53L1_limitcheck_group */
+
+
+
+/** @defgroup VL53L1_ROI_group VL53L1 ROI Functions
+ * @brief Functions used to select ROIs
+ * @{
+ */
+
+/**
+ * @brief Set the ROI to be used for ranging
+ *
+ * @par Function Description
+ * The user defined ROI is a rectangle described as per the following system
+ * from the Top Left corner to the Bottom Right corner.
+ *
Minimal ROI size is 4x4 spads
+ * @image html roi_coord.png
+ *
+ * @param Dev Device Handle
+ * @param pUserROi Pointer to the Structure definining the ROI
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_SetUserROI(VL53L1_DEV Dev,
+ VL53L1_UserRoi_t *pUserROi);
+
+/**
+ * @brief Get the ROI managed by the Device
+ *
+ * @par Function Description
+ * Get the ROI managed by the Device
+ *
+ * @param Dev Device Handle
+ * @param pUserROi Pointer to the Structure definining the ROI
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetUserROI(VL53L1_DEV Dev,
+ VL53L1_UserRoi_t *pUserROi);
+
+/** @} VL53L1_ROI_group */
+
+/* \internal */
+/** @defgroup VL53L1_sequencestep_group VL53L1 Sequence Step Functions
+ * @brief Functions used to select Steps done on each ranging
+ * @{
+ */
+
+/**
+ * @brief Gets number of sequence steps managed by the API.
+ *
+ * @par Function Description
+ * This function retrieves the number of sequence steps currently managed
+ * by the API
+ *
+ * @note This function Accesses the device
+ *
+ * @param Dev Device Handle
+ * @param pNumberOfSequenceSteps Out parameter reporting the number of
+ * sequence steps.
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetNumberOfSequenceSteps(VL53L1_DEV Dev,
+ uint8_t *pNumberOfSequenceSteps);
+
+/**
+ * @brief Gets the name of a given sequence step.
+ *
+ * @par Function Description
+ * This function retrieves the name of sequence steps corresponding to
+ * SequenceStepId.
+ *
+ * @note This function doesn't Accesses the device
+ *
+ * @param SequenceStepId Sequence step identifier.
+ * @param pSequenceStepsString Pointer to Info string. Shall be
+ * defined as char buf[VL53L1_MAX_STRING_LENGTH]
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetSequenceStepsInfo(
+ VL53L1_SequenceStepId SequenceStepId, char *pSequenceStepsString);
+
+
+
+/**
+ * @brief Sets the (on/off) state of a requested sequence step.
+ *
+ * @par Function Description
+ * This function enables/disables a requested sequence step.
+ *
+ * @note This function Accesses the device
+ *
+ * @param Dev Device Handle
+ * @param SequenceStepId Sequence step identifier.
+ * @param SequenceStepEnabled Demanded state {0=Off,1=On}
+ * is enabled.
+ * @return VL53L1_ERROR_NONE Success
+ * @return VL53L1_ERROR_INVALID_PARAMS Error SequenceStepId parameter not
+ * supported.
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_SetSequenceStepEnable(VL53L1_DEV Dev,
+ VL53L1_SequenceStepId SequenceStepId, uint8_t SequenceStepEnabled);
+
+/**
+ * @brief Gets the (on/off) state of a requested sequence step.
+ *
+ * @par Function Description
+ * This function retrieves the state of a requested sequence step, i.e. on/off.
+ *
+ * @note This function Accesses the device
+ *
+ * @param Dev Device Handle
+ * @param SequenceStepId Sequence step identifier.
+ * @param pSequenceStepEnabled Out parameter reporting if the sequence step
+ * is enabled {0=Off,1=On}.
+ * @return VL53L1_ERROR_NONE Success
+ * @return VL53L1_ERROR_INVALID_PARAMS Error SequenceStepId parameter not
+ * supported.
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetSequenceStepEnable(VL53L1_DEV Dev,
+ VL53L1_SequenceStepId SequenceStepId, uint8_t *pSequenceStepEnabled);
+
+
+/** @} VL53L1_sequencestep_group */
+/* \endinternal */
+
+
+
+/** @defgroup VL53L1_measurement_group VL53L1 Measurement Functions
+ * @brief Functions used for the measurements
+ * @{
+ */
+
+/**
+ * @brief Start device measurement
+ *
+ * @details Started measurement will depend on preset parameters set through
+ * @a VL53L1_SetPreseMode()
+ * This function will change the VL53L1_State from VL53L1_STATE_IDLE to
+ * VL53L1_STATE_RUNNING.
+ *
+ * @note This function Access to the device
+ *
+ * @param Dev Device Handle
+ * @return VL53L1_ERROR_NONE Success
+ * @return VL53L1_ERROR_MODE_NOT_SUPPORTED This error occurs when
+ * PresetMode programmed with @a VL53L1_SetPresetMode
+ *
+ * @return VL53L1_ERROR_TIME_OUT Time out on start measurement
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_StartMeasurement(VL53L1_DEV Dev);
+
+/**
+ * @brief Stop device measurement
+ *
+ * @details Will set the device in standby mode at end of current measurement\n
+ * Not necessary in single mode as device shall return automatically
+ * in standby mode at end of measurement.
+ * This function will change the VL53L1_State from VL53L1_STATE_RUNNING
+ * to VL53L1_STATE_IDLE.
+ *
+ * @note This function Access to the device
+ *
+ * @param Dev Device Handle
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_StopMeasurement(VL53L1_DEV Dev);
+
+/**
+ * @brief Clear the Interrupt flag and start new measurement
+ * *
+ * @note This function Access to the device
+ *
+ * @param Dev Device Handle
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_ClearInterruptAndStartMeasurement(VL53L1_DEV Dev);
+
+/**
+ * @brief Return Measurement Data Ready
+ *
+ * @par Function Description
+ * This function indicate that a measurement data is ready.
+ * This function is used for non-blocking capture.
+ *
+ * @note This function Access to the device
+ *
+ * @param Dev Device Handle
+ * @param pMeasurementDataReady Pointer to Measurement Data Ready.
+ * 0 = data not ready, 1 = data ready
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetMeasurementDataReady(VL53L1_DEV Dev,
+ uint8_t *pMeasurementDataReady);
+
+/**
+ * @brief Wait for measurement data ready.
+ * Blocking function.
+ * Note that the timeout is given by:
+ * VL53L1_RANGE_COMPLETION_POLLING_TIMEOUT_MS defined in def.h
+ *
+ *
+ * @note This function Access to the device
+ *
+ * @param Dev Device Handle
+ * @return VL53L1_ERROR_NONE Success
+ * @return VL53L1_ERROR_TIME_OUT In case of timeout
+ */
+VL53L1_Error VL53L1_WaitMeasurementDataReady(VL53L1_DEV Dev);
+
+
+/**
+ * @brief Retrieve the measurements from device for a given setup
+ *
+ * @par Function Description
+ * Get data from last successful Ranging measurement
+ */
+/**
+ *
+ * @warning USER must call @a VL53L1_ClearInterruptAndStartMeasurement() prior
+ * to call again this function
+ *
+ * @note This function Access to the device
+ *
+ * @note The first valid value returned by this function will have a range
+ * status equal to VL53L1_RANGESTATUS_RANGE_VALID_NO_WRAP_CHECK which means that
+ * the data is valid but no wrap around check have been done. User should take
+ * care about that.
+ *
+ * @param Dev Device Handle
+ * @param pRangingMeasurementData Pointer to the data structure to fill up.
+ * @return VL53L1_ERROR_NONE Success
+ * @return VL53L1_ERROR_MODE_NOT_SUPPORTED in case of MULTIZONES_SCANNING
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetRangingMeasurementData(VL53L1_DEV Dev,
+ VL53L1_RangingMeasurementData_t *pRangingMeasurementData);
+
+
+
+/** @} VL53L1_measurement_group */
+
+/** @defgroup VL53L1_Calibration_group VL53L1 Calibration Functions
+ * @brief Functions used for Calibration
+ * @{
+ */
+
+
+/**
+ * @brief Set Tuning Parameter value for a given parameter ID
+ *
+ * @par Function Description
+ * This function is used to improve the performance of the device. It permit to
+ * change a particular value used for a timeout or a threshold or a constant
+ * in an algorithm. The function will change the value of the parameter
+ * identified by an unique ID.
+ *
+ * @note This function doesn't Access to the device
+ *
+ * @param Dev Device Handle
+ * @param TuningParameterId Tuning Parameter ID
+ * @param TuningParameterValue Tuning Parameter Value
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_SetTuningParameter(VL53L1_DEV Dev,
+ uint16_t TuningParameterId, int32_t TuningParameterValue);
+
+/**
+ * @brief Get Tuning Parameter value for a given parameter ID
+ *
+ * @par Function Description
+ * This function is used to get the value of the parameter
+ * identified by an unique ID.
+ *
+ * @note This function doesn't Access to the device
+ *
+ * @param Dev Device Handle
+ * @param TuningParameterId Tuning Parameter ID
+ * @param pTuningParameterValue Pointer to Tuning Parameter Value
+ * for a given TuningParameterId.
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetTuningParameter(VL53L1_DEV Dev,
+ uint16_t TuningParameterId, int32_t *pTuningParameterValue);
+
+/**
+ * @brief Performs Reference Spad Management
+ *
+ * @par Function Description
+ * The reference SPAD initialization procedure determines the minimum amount
+ * of reference spads to be enables to achieve a target reference signal rate
+ * and should be performed once during initialization.
+ *
+ * @note This function Access to the device
+ *
+ * @param Dev Device Handle
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_PerformRefSpadManagement(VL53L1_DEV Dev);
+
+
+/**
+ * @brief Enable/Disable Cross talk compensation feature
+ *
+ * Enable/Disable Cross Talk correction.
+ *
+ * @param Dev Device Handle
+ * @param XTalkCompensationEnable Cross talk compensation
+ * to be set 0 = disabled or 1 = enabled.
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+*/
+VL53L1_Error VL53L1_SetXTalkCompensationEnable(VL53L1_DEV Dev,
+uint8_t XTalkCompensationEnable);
+
+/**
+ * @brief Get Cross talk compensation rate enable
+ *
+ * Get if the Cross Talk is Enabled or Disabled.
+ *
+ * @note This function doesn't access to the device
+ *
+ * @param Dev Device Handle
+ * @param pXTalkCompensationEnable Pointer to the Cross talk compensation
+ * state 0=disabled or 1 = enabled
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetXTalkCompensationEnable(VL53L1_DEV Dev,
+ uint8_t *pXTalkCompensationEnable);
+
+/**
+ * @brief Perform XTalk Calibration
+ *
+ * @details Perform a XTalk calibration of the Device.
+ * This function will launch a ranging measurement, if interrupts
+ * are enabled an interrupt will be done.
+ * This function will clear the interrupt generated automatically.
+ * This function will program a new value for the XTalk compensation
+ * and it will enable the cross talk before exit.
+ *
+ * @warning This function is a blocking function
+ *
+ * @note This function Access to the device
+ *
+ * @param Dev Device Handle
+ * @param XTalkCalDistance Target distance in mm
+ * The calibration uses current preset and distance mode without altering them.
+ *
User must call @a VL53L1_SetPresetMode() with
+ * VL53L1_PRESETMODE_AUTONOMOUS, VL53L1_PRESETMODE_LITE_RANGING or
+ * VL53L1_PRESETMODE_LOWPOWER_AUTONOMOUS parameter prior to launch calibration
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_PerformSingleTargetXTalkCalibration(VL53L1_DEV Dev,
+ int32_t XTalkCalDistance);
+
+
+/**
+ * @brief Define the mode to be used for the offset calibration
+ *
+ * Define the mode to be used for the offset calibration. This function should
+ * be called before run the @a VL53L1_PerformOffsetCalibration()
+ *
+ * @param Dev Device Handle
+ * @param OffsetCalibrationMode Offset Calibration Mode valid values are:
+ * @li VL53L1_OFFSETCALIBRATIONMODE_STANDARD
+ * @li VL53L1_OFFSETCALIBRATIONMODE_PRERANGE_ONLY
+ */
+/**
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_SetOffsetCalibrationMode(VL53L1_DEV Dev,
+ VL53L1_OffsetCalibrationModes OffsetCalibrationMode);
+
+
+
+/**
+ * @brief Perform Offset Calibration
+ *
+ * @details Perform a Offset calibration of the Device.
+ * This function will launch a ranging measurement, if interrupts are
+ * enabled interrupts will be done.
+ * This function will program a new value for the Offset calibration value
+ *
+ * @warning This function is a blocking function
+ *
+ * @note This function Access to the device
+ *
+ * @param Dev Device Handle
+ * @param CalDistanceMilliMeter Calibration distance value used for the
+ * offset compensation.
+ *
+ * @return VL53L1_ERROR_NONE
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_PerformOffsetCalibration(VL53L1_DEV Dev,
+ int32_t CalDistanceMilliMeter);
+
+/**
+ * @brief Perform Offset simple Calibration
+ *
+ * @details Perform a very simple offset calibration of the Device.
+ * This function will launch few ranging measurements and computes offset
+ * calibration. The preset mode and the distance mode MUST be set by the
+ * application before to call this function.
+ *
+ * @warning This function is a blocking function
+ *
+ * @note This function Access to the device
+ *
+ * @param Dev Device Handle
+ * @param CalDistanceMilliMeter Calibration distance value used for the
+ * offset compensation.
+ *
+ * @return VL53L1_ERROR_NONE
+ * @return VL53L1_ERROR_OFFSET_CAL_NO_SAMPLE_FAIL the calibration failed by
+ * lack of valid measurements
+ * @return VL53L1_WARNING_OFFSET_CAL_SIGMA_TOO_HIGH means that the target
+ * distance combined to the number of loops performed in the calibration lead to
+ * an internal overflow. Try to reduce the distance of the target (140 mm)
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_PerformOffsetSimpleCalibration(VL53L1_DEV Dev,
+ int32_t CalDistanceMilliMeter);
+
+/**
+ * @brief Sets the Calibration Data.
+ *
+ * @par Function Description
+ * This function set all the Calibration Data issued from the functions
+ * @a VL53L1_PerformRefSpadManagement(), @a VL53L1_PerformXTalkCalibration,
+ * @a VL53L1_PerformOffsetCalibration()
+ *
+ * @note This function doesn't Accesses the device
+ *
+ * @param Dev Device Handle
+ * @param *pCalibrationData Pointer to Calibration data to be set.
+ * @return VL53L1_ERROR_NONE Success
+ * @return VL53L1_ERROR_INVALID_PARAMS pCalibrationData points to an older
+ * version of the inner structure. Need for support to convert its content.
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_SetCalibrationData(VL53L1_DEV Dev,
+ VL53L1_CalibrationData_t *pCalibrationData);
+
+/**
+ * @brief Gets the Calibration Data.
+ *
+ * @par Function Description
+ * This function get all the Calibration Data issued from the functions
+ * @a VL53L1_PerformRefSpadManagement(), @a VL53L1_PerformXTalkCalibration,
+ * @a VL53L1_PerformOffsetCalibration()
+ *
+ * @note This function doesn't Accesses the device
+ *
+ * @param Dev Device Handle
+ * @param *pCalibrationData pointer where to store Calibration
+ * data.
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetCalibrationData(VL53L1_DEV Dev,
+ VL53L1_CalibrationData_t *pCalibrationData);
+
+/**
+ * @brief Gets the optical center.
+ *
+ * @par Function Description
+ * This function get the optical center issued from the nvm set at FTM stage
+ * expressed in the same coordinate system as the ROI are
+ *
+ * @note This function doesn't Accesses the device
+ *
+ * @param Dev Device Handle
+ * @param *pOpticalCentreX pointer to the X position of center
+ * in 16.16 fix point
+ * @param *pOpticalCentreY pointer to the Y position of center
+ * in 16.16 fix point
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_GetOpticalCenter(VL53L1_DEV Dev,
+ FixPoint1616_t *pOpticalCenterX,
+ FixPoint1616_t *pOpticalCenterY);
+
+/** @} VL53L1_Calibration_group */
+
+/** @defgroup VL53L1_Thresholds_group VL53L1 IRQ Triggered events Functions
+ * @brief Functions used to configure interrupt to be triggered only when
+ * a measurement satisfies some thresholds parameters
+ * @{
+ */
+
+/**
+* @brief Configure the interrupt config, from the given structure
+*
+* @param[in] Dev : Device Handle
+* @param[in] pConfig : pointer to configuration structure
+*/
+
+VL53L1_Error VL53L1_SetThresholdConfig(VL53L1_DEV Dev,
+ VL53L1_DetectionConfig_t *pConfig);
+
+/**
+* @brief Retrieves the interrupt config structure currently programmed
+* into the API
+*
+* @param[in] Dev : Device Handle
+* @param[out] pConfig : pointer to configuration structure
+*/
+
+VL53L1_Error VL53L1_GetThresholdConfig(VL53L1_DEV Dev,
+ VL53L1_DetectionConfig_t *pConfig);
+
+
+/** @} VL53L1_Thresholds_group */
+
+
+/** @} VL53L1_cut11_group */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _VL53L1_API_H_ */
diff --git a/src/lib/vl53l1/core/inc/vl53l1_api_calibration.h b/src/lib/vl53l1/core/inc/vl53l1_api_calibration.h
new file mode 100644
index 0000000000..5ebfaaf07d
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_api_calibration.h
@@ -0,0 +1,202 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*******************************************************************************/
+
+/**
+ * @file vl53l1_api_core.h
+ *
+ * @brief EwokPlus25 low level API function definitions
+ */
+
+#ifndef _VL53L1_API_CALIBRATION_H_
+#define _VL53L1_API_CALIBRATION_H_
+
+#include "vl53l1_platform.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+/**
+ * @brief Run Reference Array SPAD Characterisation.
+ *
+ * This function finds the required number of reference SPAD
+ * to meet the input required peak reference rate.
+ *
+ * The algorithm first tries the non apertured reference SPAD's,
+ * if the rate is too high for the minimum allowed SPAD count (5)
+ * then the algo switches to 5x apertured SPAD's and if the rate
+ * is still to high then the 10x apertured SPAD are selected.
+ *
+ * The function reads the following results from the device and
+ * both caches the values in the pdev->customer structure and
+ * writes the data into the G02 customer register group.
+ *
+ * - num_ref_spads
+ * - ref_location
+ * - DCR SPAD enables for selected reference location
+ *
+ * Note power force is enabled as the function needs to read
+ * data from the Patch RAM.
+ *
+ * Should only be called once per part with coverglass attached to
+ * generate the required num of SPAD, Ref location and DCR SPAD enable
+ * data
+ *
+ * @param[in] Dev : Device Handle
+ * @param[out] pcal_status : Pointer to unfiltered calibration status
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return VL53L1_WARNING_REF_SPAD_CHAR_NOT_ENOUGH_SPADS
+ * Less than 5 Good SPAD available, output not valid
+ * @return VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_HIGH
+ * At end of search reference rate > 40.0 Mcps
+ * Offset stability may be degraded.
+ * @return VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_LOW
+ * At end of search reference rate < 10.0 Mcps
+ * Offset stability may be degraded.
+ *
+ */
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_run_ref_spad_char(VL53L1_DEV Dev, VL53L1_Error *pcal_status);
+#endif
+
+
+/**
+ * @brief Runs the input Device Test
+ *
+ * Calls
+ *
+ * - VL53L1_enable_powerforce()
+ * - VL53L1_start_test()
+ * - VL53L1_poll_for_range_completion()
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] device_test_mode : Device test mode register value
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_run_device_test(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceTestMode device_test_mode);
+#endif
+
+
+/**
+ * @brief Runs SPAD rate map
+ *
+ * Output structure contains SPAD rate data in SPAD number order
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] device_test_mode : Device test mode register value.
+ * Valid options: \n
+ * - VL53L1_DEVICETESTMODE_LCR_VCSEL_OFF \n
+ * - VL53L1_DEVICETESTMODE_LCR_VCSEL_ON
+ * @param[in] array_select : Device SPAD array select
+ * Valid options: \n
+ * - VL53L1_DEVICESSCARRAY_RTN \n
+ * - VL53L1_DEVICESSCARRAY_REF
+ * @param[in] ssc_config_timeout_us : SSC timeout in [us] e.g 36000us
+ * @param[out] pspad_rate_data : pointer to output rates structure
+ * 1.15 format for LCR_VCSEL_OFF
+ * 9.7 format for LCR_VCSEL_ON
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_run_spad_rate_map(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceTestMode device_test_mode,
+ VL53L1_DeviceSscArray array_select,
+ uint32_t ssc_config_timeout_us,
+ VL53L1_spad_rate_data_t *pspad_rate_data);
+#endif
+
+
+/**
+ * @brief Run offset calibration
+ *
+ * Runs the standard ranging MM1 and MM2 calibration presets
+ * to generate the MM1 and MM2 range offset data
+ *
+ * The range config timeout is used for both MM1 and MM2 so that
+ * the sigma delta settling is the same as for the 'real' range
+ *
+ * Places results into VL53L1_customer_nvm_managed_t within pdev
+ *
+ * Use VL53L1_get_part_to_part_data() to get the offset calibration
+ * results
+ *
+ * Current FMT settings:
+ *
+ * - offset_calibration_mode = VL53L1_OFFSETCALIBRATIONMODE__STANDARD_RANGING
+ * - dss_config__target_total_rate_mcps = 0x0A00 (20.0Mcps) to 0x1400 (40.0Mcps)
+ * - phasecal_config_timeout_us = 1000
+ * - range_config_timeout_us = 13000
+ * - pre_num_of_samples = 32
+ * - mm1_num_of_samples = 100
+ * - mm2_range_num_of_samples = 64
+ * - target_distance_mm = 140 mm
+ * - target reflectance = 5%
+ *
+ * Note: function parms simplified as part of Patch_CalFunctionSimplification_11791
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] cal_distance_mm : Distance to target in [mm] - the ground truth
+ * @param[out] pcal_status : Pointer to unfiltered calibration status
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return VL53L1_WARNING_OFFSET_CAL_INSUFFICIENT_MM1_SPADS
+ * Effective MM1 SPAD count too low (<5.0).
+ * Out with recommended calibration condition.
+ * Accuracy of offset calibration may be degraded.
+ * @return VL53L1_WARNING_OFFSET_CAL_PRE_RANGE_RATE_TOO_HIGH
+ * Pre range too high (>40.0) in pile up region.
+ * Out with recommended calibration condition.
+ * Accuracy of offset calibration may be degraded.
+ */
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_run_offset_calibration(
+ VL53L1_DEV Dev,
+ int16_t cal_distance_mm,
+ VL53L1_Error *pcal_status);
+#endif
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _VL53L1_API_CALIBRATION_H_ */
diff --git a/src/lib/vl53l1/core/inc/vl53l1_api_core.h b/src/lib/vl53l1/core/inc/vl53l1_api_core.h
new file mode 100644
index 0000000000..f3721b3d54
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_api_core.h
@@ -0,0 +1,1153 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*******************************************************************************/
+
+/**
+ * @file vl53l1_api_core.h
+ *
+ * @brief EwokPlus25 low level API function definitions
+ */
+
+#ifndef _VL53L1_API_CORE_H_
+#define _VL53L1_API_CORE_H_
+
+#include "vl53l1_platform.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+/**
+ * @brief Get LL Driver version information
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] pversion : pointer to VL53L1_ll_version_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ */
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_get_version(
+ VL53L1_DEV Dev,
+ VL53L1_ll_version_t *pversion);
+
+/**
+ * @brief Gets Device Firmware version
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] pfw_version : pointer to uint16_t FW version
+ *
+ * @return VL53L1_ERROR_NONE Success
+ */
+
+VL53L1_Error VL53L1_get_device_firmware_version(
+ VL53L1_DEV Dev,
+ uint16_t *pfw_version);
+#endif
+
+
+/**
+ * @brief Initialises pdev structure and optionally read the
+ * part to part information form he device G02 registers
+ *
+ * Important: VL53L1_platform_initialise() *must* called before calling
+ * this function
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] read_p2p_data : if > 0 then reads and caches P2P data
+ *
+ * @return VL53L1_ERROR_NONE Success
+ */
+
+VL53L1_Error VL53L1_data_init(
+ VL53L1_DEV Dev,
+ uint8_t read_p2p_data);
+
+
+/**
+ * @brief For C-API one time initialization only reads device
+ * G02 registers containing data copied from NVM
+ *
+ * Contains the key NVM data e.g identification info
+ * fast oscillator freq, max trim and laser safety info
+ *
+ * Function all only be called after the device has finished booting
+ *
+ * @param[in] Dev : Device handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ */
+
+VL53L1_Error VL53L1_read_p2p_data(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Performs device software reset and then waits for the firmware
+ * to finish booting
+ *
+ * @param[in] Dev : Device handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_software_reset(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Sets the customer part to part data
+ *
+ * Important: does **not** apply the settings to the device.
+ * Updates the following structures in the device structure
+ *
+ * Just an internal memcpy to
+ *
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] pcal_data : pointer to VL53L1_calibration_data_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_part_to_part_data(
+ VL53L1_DEV Dev,
+ VL53L1_calibration_data_t *pcal_data);
+
+
+/**
+ * @brief Gets the customer part to part data
+ *
+ * Just an internal memory copy
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] pcal_data : pointer to VL53L1_calibration_data_t
+ *
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_part_to_part_data(
+ VL53L1_DEV Dev,
+ VL53L1_calibration_data_t *pcal_data);
+
+
+/**
+ * @brief Gets the tuning parm part to part data
+ *
+ * Just an internal copy
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] ptun_data : pointer to VL53L1_tuning_parameters_t
+ *
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_get_tuning_debug_data(
+ VL53L1_DEV Dev,
+ VL53L1_tuning_parameters_t *ptun_data);
+#endif
+
+
+/**
+ * @brief Sets the inter measurement period in the VL53L1_timing_config_t structure
+ *
+ * Uses the pdev->dbg_results.result__osc_calibrate_val value convert from [ms]
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] inter_measurement_period_ms : requested inter measurement period in [ms]
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_inter_measurement_period_ms(
+ VL53L1_DEV Dev,
+ uint32_t inter_measurement_period_ms);
+
+
+/**
+ * @brief Gets inter measurement period from the VL53L1_timing_config_t structure
+ *
+ * Uses the pdev->dbg_results.result__osc_calibrate_val value convert into [ms]
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] pinter_measurement_period_ms : current inter measurement period in [ms]
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_inter_measurement_period_ms(
+ VL53L1_DEV Dev,
+ uint32_t *pinter_measurement_period_ms);
+
+
+/**
+ * @brief Sets the phasecal, mode mitigation and ranging timeouts
+ * in the VL53L1_timing_config_t structure
+ *
+ * Uses the pdev->stat_nvm.osc_measured__fast_osc__frequency value convert from [us]
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] phasecal_config_timeout_us : requested Phase Cal Timeout e.g. 1000us
+ * @param[in] mm_config_timeout_us : requested MM Timeout e.g. 2000us
+ * @param[in] range_config_timeout_us : requested Ranging Timeout e.g 13000us
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_timeouts_us(
+ VL53L1_DEV Dev,
+ uint32_t phasecal_config_timeout_us,
+ uint32_t mm_config_timeout_us,
+ uint32_t range_config_timeout_us);
+
+
+/**
+ * @brief Gets the phasecal, mode mitigation and ranging timeouts
+ * for the VL53L1_timing_config_t structure
+ *
+ * Uses the pdev->stat_nvm.osc_measured__fast_osc__frequency convert into [us]
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] pphasecal_config_timeout_us : current Phase Cal Timeout in [us]
+ * @param[out] pmm_config_timeout_us : current MM Timeout in [us]
+ * @param[out] prange_config_timeout_us : current Ranging Timeout in [us]
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_timeouts_us(
+ VL53L1_DEV Dev,
+ uint32_t *pphasecal_config_timeout_us,
+ uint32_t *pmm_config_timeout_us,
+ uint32_t *prange_config_timeout_us);
+
+
+/**
+ * @brief Sets the 12-bit calibration repeat period value
+ *
+ * Sets the repeat period for VHV and phasecal in ranges.
+ * Setting to zero to disables the repeat, but the VHV
+ * and PhaseCal is still run on the very first range in
+ * this case.
+ *
+ * Only even values should be set
+ *
+ * The max value is 4094 i.e. every
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] cal_config__repeat_period : current calibration config repeat period
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_calibration_repeat_period(
+ VL53L1_DEV Dev,
+ uint16_t cal_config__repeat_period);
+
+
+/**
+ * @brief Gets the current 12-bit calibration repeat period value
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] pcal_config__repeat_period : current calibration config repeat period
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_calibration_repeat_period(
+ VL53L1_DEV Dev,
+ uint16_t *pcal_config__repeat_period);
+
+
+/**
+ * @brief Set system sequence config bit value
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] bit_id : VL53L1_DeviceSequenceConfig bit id
+ * @param[in] value : Input Bit value = 0 or 1
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_sequence_config_bit(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceSequenceConfig bit_id,
+ uint8_t value);
+
+
+/**
+ * @brief Get system sequence config bit value
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] bit_id : VL53L1_DeviceSequenceConfig bit id
+ * @param[out] pvalue : Output Bit value = 0 or 1
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_sequence_config_bit(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceSequenceConfig bit_id,
+ uint8_t *pvalue);
+
+
+/**
+ * @brief Set the interrupt polarity bit in
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] interrupt_polarity : Interrupt Polarity
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_interrupt_polarity(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceInterruptPolarity interrupt_polarity);
+
+
+/**
+ * @brief Get the interrupt polarity bit state
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] pinterrupt_polarity : Interrupt Polarity Bit value
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_interrupt_polarity(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceInterruptPolarity *pinterrupt_polarity);
+
+/**
+ * @brief Set the Ref spad char cfg struct internal to pdev
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] pdata : Input pointer to VL53L1_refspadchar_config_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_get_refspadchar_config_struct(
+ VL53L1_DEV Dev,
+ VL53L1_refspadchar_config_t *pdata);
+#endif
+
+/**
+ * @brief Extract the Ref spad char cfg struct from pdev
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] pdata : Output pointer to VL53L1_refspadchar_config_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_set_refspadchar_config_struct(
+ VL53L1_DEV Dev,
+ VL53L1_refspadchar_config_t *pdata);
+#endif
+
+/**
+ * @brief Set the Range Ignore Threshold Rate value
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] range_ignore_thresh_mult : Input RIT Mult value, in \
+ * 3.5 fractional value
+ * @param[in] range_ignore_threshold_mcps : Range Ignore Threshold value
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_range_ignore_threshold(
+ VL53L1_DEV Dev,
+ uint8_t range_ignore_thresh_mult,
+ uint16_t range_ignore_threshold_mcps);
+
+/**
+ * @brief Get the Range Ignore Threshold Rate value
+ *
+ *
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] prange_ignore_thresh_mult : \
+ * Range ignore threshold internal multiplier value in \
+ * 3.5 fractional format.
+ * @param[out] prange_ignore_threshold_mcps_internal : \
+ * Range Ignore Threshold Rate value generated from \
+ * current xtalk parms
+ * @param[out] prange_ignore_threshold_mcps_current : \
+ * Range Ignore Threshold Rate value generated from \
+ * device static config struct
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_range_ignore_threshold(
+ VL53L1_DEV Dev,
+ uint8_t *prange_ignore_thresh_mult,
+ uint16_t *prange_ignore_threshold_mcps_internal,
+ uint16_t *prange_ignore_threshold_mcps_current);
+
+
+/**
+ * @brief Sets the current user Zone (ROI) configuration structure data
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] puser_zone : pointer to user Zone (ROI) data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_user_zone(
+ VL53L1_DEV Dev,
+ VL53L1_user_zone_t *puser_zone);
+
+
+/**
+ * @brief Gets the current user zone (ROI) configuration structure data
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] puser_zone : pointer to user zone (ROI) data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_user_zone(
+ VL53L1_DEV Dev,
+ VL53L1_user_zone_t *puser_zone);
+
+
+/**
+ * @brief Gets the current mode mitigation zone (ROI) configuration structure data
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] pmm_roi : pointer to user zone (ROI) data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_mode_mitigation_roi(
+ VL53L1_DEV Dev,
+ VL53L1_user_zone_t *pmm_roi);
+
+
+/**
+ * @brief Initialises the configuration data structures for
+ * the selected preset mode
+ *
+ * Important: does **not** apply the settings to the device.
+ * Updates the following structures in the device structure
+ *
+ * - static config : pdev->stat_cfg
+ * - dynamic config : pdev->dyn_cfg
+ * - system_control :pdev->sys_ctrl
+ *
+ * Uses osc_measured__fast_osc__frequency in pdev->stat_nvm to
+ * convert the input timeouts in [us] to internal macro period
+ * timeout values.
+ *
+ * Please call VL53L1_init_and_start_range() to update device
+ * and start a range
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] device_preset_mode : selected device preset mode
+ * @param[in] dss_config__target_total_rate_mcps : DSS target rate in 9.7 format e.g 0x0A00 -> 20.0 Mcps
+ * @param[in] phasecal_config_timeout_us : requested Phase Cal Timeout e.g. 1000us
+ * @param[in] mm_config_timeout_us : requested MM Timeout e.g. 2000us
+ * @param[in] range_config_timeout_us : requested Ranging Timeout e.g 10000us
+ * @param[in] inter_measurement_period_ms : requested timed mode repeat rate e.g 100ms
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_preset_mode(
+ VL53L1_DEV Dev,
+ VL53L1_DevicePresetModes device_preset_mode,
+ uint16_t dss_config__target_total_rate_mcps,
+ uint32_t phasecal_config_timeout_us,
+ uint32_t mm_config_timeout_us,
+ uint32_t range_config_timeout_us,
+ uint32_t inter_measurement_period_ms);
+
+
+/**
+ * @brief Gets the requested preset mode configuration tuning parameters
+ *
+ * Function Added as part of Patch_TuningParmPresetModeAddition_11839
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] device_preset_mode : selected device preset mode
+ * @param[out] pdss_config__target_total_rate_mcps : dss rate output value
+ * @param[out] pphasecal_config_timeout_us : phasecal timeout output value
+ * @param[out] pmm_config_timeout_us : mm timeout output value
+ * @param[out] prange_config_timeout_us : range timeout output value
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_preset_mode_timing_cfg(
+ VL53L1_DEV Dev,
+ VL53L1_DevicePresetModes device_preset_mode,
+ uint16_t *pdss_config__target_total_rate_mcps,
+ uint32_t *pphasecal_config_timeout_us,
+ uint32_t *pmm_config_timeout_us,
+ uint32_t *prange_config_timeout_us);
+
+/**
+ * @brief Simple function to enable xtalk compensation
+ *
+ * Applies xtalk compensation to hist post processing,
+ * and applies settings to device,
+ *
+ * @param[in] Dev : Device Handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_enable_xtalk_compensation(
+ VL53L1_DEV Dev);
+
+/**
+ * @brief Simple function to disable xtalk compensation
+ *
+ * Disables xtalk compensation from hist post processing,
+ * and clears settings to device
+ *
+ * @param[in] Dev : Device Handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_disable_xtalk_compensation(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Simple function to retrieve xtalk compensation
+ * status
+ *
+ * @param[in] Dev : Device Handle
+ * @param[out] pcrosstalk_compensation_enable : pointer to \
+ * uint8 type, returns crosstalk compensation status \
+ * where 0 means disabled and 1 means enabled.
+ *
+ */
+
+void VL53L1_get_xtalk_compensation_enable(
+ VL53L1_DEV Dev,
+ uint8_t *pcrosstalk_compensation_enable);
+
+/**
+ * @brief Builds and sends the I2C buffer to initialize the device
+ * and start a range measurement
+ *
+ * The device_config_level input controls the level of initialization
+ * applied to the device
+ *
+ * - System control only
+ * - Dynamic Onwards
+ * - dynamic_config and system_control
+ * - Static Onwards
+ * - static_config, dynamic_config & system_control
+ * - software standby mode only
+ * - Customer Onwards
+ * - customer_nvm_managed, static_config, dynamic_config & system_control
+ * - software standby mode only
+ * - Full
+ * - static_nvm_managed, customer_nvm_managed, static_config, dynamic_config & system_control
+ * - software standby mode only
+ *
+ * The system_control register group is always written as the last
+ * register of this group SYSTEM__MODE_START decides what happens next ...
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] measurement_mode : Options: \n
+ * VL53L1_DEVICEMEASUREMENTMODE_STOP \n
+ * VL53L1_DEVICEMEASUREMENTMODE_SINGLESHOT \n
+ * VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK \n
+ * VL53L1_DEVICEMEASUREMENTMODE_TIMED
+ * @param[in] device_config_level : Options: \n
+ * VL53L1_DEVICECONFIGLEVEL_SYSTEM_CONTROL \n
+ * VL53L1_DEVICECONFIGLEVEL_DYNAMIC_ONWARDS \n
+ * VL53L1_DEVICECONFIGLEVEL_TIMING_ONWARDS \n
+ * VL53L1_DEVICECONFIGLEVEL_STATIC_ONWARDS \n
+ * VL53L1_DEVICECONFIGLEVEL_CUSTOMER_ONWARDS \n
+ * VL53L1_DEVICECONFIGLEVEL_FULL
+ *
+ * The system_control register group is always written as the last
+ * register of this group SYSTEM__MODE_START decides what happens next ..
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_init_and_start_range(
+ VL53L1_DEV Dev,
+ uint8_t measurement_mode,
+ VL53L1_DeviceConfigLevel device_config_level);
+
+
+/**
+ * @brief Sends an abort command to stop the in progress range.
+ * Also clears all of the measurement mode bits.
+ *
+ * @param[in] Dev : Device handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_stop_range(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Get range measurement result data
+ *
+ * Reads the required number of registers as single multi byte read
+ * transaction and decodes the data into the data structures
+ *
+ * range_result_level controls which result data is read back from the
+ * device
+ *
+ * - Full
+ * - both system and core results are read back
+ * - System Results
+ * - only system results are read back
+ * - only the system_results structure is updated in this case
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] device_result_level : Options: \n
+ * VL53L1_DEVICERESULTSLEVEL_FULL \n
+ * VL53L1_DEVICERESULTSLEVEL_UPTO_CORE \n
+ * VL53L1_DEVICERESULTSLEVEL_SYSTEM_RESULTS
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_measurement_results(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceResultsLevel device_result_level);
+
+
+/**
+ * @brief Get device system results, updates GPH registers and
+ * clears interrupt and configures SYSTEM__MODE_START
+ * based on the input measurement mode
+ *
+ * Internally uses the following functions:
+ *
+ * - VL53L1_get_measurement_results()
+ * - VLS3L1_init_and_start_range()
+ *
+ * The system_control register group is always written as the last
+ * register of this group SYSTEM__MODE_START decides what happens next ...
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] device_result_level : Options: \n
+ * VL53L1_DEVICERESULTSLEVEL_FULL \n
+ * VL53L1_DEVICERESULTSLEVEL_UPTO_CORE \n
+ * VL53L1_DEVICERESULTSLEVEL_SYSTEM_RESULTS
+ * @param[out] prange_results : pointer to VL53L1_range_results_t
+
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_device_results(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceResultsLevel device_result_level,
+ VL53L1_range_results_t *prange_results);
+
+
+/**
+ * @brief Sends the ranging handshake to clear the interrupt
+ * allow the device to move onto the next range
+ *
+ * updates GPH registers and clears interrupt and configures
+ * SYSTEM__MODE_START register based on the input measurement mode
+ *
+ * Internally uses the following functions:
+ *
+ * - VLS3L1_init_and_start_range()
+ *
+ * The system_control register group is always written as the last
+ * register of this group SYSTEM__MODE_START decides what happens next ...
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] measurement_mode : Options: \n
+ * VL53L1_DEVICEMEASUREMENTMODE_STOP \n
+ * VL53L1_DEVICEMEASUREMENTMODE_SINGLESHOT \n
+ * VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK \n
+ * VL53L1_DEVICEMEASUREMENTMODE_TIMED
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_clear_interrupt_and_enable_next_range(
+ VL53L1_DEV Dev,
+ uint8_t measurement_mode);
+
+
+/**
+ * @brief Copies system and core results to range results data structure
+ *
+ * @param[in] gain_factor : gain correction factor 1.11 format
+ * @param[in] psys : pointer to VL53L1_system_results_t
+ * @param[in] pcore : pointer to VL53L1_core_results_t
+ * @param[out] presults : pointer to VL53L1_range_results_t
+ */
+
+void VL53L1_copy_sys_and_core_results_to_range_results(
+ int32_t gain_factor,
+ VL53L1_system_results_t *psys,
+ VL53L1_core_results_t *pcore,
+ VL53L1_range_results_t *presults);
+
+/**
+ * @brief Configure the GPIO interrupt config, from the given input
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] intr_mode_distance : distance interrupt mode
+ * @param[in] intr_mode_rate : rate interrupt mode
+ * @param[in] intr_new_measure_ready : trigger when new interrupt ready
+ * @param[in] intr_no_target : trigger when no target found
+ * @param[in] intr_combined_mode : switch on combined mode
+ * @param[in] thresh_distance_high : High distance threshold in mm
+ * @param[in] thresh_distance_low : Low distance threshold in mm
+ * @param[in] thresh_rate_high : High rate threshold in 9.7 Mcps
+ * @param[in] thresh_rate_low : Low rate threshold in 9.7 Mcps
+ */
+
+VL53L1_Error VL53L1_set_GPIO_interrupt_config(
+ VL53L1_DEV Dev,
+ VL53L1_GPIO_Interrupt_Mode intr_mode_distance,
+ VL53L1_GPIO_Interrupt_Mode intr_mode_rate,
+ uint8_t intr_new_measure_ready,
+ uint8_t intr_no_target,
+ uint8_t intr_combined_mode,
+ uint16_t thresh_distance_high,
+ uint16_t thresh_distance_low,
+ uint16_t thresh_rate_high,
+ uint16_t thresh_rate_low
+ );
+
+/**
+ * @brief Configure the GPIO interrupt config, from the given structure
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] intconf : input structure (note, not a pointer)
+ */
+
+VL53L1_Error VL53L1_set_GPIO_interrupt_config_struct(
+ VL53L1_DEV Dev,
+ VL53L1_GPIO_interrupt_config_t intconf);
+
+/**
+ * @brief Retrieves the GPIO interrupt config structure currently programmed
+ * into the API
+ *
+ * @param[in] Dev : Device Handle
+ * @param[out] pintconf : output pointer to structure (note, pointer)
+ */
+
+VL53L1_Error VL53L1_get_GPIO_interrupt_config(
+ VL53L1_DEV Dev,
+ VL53L1_GPIO_interrupt_config_t *pintconf);
+
+/**
+ * @brief Set function for offset calibration mode
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] offset_cal_mode : input calibration mode
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_offset_calibration_mode(
+ VL53L1_DEV Dev,
+ VL53L1_OffsetCalibrationMode offset_cal_mode);
+
+
+/**
+ * @brief Get function for offset calibration mode
+ *
+ * @param[in] Dev : Device Handle
+ * @param[out] poffset_cal_mode : output pointer for calibration mode
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_offset_calibration_mode(
+ VL53L1_DEV Dev,
+ VL53L1_OffsetCalibrationMode *poffset_cal_mode);
+
+
+/**
+ * @brief Set function for offset correction mode
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] offset_cor_mode : input correction mode
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_offset_correction_mode(
+ VL53L1_DEV Dev,
+ VL53L1_OffsetCalibrationMode offset_cor_mode);
+
+
+/**
+ * @brief Get function for offset correction mode
+ *
+ * @param[in] Dev : Device Handle
+ * @param[out] poffset_cor_mode : output pointer for correction mode
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_offset_correction_mode(
+ VL53L1_DEV Dev,
+ VL53L1_OffsetCorrectionMode *poffset_cor_mode);
+
+/**
+ * @brief Get function for Xtalk Margin setting
+ * Histogram Mode version
+ *
+ * @param[in] Dev : Device Handle
+ * @param[out] pxtalk_margin : output pointer for int16_t xtalk_margin factor \
+ * in fixed point 7.9 Kcps.
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_lite_xtalk_margin_kcps(
+ VL53L1_DEV Dev,
+ int16_t *pxtalk_margin);
+
+/**
+ * @brief Set function for Xtalk Margin setting
+ * Histogram Mode version
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] xtalk_margin : Input int16_t xtalk_margin factor \
+ * in fixed point 7.9 Kcps.
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_lite_xtalk_margin_kcps(
+ VL53L1_DEV Dev,
+ int16_t xtalk_margin);
+
+/**
+ * @brief Get function for Lite Mode Minimum Count Rate
+ * parameter, used to filter and validate ranges based on
+ * signal rate
+ *
+ * Note: the min count rate value is overwritten when setting preset
+ * modes, and should only be altered after preset mode has been
+ * selected when running Lite Mode.
+ *
+ * @param[in] Dev : Device Handle
+ * @param[out] plite_mincountrate : Output pointer for uint16_t min count rate\
+ * in fixed point 9.7 Mcps
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_lite_min_count_rate(
+ VL53L1_DEV Dev,
+ uint16_t *plite_mincountrate);
+
+
+/**
+ * @brief Set function for Lite Mode Minimum Count Rate
+ * parameter, used to filter and validate ranges based on
+ * signal rate
+ *
+ * Note: the min count rate value is overwritten when setting preset
+ * modes, and should only be altered after preset mode has been
+ * selected when running Lite Mode.
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] lite_mincountrate : Input uint16_t min count rate
+ * in fixed point 9.7 Mcps
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_lite_min_count_rate(
+ VL53L1_DEV Dev,
+ uint16_t lite_mincountrate);
+
+
+/**
+ * @brief Get function for Lite Mode Max Sigma Threshold
+ * parameter, used to filter and validate ranges based on
+ * estimated sigma level
+ *
+ * Note: the sigma thresh value is overwritten when setting preset
+ * modes, and should only be altered after preset mode has been
+ * selected when running Lite Mode.
+ *
+ * @param[in] Dev : Device Handle
+ * @param[out] plite_sigma : Output pointer for uint16_t sigma thresh\
+ * in fixed point 14.2 mm
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+
+VL53L1_Error VL53L1_get_lite_sigma_threshold(
+ VL53L1_DEV Dev,
+ uint16_t *plite_sigma);
+
+
+/**
+ * @brief Set function for Lite Mode Max Sigma Threshold
+ * parameter, used to filter and validate ranges based on
+ * estimated sigma level
+ *
+ * Note: the sigma thresh value is overwritten when setting preset
+ * modes, and should only be altered after preset mode has been
+ * selected when running Lite Mode.
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] lite_sigma : Input uint16_t sigma thresh\
+ * in fixed point 14.2 mm
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_lite_sigma_threshold(
+ VL53L1_DEV Dev,
+ uint16_t lite_sigma);
+
+
+/**
+ * @brief Function to restore the plane_offset, x gradient and y gradient
+ * values to original NVM values.
+ *
+ * This function does not recalculate all xtalk parms derived from the
+ * rates in question. In order to ensure correct ranging, a call to
+ * VL53L1_enable_xtalk_compensation should always be called prior
+ * to starting the ranging process.
+ *
+ * @param[in] Dev : Device Handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_restore_xtalk_nvm_default(
+ VL53L1_DEV Dev);
+
+/**
+ * @brief Set function for VHV Config values
+ * sets two parms into individual internal byte
+ *
+ * init_en - enables use of the init value instead of latest setting
+ * init_value - custom vhv setting or populated from nvm
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] vhv_init_en : input init_en setting
+ * @param[in] vhv_init_value : input vhv custom value
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_vhv_config(
+ VL53L1_DEV Dev,
+ uint8_t vhv_init_en,
+ uint8_t vhv_init_value);
+
+/**
+ * @brief Get function for VHV Config values
+ * extracts two parms from individual internal byte
+ *
+ * init_en - enables use of the init value instead of latest setting
+ * init_value - custom vhv setting or populated from nvm
+ *
+ * @param[in] Dev : Device Handle
+ * @param[out] pvhv_init_en : Output pointer to uint8_t value
+ * @param[out] pvhv_init_value : Output pointer to uint8_t value
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_vhv_config(
+ VL53L1_DEV Dev,
+ uint8_t *pvhv_init_en,
+ uint8_t *pvhv_init_value);
+
+/**
+ * @brief Set function for VHV loopbound config
+ *
+ * Loopbound sets the number of +/- vhv settings to try
+ * around the vhv init value during vhv search
+ * i.e. if init_value = 10 and loopbound = 2
+ * vhv search will run from 10-2 to 10+2
+ * 8 to 12.
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] vhv_loopbound : input loopbound value
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_vhv_loopbound(
+ VL53L1_DEV Dev,
+ uint8_t vhv_loopbound);
+
+/**
+ * @brief Get function for VHV loopbound config
+ *
+ * Loopbound sets the number of +/- vhv settings to try
+ * around the vhv init value during vhv search
+ * i.e. if init_value = 10 and loopbound = 2
+ * vhv search will run from 10-2 to 10+2
+ * 8 to 12.
+ *
+ * @param[in] Dev : Device Handle
+ * @param[out] pvhv_loopbound : pointer to byte to extract loopbound
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_vhv_loopbound(
+ VL53L1_DEV Dev,
+ uint8_t *pvhv_loopbound);
+
+/**
+ * @brief Generic Tuning Parameter extraction function
+ *
+ * User passes a key input to retrieve a specific tuning parameter
+ * value, this will be cast to the int32_t type and output via
+ * the ptuning_parm_value pointer
+ *
+ * If the key does not match any tuning parameter, status is returned
+ * with VL53L1_ERROR_INVALID_PARAMS
+ *
+ * Patch_AddedTuningParms_11761
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] tuning_parm_key : Key value to access specific tuning parm
+ * @param[out] ptuning_parm_value : Pointer to output int32_t type, retrieves \
+ * requested tuning parm
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_get_tuning_parm(
+ VL53L1_DEV Dev,
+ VL53L1_TuningParms tuning_parm_key,
+ int32_t *ptuning_parm_value);
+#endif
+
+/**
+ * @brief Generic Tuning Parameter set function
+ *
+ * User passes a key input to set a specific tuning parameter
+ * value, this will be cast to the internal data type from the
+ * input int32_t data type.
+ *
+ * If the key does not match any tuning parameter, status is returned
+ * with VL53L1_ERROR_INVALID_PARAMS
+ *
+ * Patch_AddedTuningParms_11761
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] tuning_parm_key : Key value to access specific tuning parm
+ * @param[in] tuning_parm_value : Input tuning parm value of int32_t type, \
+ * sets requested tuning parm.
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_set_tuning_parm(
+ VL53L1_DEV Dev,
+ VL53L1_TuningParms tuning_parm_key,
+ int32_t tuning_parm_value);
+#endif
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _VL53L1_API_CORE_H_ */
diff --git a/src/lib/vl53l1/core/inc/vl53l1_api_debug.h b/src/lib/vl53l1/core/inc/vl53l1_api_debug.h
new file mode 100644
index 0000000000..c9ecb4471f
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_api_debug.h
@@ -0,0 +1,320 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*******************************************************************************/
+
+/**
+ * @file vl53l1_api_debug.h
+ *
+ * @brief EwokPlus25 low level API function definitions
+ */
+
+#ifndef _VL53L1_API_DEBUG_H_
+#define _VL53L1_API_DEBUG_H_
+
+#include "vl53l1_platform.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+
+/* Start Patch_AdditionalDebugData_11823 */
+
+/**
+ * @brief Gets the current LL Driver configuration parameters and the last
+ * set of histogram data for debug
+ *
+ * @param[in] Dev : Device Handle
+ * @param[out] pdata : pointer to VL53L1_additional_data_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_additional_data(
+ VL53L1_DEV Dev,
+ VL53L1_additional_data_t *pdata);
+
+/* End Patch_AdditionalDebugData_11823 */
+
+
+#ifdef VL53L1_LOG_ENABLE
+
+/**
+ * @brief Implements an sprintf function for signed fixed point numbers
+ *
+ * @param[in] fp_value : input signed fixed point number
+ * @param[in] frac_bits : number of fixed point fractional bits
+ * @param[in] buf_size : size of supplied text buffer
+ * @param[out] pbuffer : pointer to text buffer
+ *
+ */
+
+void VL53L1_signed_fixed_point_sprintf(
+ int32_t fp_value,
+ uint8_t frac_bits,
+ uint16_t buf_size,
+ char *pbuffer);
+
+
+/**
+ * @brief Convenience function to print out VL53L1_static_nvm_managed_t for debug
+ *
+ * @param[in] pdata : pointer to VL53L1_static_nvm_managed_t
+ * @param[in] pprefix : pointer to name prefix string
+ * @param[in] trace_flags : logging module enable bit flags
+ */
+
+void VL53L1_print_static_nvm_managed(
+ VL53L1_static_nvm_managed_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags);
+
+
+/**
+ * @brief Convenience function to print out VL53L1_customer_nvm_managed_t for debug
+ *
+ * @param[in] pdata : pointer to VL53L1_customer_nvm_managed_t
+ * @param[in] pprefix : pointer to name prefix string
+ * @param[in] trace_flags : logging module enable bit flags
+ */
+
+void VL53L1_print_customer_nvm_managed(
+ VL53L1_customer_nvm_managed_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags);
+
+
+/**
+ * @brief Convenience function to print out VL53L1_nvm_copy_data_t for debug
+ *
+ * @param[in] pdata : pointer to VL53L1_nvm_copy_data_t
+ * @param[in] pprefix : pointer to name prefix string
+ * @param[in] trace_flags : logging module enable bit flags
+ */
+
+void VL53L1_print_nvm_copy_data(
+ VL53L1_nvm_copy_data_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags);
+
+
+/**
+ * @brief Convenience function to print out the contents of
+ * the Range Results structure for debug
+ *
+ * @param[in] pdata : pointer to a VL53L1_range_results_t structure
+ * @param[in] pprefix : pointer to name prefix string
+ * @param[in] trace_flags : logging module enable bit flags
+ */
+
+void VL53L1_print_range_results(
+ VL53L1_range_results_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags);
+
+/**
+ * @brief Convenience function to print out the contents of
+ * the Range Data structure for debug
+ *
+ * @param[in] pdata : pointer to a VL53L1_range_data_t structure
+ * @param[in] pprefix : pointer to name prefix string
+ * @param[in] trace_flags : logging module enable bit flags
+ */
+
+void VL53L1_print_range_data(
+ VL53L1_range_data_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags);
+
+/**
+ * @brief Convenience function to print out the contents of
+ * the offset range results structure for debug
+ *
+ * @param[in] pdata : pointer to a VL53L1_offset_range_results_t structure
+ * @param[in] pprefix : pointer to name prefix string
+ * @param[in] trace_flags : logging module enable bit flags
+ */
+
+void VL53L1_print_offset_range_results(
+ VL53L1_offset_range_results_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags);
+
+/**
+ * @brief Convenience function to print out the contents of
+ * the offset range data structure for debug
+ *
+ * @param[in] pdata : pointer to a VL53L1_offset_range_data_t structure
+ * @param[in] pprefix : pointer to name prefix string
+ * @param[in] trace_flags : logging module enable bit flags
+ */
+
+void VL53L1_print_offset_range_data(
+ VL53L1_offset_range_data_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags);
+
+
+/**
+ * @brief Convenience function to print out the contents of
+ * the peak rate map calibration data structure
+ *
+ * @param[in] pdata : pointer to a VL53L1_cal_peak_rate_map_t structure
+ * @param[in] pprefix : pointer to name prefix string
+ * @param[in] trace_flags : logging module enable bit flags
+ */
+
+void VL53L1_print_cal_peak_rate_map(
+ VL53L1_cal_peak_rate_map_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags);
+
+
+/**
+ * @brief Convenience function to print out the contents of
+ * the additional offset calibration data structure
+ *
+ * @param[in] pdata : pointer to a VL53L1_additional_offset_cal_data_t structure
+ * @param[in] pprefix : pointer to name prefix string
+ * @param[in] trace_flags : logging module enable bit flags
+ */
+
+void VL53L1_print_additional_offset_cal_data(
+ VL53L1_additional_offset_cal_data_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags);
+
+/**
+ * @brief Convenience function to print out the contents of
+ * the additional data structure
+ *
+ * @param[in] pdata : pointer to a VL53L1_additional_data_t structure
+ * @param[in] pprefix : pointer to name prefix string
+ * @param[in] trace_flags : logging module enable bit flags
+ */
+
+void VL53L1_print_additional_data(
+ VL53L1_additional_data_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags);
+
+
+/**
+ * @brief Convenience function to print out the contents of
+ * the LL driver gain calibration data structure
+ *
+ * @param[in] pdata : pointer to a VL53L1_gain_calibration_data_t structure
+ * @param[in] pprefix : pointer to name prefix string
+ * @param[in] trace_flags : logging module enable bit flags
+ */
+
+void VL53L1_print_gain_calibration_data(
+ VL53L1_gain_calibration_data_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags);
+
+
+/**
+ * @brief Convenience function to print out the contents of
+ * the xtalk configuration data for debug
+ *
+ * @param[in] pdata : pointer to a VL53L1_xtalk_config_t Structure
+ * @param[in] pprefix : pointer to name prefix string
+ * @param[in] trace_flags : logging module enable bit flags
+ */
+
+void VL53L1_print_xtalk_config(
+ VL53L1_xtalk_config_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags);
+
+/**
+ * @brief Convenience function to print out the contents of
+ * the Optical Centre structure for debug
+ *
+ * @param[in] pdata : pointer to a VL53L1_optical_centre_t structure
+ * @param[in] pprefix : pointer to name prefix string
+ * @param[in] trace_flags : logging module enable bit flags
+ */
+
+void VL53L1_print_optical_centre(
+ VL53L1_optical_centre_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags);
+
+
+/**
+ * @brief Convenience function to print out the contents of
+ * the User Zone (ROI) structure for debug
+ *
+ * @param[in] pdata : pointer to a VL53L1_user_zone_t structure
+ * @param[in] pprefix : pointer to name prefix string
+ * @param[in] trace_flags : logging module enable bit flags
+ */
+
+void VL53L1_print_user_zone(
+ VL53L1_user_zone_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags);
+
+/**
+ * @brief Convenience function for printing out VL53L1_spad_rate_data_t
+ *
+ * @param[in] pspad_rates : pointer to VL53L1_spad_rate_data_t
+ * @param[in] pprefix : pointer to name prefix string
+ * @param[in] trace_flags : logging module enable bit flags
+ */
+
+void VL53L1_print_spad_rate_data(
+ VL53L1_spad_rate_data_t *pspad_rates,
+ char *pprefix,
+ uint32_t trace_flags);
+
+
+/**
+ * @brief Convenience function for printing out VL53L1_spad_rate_map_t
+ *
+ * @param[in] pspad_rates : pointer to VL53L1_spad_rate_map_t
+ * @param[in] pprefix : pointer to name prefix string
+ * @param[in] trace_flags : logging module enable bit flags
+ */
+
+void VL53L1_print_spad_rate_map(
+ VL53L1_spad_rate_data_t *pspad_rates,
+ char *pprefix,
+ uint32_t trace_flags);
+
+
+#endif /* VL53L1_LOG_ENABLE */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _VL53L1_API_DEBUG_H_ */
diff --git a/src/lib/vl53l1/core/inc/vl53l1_api_preset_modes.h b/src/lib/vl53l1/core/inc/vl53l1_api_preset_modes.h
new file mode 100644
index 0000000000..f8eb6333a9
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_api_preset_modes.h
@@ -0,0 +1,437 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*******************************************************************************/
+
+/**
+ * @file vl53l1_api_preset_modes.h
+ *
+ * @brief EwokPlus25 API core function definition
+ */
+
+#ifndef _VL53L1_API_PRESET_MODES_H_
+#define _VL53L1_API_PRESET_MODES_H_
+
+#include "vl53l1_ll_def.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+/**
+ * @brief Initializes Ref SPAD Char Configuration Parameters
+ *
+ * @param[out] pdata : pointer to VL53L1_refspadchar_config_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_init_refspadchar_config_struct(
+ VL53L1_refspadchar_config_t *pdata);
+#endif
+
+
+/**
+ * @brief Initializes SPAD Self Check (SSC) Configuration Parameters
+ *
+ * @param[out] pdata : pointer to VL53L1_ssc_config_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_init_ssc_config_struct(
+ VL53L1_ssc_config_t *pdata);
+
+/**
+ * @brief Initializes Xtalk Configuration Parameters
+ *
+ * @param[in] pnvm : pointer to VL53L1_customer_nvm_managed_t data structure
+ * @param[out] pdata : pointer to VL53L1_xtalk_config_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_init_xtalk_config_struct(
+ VL53L1_customer_nvm_managed_t *pnvm,
+ VL53L1_xtalk_config_t *pdata);
+
+/**
+ * @brief Initializes Offset Calibration Configuration Parameters
+ *
+ * @param[out] pdata : pointer to VL53L1_offsetcal_config_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_init_offset_cal_config_struct(
+ VL53L1_offsetcal_config_t *pdata);
+#endif
+
+
+/**
+ * @brief Initializes Tuning Parameter Storage Values
+ *
+ * @param[out] pdata : pointer to VL53L1_tuning_parm_storage_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_init_tuning_parm_storage_struct(
+ VL53L1_tuning_parm_storage_t *pdata);
+
+/**
+ * @brief Initializes static and dynamic configuration settings for
+ * preset mode VL53L1_DEVICEPRESETMODE_STANDARD_RANGING
+ *
+ * @param[out] pstatic : pointer to VL53L1_static_config_t data structure
+ * @param[out] pgeneral : pointer to VL53L1_general_config_t data structure
+ * @param[out] ptiming : pointer to VL53L1_timing_config_t data structure
+ * @param[out] pdynamic : pointer to VL53L1_dynamic_config_t data structure
+ * @param[out] psystem : pointer to VL53L1_system_control_t data structure
+ * @param[out] ptuning_parms : pointer to VL53L1_tuning_parms_storage_t structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_preset_mode_standard_ranging(
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms);
+
+/**
+ * @brief Initializes static and dynamic configuration settings for
+ * preset mode VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_SHORT_RANGE
+ *
+ * @param[out] pstatic : pointer to VL53L1_static_config_t data structure
+ * @param[out] pgeneral : pointer to VL53L1_general_config_t data structure
+ * @param[out] ptiming : pointer to VL53L1_timing_config_t data structure
+ * @param[out] pdynamic : pointer to VL53L1_dynamic_config_t data structure
+ * @param[out] psystem : pointer to VL53L1_system_control_t data structure
+ * @param[out] ptuning_parms : pointer to VL53L1_tuning_parms_storage_t structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_preset_mode_standard_ranging_short_range(
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms);
+
+
+/**
+ * @brief Initializes static and dynamic configuration settings for
+ * preset mode VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_LONG_RANGE
+ *
+ * @param[out] pstatic : pointer to VL53L1_static_config_t data structure
+ * @param[out] pgeneral : pointer to VL53L1_general_config_t data structure
+ * @param[out] ptiming : pointer to VL53L1_timing_config_t data structure
+ * @param[out] pdynamic : pointer to VL53L1_dynamic_config_t data structure
+ * @param[out] psystem : pointer to VL53L1_system_control_t data structure
+ * @param[out] ptuning_parms : pointer to VL53L1_tuning_parms_storage_t structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_preset_mode_standard_ranging_long_range(
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms);
+
+/**
+ * @brief Initializes static and dynamic configuration settings for
+ * preset mode VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM1_CAL
+ *
+ * @param[out] pstatic : pointer to VL53L1_static_config_t data structure
+ * @param[out] pgeneral : pointer to VL53L1_general_config_t data structure
+ * @param[out] ptiming : pointer to VL53L1_timing_config_t data structure
+ * @param[out] pdynamic : pointer to VL53L1_dynamic_config_t data structure
+ * @param[out] psystem : pointer to VL53L1_system_control_t data structure
+ * @param[out] ptuning_parms : pointer to VL53L1_tuning_parms_storage_t structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_preset_mode_standard_ranging_mm1_cal(
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms);
+#endif
+
+
+/**
+ * @brief Initializes static and dynamic configuration settings for
+ * preset mode VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM2_CAL
+ *
+ * @param[out] pstatic : pointer to VL53L1_static_config_t data structure
+ * @param[out] pgeneral : pointer to VL53L1_general_config_t data structure
+ * @param[out] ptiming : pointer to VL53L1_timing_config_t data structure
+ * @param[out] pdynamic : pointer to VL53L1_dynamic_config_t data structure
+ * @param[out] psystem : pointer to VL53L1_system_control_t data structure
+ * @param[out] ptuning_parms : pointer to VL53L1_tuning_parms_storage_t structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_preset_mode_standard_ranging_mm2_cal(
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms);
+#endif
+
+
+/**
+ * @brief Initializes static and dynamic configuration settings for
+ * preset mode VL53L1_DEVICEPRESETMODE_TIMED_RANGING
+ *
+ * @param[out] pstatic : pointer to VL53L1_static_config_t data structure
+ * @param[out] pgeneral : pointer to VL53L1_general_config_t data structure
+ * @param[out] ptiming : pointer to VL53L1_timing_config_t data structure
+ * @param[out] pdynamic : pointer to VL53L1_dynamic_config_t data structure
+ * @param[out] psystem : pointer to VL53L1_system_control_t data structure
+ * @param[out] ptuning_parms : pointer to VL53L1_tuning_parms_storage_t structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_preset_mode_timed_ranging(
+
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms);
+
+/**
+ * @brief Initializes static and dynamic configuration settings for
+ * preset mode VL53L1_DEVICEPRESETMODE_TIMED_RANGING_SHORT_RANGE
+ *
+ * @param[out] pstatic : pointer to VL53L1_static_config_t data structure
+ * @param[out] pgeneral : pointer to VL53L1_general_config_t data structure
+ * @param[out] ptiming : pointer to VL53L1_timing_config_t data structure
+ * @param[out] pdynamic : pointer to VL53L1_dynamic_config_t data structure
+ * @param[out] psystem : pointer to VL53L1_system_control_t data structure
+ * @param[out] ptuning_parms : pointer to VL53L1_tuning_parms_storage_t structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_preset_mode_timed_ranging_short_range(
+
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms);
+
+/**
+ * @brief Initializes static and dynamic configuration settings for
+ * preset mode VL53L1_DEVICEPRESETMODE_TIMED_RANGING_LONG_RANGE
+ *
+ * @param[out] pstatic : pointer to VL53L1_static_config_t data structure
+ * @param[out] pgeneral : pointer to VL53L1_general_config_t data structure
+ * @param[out] ptiming : pointer to VL53L1_timing_config_t data structure
+ * @param[out] pdynamic : pointer to VL53L1_dynamic_config_t data structure
+ * @param[out] psystem : pointer to VL53L1_system_control_t data structure
+ * @param[out] ptuning_parms : pointer to VL53L1_tuning_parms_storage_t structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_preset_mode_timed_ranging_long_range(
+
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms);
+
+/**
+ * @brief Initializes static and dynamic configuration settings for
+ * preset mode VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_MEDIUM_RANGE
+ *
+ * @param[out] pstatic : pointer to VL53L1_static_config_t data structure
+ * @param[out] pgeneral : pointer to VL53L1_general_config_t data structure
+ * @param[out] ptiming : pointer to VL53L1_timing_config_t data structure
+ * @param[out] pdynamic : pointer to VL53L1_dynamic_config_t data structure
+ * @param[out] psystem : pointer to VL53L1_system_control_t data structure
+ * @param[out] ptuning_parms : pointer to VL53L1_tuning_parms_storage_t structure
+ * @param[out] plpadata : pointer to VL53L1_low_power_auto_data_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_preset_mode_low_power_auto_ranging(
+
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms,
+ VL53L1_low_power_auto_data_t *plpadata);
+
+/**
+ * @brief Initializes static and dynamic configuration settings for
+ * preset mode VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_SHORT_RANGE
+ *
+ * @param[out] pstatic : pointer to VL53L1_static_config_t data structure
+ * @param[out] pgeneral : pointer to VL53L1_general_config_t data structure
+ * @param[out] ptiming : pointer to VL53L1_timing_config_t data structure
+ * @param[out] pdynamic : pointer to VL53L1_dynamic_config_t data structure
+ * @param[out] psystem : pointer to VL53L1_system_control_t data structure
+ * @param[out] ptuning_parms : pointer to VL53L1_tuning_parms_storage_t structure
+ * @param[out] plpadata : pointer to VL53L1_low_power_auto_data_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_preset_mode_low_power_auto_short_ranging(
+
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms,
+ VL53L1_low_power_auto_data_t *plpadata);
+
+/**
+ * @brief Initializes static and dynamic configuration settings for
+ * preset mode VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_LONG_RANGE
+ *
+ * @param[out] pstatic : pointer to VL53L1_static_config_t data structure
+ * @param[out] pgeneral : pointer to VL53L1_general_config_t data structure
+ * @param[out] ptiming : pointer to VL53L1_timing_config_t data structure
+ * @param[out] pdynamic : pointer to VL53L1_dynamic_config_t data structure
+ * @param[out] psystem : pointer to VL53L1_system_control_t data structure
+ * @param[out] ptuning_parms : pointer to VL53L1_tuning_parms_storage_t structure
+ * @param[out] plpadata : pointer to VL53L1_low_power_auto_data_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_preset_mode_low_power_auto_long_ranging(
+
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms,
+ VL53L1_low_power_auto_data_t *plpadata);
+
+
+/**
+ * @brief Initializes static and dynamic configuration settings for
+ * preset mode VL53L1_DEVICEPRESETMODE_OLT
+ *
+ * @param[out] pstatic : pointer to VL53L1_static_config_t data structure
+ * @param[out] pgeneral : pointer to VL53L1_general_config_t data structure
+ * @param[out] ptiming : pointer to VL53L1_timing_config_t data structure
+ * @param[out] pdynamic : pointer to VL53L1_dynamic_config_t data structure
+ * @param[out] psystem : pointer to VL53L1_system_control_t data structure
+ * @param[out] ptuning_parms : pointer to VL53L1_tuning_parms_storage_t structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_preset_mode_olt(
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms);
+
+/**
+ * @brief Initializes static and dynamic configuration settings for
+ * preset mode VL53L1_DEVICEPRESETMODE_SINGLESHOT_RANGING
+ *
+ * @param[out] pstatic : pointer to VL53L1_static_config_t data structure
+ * @param[out] pgeneral : pointer to VL53L1_general_config_t data structure
+ * @param[out] ptiming : pointer to VL53L1_timing_config_t data structure
+ * @param[out] pdynamic : pointer to VL53L1_dynamic_config_t data structure
+ * @param[out] psystem : pointer to VL53L1_system_control_t data structure
+ * @param[out] ptuning_parms : pointer to VL53L1_tuning_parms_storage_t structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_preset_mode_singleshot_ranging(
+
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _VL53L1_API_CORE_H_ */
diff --git a/src/lib/vl53l1/core/inc/vl53l1_api_strings.h b/src/lib/vl53l1/core/inc/vl53l1_api_strings.h
new file mode 100644
index 0000000000..9df1d5ddae
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_api_strings.h
@@ -0,0 +1,210 @@
+/*
+* Copyright (c) 2017, STMicroelectronics - All Rights Reserved
+*
+* This file is part of VL53L1 Core and is dual licensed, either
+* 'STMicroelectronics Proprietary license'
+* or 'BSD 3-clause "New" or "Revised" License' , at your option.
+*
+********************************************************************************
+*
+* 'STMicroelectronics Proprietary license'
+*
+********************************************************************************
+*
+* License terms: STMicroelectronics Proprietary in accordance with licensing
+* terms at www.st.com/sla0044
+*
+* STMicroelectronics confidential
+* Reproduction and Communication of this document is strictly prohibited unless
+* specifically authorized in writing by STMicroelectronics.
+*
+*
+********************************************************************************
+*
+* Alternatively, VL53L1 Core may be distributed under the terms of
+* 'BSD 3-clause "New" or "Revised" License', in which case the following
+* provisions apply instead of the ones
+* mentioned above :
+*
+********************************************************************************
+*
+* License terms: BSD 3-clause "New" or "Revised" License.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions are met:
+*
+* 1. Redistributions of source code must retain the above copyright notice, this
+* list of conditions and the following disclaimer.
+*
+* 2. Redistributions in binary form must reproduce the above copyright notice,
+* this list of conditions and the following disclaimer in the documentation
+* and/or other materials provided with the distribution.
+*
+* 3. Neither the name of the copyright holder nor the names of its contributors
+* may be used to endorse or promote products derived from this software
+* without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*
+********************************************************************************
+*
+*/
+
+/**
+ * @file vl53l1_api_strings.h
+ * @brief VL53L1 API function declarations for decoding error codes to a
+ * text strings
+ */
+
+
+#ifndef VL53L1_API_STRINGS_H_
+#define VL53L1_API_STRINGS_H_
+
+#include "vl53l1_def.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+
+/**
+ * @brief Generates a string for the input device range status code
+ *
+ * @param[in] RangeStatus : Device Range AStatus Code
+ * @param[out] pRangeStatusString : pointer to character buffer
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_range_status_string(
+ uint8_t RangeStatus,
+ char *pRangeStatusString);
+
+/**
+ * @brief Generates an error string for the input PAL error code
+ *
+ * @param[in] PalErrorCode : PAL Error Code
+ * @param[out] pPalErrorString : pointer to character buffer
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_pal_error_string(
+ VL53L1_Error PalErrorCode,
+ char *pPalErrorString);
+
+/**
+ * @brief Generates a string for the input PAL State code
+ *
+ * @param[in] PalStateCode : PAL State Code
+ * @param[out] pPalStateString : pointer to character buffer
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_pal_state_string(
+ VL53L1_State PalStateCode,
+ char *pPalStateString);
+
+
+/**
+ * @brief Generates a string for the sequence step Id
+ *
+ * @param[in] SequenceStepId : Sequence Step Id
+ * @param[out] pSequenceStepsString : pointer to character buffer
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_get_sequence_steps_info(
+ VL53L1_SequenceStepId SequenceStepId,
+ char *pSequenceStepsString);
+
+/**
+ * @brief Generates a string for the limit check Id
+ *
+ * @param[in] LimitCheckId : Limit check Id
+ * @param[out] pLimitCheckString : pointer to character buffer
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_get_limit_check_info(uint16_t LimitCheckId,
+ char *pLimitCheckString);
+
+#ifndef VL53L1_USE_EMPTY_STRING
+ #define VL53L1_STRING_DEVICE_INFO_NAME0 "VL53L1 cut1.0"
+ #define VL53L1_STRING_DEVICE_INFO_NAME1 "VL53L1 cut1.1"
+ #define VL53L1_STRING_DEVICE_INFO_TYPE "VL53L1"
+
+ /* Range Status */
+ #define VL53L1_STRING_RANGESTATUS_NONE "No Update"
+ #define VL53L1_STRING_RANGESTATUS_RANGEVALID "Range Valid"
+ #define VL53L1_STRING_RANGESTATUS_SIGMA "Sigma Fail"
+ #define VL53L1_STRING_RANGESTATUS_SIGNAL "Signal Fail"
+ #define VL53L1_STRING_RANGESTATUS_MINRANGE "Min Range Fail"
+ #define VL53L1_STRING_RANGESTATUS_PHASE "Phase Fail"
+ #define VL53L1_STRING_RANGESTATUS_HW "Hardware Fail"
+
+
+ /* Range Status */
+ #define VL53L1_STRING_STATE_POWERDOWN "POWERDOWN State"
+ #define VL53L1_STRING_STATE_WAIT_STATICINIT \
+ "Wait for staticinit State"
+ #define VL53L1_STRING_STATE_STANDBY "STANDBY State"
+ #define VL53L1_STRING_STATE_IDLE "IDLE State"
+ #define VL53L1_STRING_STATE_RUNNING "RUNNING State"
+ #define VL53L1_STRING_STATE_RESET "RESET State"
+ #define VL53L1_STRING_STATE_UNKNOWN "UNKNOWN State"
+ #define VL53L1_STRING_STATE_ERROR "ERROR State"
+
+
+
+ /* Check Enable */
+ #define VL53L1_STRING_CHECKENABLE_SIGMA_FINAL_RANGE \
+ "SIGMA FINAL RANGE"
+ #define VL53L1_STRING_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE \
+ "SIGNAL RATE FINAL RANGE"
+ #define VL53L1_STRING_CHECKENABLE_SIGNAL_MIN_CLIP \
+ "SIGNAL MIN CLIP"
+ #define VL53L1_STRING_CHECKENABLE_RANGE_IGNORE_THRESHOLD \
+ "RANGE IGNORE THRESHOLD"
+ #define VL53L1_STRING_CHECKENABLE_RANGE_PHASE_HIGH \
+ "RANGE PHASE HIGH"
+ #define VL53L1_STRING_CHECKENABLE_RANGE_PHASE_LOW \
+ "RANGE PHASE LOW"
+ #define VL53L1_STRING_CHECKENABLE_RANGE_PHASE_CONSISTENCY \
+ "RANGE PHASE CONSISTENCY"
+
+ /* Sequence Step */
+ #define VL53L1_STRING_SEQUENCESTEP_VHV "VHV"
+ #define VL53L1_STRING_SEQUENCESTEP_PHASECAL "PHASE CAL"
+ #define VL53L1_STRING_SEQUENCESTEP_REFPHASE "REF PHASE"
+ #define VL53L1_STRING_SEQUENCESTEP_DSS1 "DSS1"
+ #define VL53L1_STRING_SEQUENCESTEP_DSS2 "DSS2"
+ #define VL53L1_STRING_SEQUENCESTEP_MM1 "MM1"
+ #define VL53L1_STRING_SEQUENCESTEP_MM2 "MM2"
+ #define VL53L1_STRING_SEQUENCESTEP_RANGE "RANGE"
+#endif /* VL53L1_USE_EMPTY_STRING */
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
+
diff --git a/src/lib/vl53l1/core/inc/vl53l1_core.h b/src/lib/vl53l1/core/inc/vl53l1_core.h
new file mode 100644
index 0000000000..1dc556852f
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_core.h
@@ -0,0 +1,1056 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*******************************************************************************/
+
+/**
+ * @file vl53l1_core.h
+ *
+ * @brief EwokPlus25 core function definitions
+ */
+
+#ifndef _VL53L1_CORE_H_
+#define _VL53L1_CORE_H_
+
+#include "vl53l1_platform.h"
+#include "vl53l1_core_support.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+/**
+ * @brief Initialise version info in pdev
+ *
+ * @param[out] Dev : Device handle
+ */
+
+void VL53L1_init_version(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Initialise LL Driver State
+ *
+ * @param[out] Dev : Device handle
+ * @param[in] ll_state : Device state
+ */
+
+void VL53L1_init_ll_driver_state(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceState ll_state);
+
+
+/**
+ * @brief Update LL Driver Read State
+ *
+ * @param[out] Dev : Device handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_update_ll_driver_rd_state(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Checks if the LL Driver Read state and expected stream count
+ * matches the state and stream count received from the device
+ *
+ * @param[out] Dev : Device handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_check_ll_driver_rd_state(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Update LL Driver Configuration State
+ *
+ * @param[out] Dev : Device handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_update_ll_driver_cfg_state(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Convenience function to copy return SPAD enables to buffer
+ *
+ * @param[in ] pdata : pointer to VL53L1_nvm_copy_data_t
+ * @param[out] pbuffer : pointer to buffer
+ */
+
+void VL53L1_copy_rtn_good_spads_to_buffer(
+ VL53L1_nvm_copy_data_t *pdata,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Initialise system results structure to all ones
+ *
+ * This mimics what the device firmware does the the results registers
+ * at the start of each range
+ *
+ * @param[out] pdata : pointer to VL53L1_system_results_t
+ */
+
+void VL53L1_init_system_results(
+ VL53L1_system_results_t *pdata);
+
+
+/**
+ * @brief Initialise zone dynamic config DSS control values
+ *
+ * @param[in] Dev : Device handler
+ */
+
+void V53L1_init_zone_dss_configs(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Encodes a uint16_t register value into an I2C write buffer
+ *
+ * The register is encoded MS byte first is the buffer i.e as per the device register map
+ *
+ * @param[in] ip_value : input uint16_t value
+ * @param[in] count : register size of in bytes (1, 2, 3 or 4)
+ * @param[out] pbuffer : uint8_t pointer to the I2C write buffer
+ */
+
+void VL53L1_i2c_encode_uint16_t(
+ uint16_t ip_value,
+ uint16_t count,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes a uint16_t register value from an I2C read buffer
+ *
+ * The I2C read buffer is assumed to be MS byte first i.e. matching the device register map
+ *
+ * @param[in] count : register size of in bytes (1, 2, 3 or 4)
+ * @param[in] pbuffer : uint8_t pointer to the I2C read buffer
+ *
+ * @return value : decoded uint16_t value
+ */
+
+uint16_t VL53L1_i2c_decode_uint16_t(
+ uint16_t count,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Encodes a int16_t register value into an I2C write buffer
+ *
+ * The register is encoded MS byte first is the buffer i.e as per the device register map
+ *
+ * @param[in] ip_value : input int16_t value
+ * @param[in] count : register size of in bytes (1, 2, 3 or 4)
+ * @param[out] pbuffer : uint8_t pointer to the I2C write buffer
+ */
+
+void VL53L1_i2c_encode_int16_t(
+ int16_t ip_value,
+ uint16_t count,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes a int16_t register value from an I2C read buffer
+ *
+ * The I2C read buffer is assumed to be MS byte first i.e. matching the device register map
+ *
+ * @param[in] count : register size of in bytes (1, 2, 3 or 4)
+ * @param[in] pbuffer : uint8_t pointer to the I2C read buffer
+ *
+ * @return value : decoded int16_t value
+ */
+
+int16_t VL53L1_i2c_decode_int16_t(
+ uint16_t count,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Encodes a uint32_t register value into an I2C write buffer
+ *
+ * The register is encoded MS byte first is the buffer i.e as per the device register map
+ *
+ * @param[in] ip_value : input uint32_t value
+ * @param[in] count : register size of in bytes (1, 2, 3 or 4)
+ * @param[out] pbuffer : uint8_t pointer to the I2C write buffer
+ */
+
+void VL53L1_i2c_encode_uint32_t(
+ uint32_t ip_value,
+ uint16_t count,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes a uint32_t register value from an I2C read buffer
+ *
+ * The I2C read buffer is assumed to be MS byte first i.e. matching the device register map
+ *
+ * @param[in] count : register size of in bytes (1, 2, 3 or 4)
+ * @param[in] pbuffer : uint8_t pointer to the I2C read buffer
+ *
+ * @return value : decoded uint32_t value
+ */
+
+uint32_t VL53L1_i2c_decode_uint32_t(
+ uint16_t count,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes an integer register value from an I2C read buffer
+ *
+ * The I2C read buffer is assumed to be MS byte first i.e. matching the device register map
+ *
+ * @param[in] count : integer size of in bytes (1, 2, 3 or 4)
+ * @param[in] pbuffer : uint8_t pointer to the I2C read buffer
+ * @param[in] bit_mask : bit mask to apply
+ * @param[in] down_shift : down shift to apply
+ * @param[in] offset : offset to apply after the down shift
+ *
+ * @return value : decoded integer value
+ */
+
+uint32_t VL53L1_i2c_decode_with_mask(
+ uint16_t count,
+ uint8_t *pbuffer,
+ uint32_t bit_mask,
+ uint32_t down_shift,
+ uint32_t offset);
+
+
+/**
+ * @brief Encodes a int32_t register value into an I2C write buffer
+ *
+ * The register is encoded MS byte first is the buffer i.e as per the device register map
+ *
+ * @param[in] ip_value : input int32_t value
+ * @param[in] count : register size of in bytes (1, 2, 3 or 4)
+ * @param[out] pbuffer : uint8_t pointer to the I2C write buffer
+ */
+
+void VL53L1_i2c_encode_int32_t(
+ int32_t ip_value,
+ uint16_t count,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes a int32_t register value from an I2C read buffer
+ *
+ * The I2C read buffer is assumed to be MS byte first i.e. matching the device register map
+ *
+ * @param[in] count : register size of in bytes (1, 2, 3 or 4)
+ * @param[in] pbuffer : uint8_t pointer to the I2C read buffer
+ *
+ * @return value : decoded int32_t value
+ */
+
+int32_t VL53L1_i2c_decode_int32_t(
+ uint16_t count,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Triggers the start of the provided test_mode.
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] test_mode__ctrl : VL53L1_TEST_MODE__CTRL register value
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_start_test(
+ VL53L1_DEV Dev,
+ uint8_t test_mode__ctrl);
+#endif
+
+
+/**
+ * @brief Set firmware enable register
+ *
+ * Wrapper for setting power force register state
+ * Also updates pdev->sys_ctrl.firmware__enable
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] value : register value
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_firmware_enable_register(
+ VL53L1_DEV Dev,
+ uint8_t value);
+
+
+/**
+ * @brief Enables MCU firmware
+ *
+ * @param[in] Dev : Device handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_enable_firmware(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Disables MCU firmware
+ *
+ * This required to write to MCU G02, G01 registers and access the patch RAM
+ *
+ * @param[in] Dev : Device handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_disable_firmware(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Set power force register
+ *
+ * Wrapper for setting power force register state
+ * Also updates pdev->sys_ctrl.power_management__go1_power_force
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] value : register value
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_powerforce_register(
+ VL53L1_DEV Dev,
+ uint8_t value);
+
+
+/**
+ * @brief Enables power force
+ *
+ * This prevents the G01 and patch RAM from powering down between
+ * ranges to enable reading of G01 and patch RAM data
+ *
+ * Calls VL53L1_set_powerforce_register()
+ *
+ * @param[in] Dev : Device handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+
+VL53L1_Error VL53L1_enable_powerforce(
+ VL53L1_DEV Dev);
+
+/**
+ * @brief Disables power force
+ *
+ * @param[in] Dev : Device handle
+ *
+ * Disable power force
+ *
+ * Calls VL53L1_set_powerforce_register()
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_disable_powerforce(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Clears Ranging Interrupt
+ *
+ * @param[in] Dev : Device handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+
+VL53L1_Error VL53L1_clear_interrupt(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Forces shadow stream count to zero
+ *
+ * @param[in] Dev : Device handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_force_shadow_stream_count_to_zero(
+ VL53L1_DEV Dev);
+#endif
+
+/**
+ * @brief Calculates the macro period in [us] for the input
+ * fast_osc_frequency and VCSEL period register value
+ *
+ * Processing steps:
+ *
+ * 1. PLL period from fast_osc_frequency
+ * 2. VCSEL period
+ * 3. Macro period
+ *
+ * @param[in] fast_osc_frequency : fast oscillator frequency in 4.12 MHz format
+ * @param[in] vcsel_period : VCSEL period register value
+ *
+ * @return macro_period_us : macro period in [us] 12.12 format
+ */
+
+uint32_t VL53L1_calc_macro_period_us(
+ uint16_t fast_osc_frequency,
+ uint8_t vcsel_period);
+
+
+/**
+ * @brief Calculates the Xtalk Range Ignore Threshold
+ * rate per spad in 3.13Mcps
+ *
+ * This is done by calculating the worst case xtalk seen on the array
+ * and applying a user specified fractional multiplier.
+ *
+ * @param[in] central_rate : xtalk central rate in 9.9u Kcps format
+ * @param[in] x_gradient : xtalk xgradient rate in 4.11s Kcps format
+ * @param[in] y_gradient : xtalk ygradient rate in 4.11s Kcps format
+ * @param[in] rate_mult : rate multiplier in 2.5 fractional format
+ *
+ * @return range_ignore_threshold_kcps : rate per spad in mcps 3.13
+ */
+
+uint16_t VL53L1_calc_range_ignore_threshold(
+ uint32_t central_rate,
+ int16_t x_gradient,
+ int16_t y_gradient,
+ uint8_t rate_mult);
+
+
+/**
+ * @brief Calculates the timeout value in macro period based on the input
+ * timeout period in milliseconds and the macro period in us
+ *
+ * @param[in] timeout_us : timeout period in microseconds
+ * @param[in] macro_period_us : macro period in microseconds 12.12
+ *
+ * @return timeout_mclks : timeout in macro periods
+ */
+
+uint32_t VL53L1_calc_timeout_mclks(
+ uint32_t timeout_us,
+ uint32_t macro_period_us);
+
+/**
+ * @brief Calculates the encoded timeout register value based on the input
+ * timeout period in milliseconds and the macro period in us
+ *
+ * @param[in] timeout_us : timeout period in microseconds
+ * @param[in] macro_period_us : macro period in microseconds 12.12
+ *
+ * @return timeout_encoded : encoded timeout register value
+ */
+
+uint16_t VL53L1_calc_encoded_timeout(
+ uint32_t timeout_us,
+ uint32_t macro_period_us);
+
+
+/**
+ * @brief Calculates the timeout in us based on the input
+ * timeout im macro periods value and the macro period in us
+ *
+ * @param[in] timeout_mclks : timeout im macro periods
+ * @param[in] macro_period_us : macro period in microseconds 12.12
+ *
+ * @return timeout_us : encoded timeout register value
+ */
+
+uint32_t VL53L1_calc_timeout_us(
+ uint32_t timeout_mclks,
+ uint32_t macro_period_us);
+
+/**
+ * @brief Calculates the decoded timeout in us based on the input
+ * encoded timeout register value and the macro period in us
+ *
+ * @param[in] timeout_encoded : encoded timeout register value
+ * @param[in] macro_period_us : macro period in microseconds 12.12
+ *
+ * @return timeout_us : encoded timeout register value
+ */
+
+uint32_t VL53L1_calc_decoded_timeout_us(
+ uint16_t timeout_encoded,
+ uint32_t macro_period_us);
+
+
+/**
+ * @brief Encode timeout in (LSByte * 2^MSByte) + 1 register format.
+ *
+ * @param[in] timeout_mclks : uint32_t timeout value (macro periods)
+ *
+ * @return encoded_timeout : 16-bit encoded value
+ */
+
+uint16_t VL53L1_encode_timeout(
+ uint32_t timeout_mclks);
+
+
+/**
+ * @brief Decode 16-bit timeout register value.
+ *
+ * @param[in] encoded_timeout : 16-bit timeout register value
+ *
+ * @return timeout_macro_clks : uint32_t decoded value
+ *
+ */
+
+uint32_t VL53L1_decode_timeout(
+ uint16_t encoded_timeout);
+
+
+/**
+ * @brief Converts the input MM and range timeouts in [us]
+ * into the appropriate register values
+ *
+ * Must also be run after the VCSEL period settings are changed
+ *
+ * @param[in] phasecal_config_timeout_us : requested Phase Cal Timeout e.g. 1000us
+ * @param[in] mm_config_timeout_us : requested MM Timeout e.g. 2000us
+ * @param[in] range_config_timeout_us : requested Ranging Timeout e.g 10000us
+ * @param[in] fast_osc_frequency : fast oscillator frequency in 4.12 MHz format
+ * @param[out] pgeneral : general data struct
+ * @param[out] ptiming : timing data struct with input vcsel period data
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_calc_timeout_register_values(
+ uint32_t phasecal_config_timeout_us,
+ uint32_t mm_config_timeout_us,
+ uint32_t range_config_timeout_us,
+ uint16_t fast_osc_frequency,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming);
+
+
+/**
+ * @brief Encodes the real period in PLL clocks into the register value
+ *
+ * @param[in] vcsel_period_pclks : 8-bit value
+ *
+ * @return vcsel_period_reg : 8-bit encoded value
+ *
+ */
+
+uint8_t VL53L1_encode_vcsel_period(
+ uint8_t vcsel_period_pclks);
+
+
+/**
+ * @brief Decodes an unsigned integer from a uint8_t buffer 16-bit, 24-bit or 32-bit integers.
+ *
+ * Assumes MS Byte first
+ *
+ * @param[in] pbuffer : pointer to start of integer uint8_t data
+ * @param[in] no_of_bytes : size of integer in bytes
+ *
+ * @return decoded_value : decoded integer value
+ *
+ */
+
+uint32_t VL53L1_decode_unsigned_integer(
+ uint8_t *pbuffer,
+ uint8_t no_of_bytes);
+
+
+/**
+ * @brief Encodes an unsigned integer into a uint8_t buffer MS byte first
+ *
+ * @param[in] ip_value : input unsigned integer
+ * @param[in] no_of_bytes : size of integer storage in bytes
+ * @param[out] pbuffer : pointer to output buffer
+ *
+ */
+
+void VL53L1_encode_unsigned_integer(
+ uint32_t ip_value,
+ uint8_t no_of_bytes,
+ uint8_t *pbuffer);
+
+/**
+ * @brief Get the SPAD number, byte index (0-31) and bit index (0-7) for
+ *
+ * Takes the map index (0 - 255) and calculated the SPAD number, byte index
+ * within the SPAD enable byte array and but position within the SPAD enable
+ * byte
+ *
+ *
+ * @param[in] spad_number : spad number
+ * @param[out] pbyte_index : pointer to output 0-31 byte index for SPAD enables
+ * @param[out] pbit_index : pointer to output 0-7 bit index
+ * @param[out] pbit_mask : pointer to output bit mask for the byte
+ *
+ */
+
+void VL53L1_spad_number_to_byte_bit_index(
+ uint8_t spad_number,
+ uint8_t *pbyte_index,
+ uint8_t *pbit_index,
+ uint8_t *pbit_mask);
+
+
+/**
+ * @brief Encodes a (col,row) coord value into ByteIndex.BitIndex format
+ *
+ *
+ * @param[in] row : Row
+ * @param[in] col : Column
+ * @param[out] pspad_number : Encoded Coord in Byte.Bit format
+ *
+ */
+
+void VL53L1_encode_row_col(
+ uint8_t row,
+ uint8_t col,
+ uint8_t *pspad_number);
+
+
+/**
+ * @brief Decodes encoded zone size format into width and height values
+ *
+ * @param[in] encoded_xy_size : Encoded zone size
+ * @param[out] pwidth : Decoded zone width
+ * @param[out] pheight : Decoded zone height
+ *
+ */
+
+void VL53L1_decode_zone_size(
+ uint8_t encoded_xy_size,
+ uint8_t *pwidth,
+ uint8_t *pheight);
+
+
+/**
+ * @brief Encodes a zone width & height into encoded size format
+ *
+ * @param[in] width : Zone Width
+ * @param[in] height : Zone height
+ * @param[out] pencoded_xy_size : Encoded zone size
+ *
+ */
+
+void VL53L1_encode_zone_size(
+ uint8_t width,
+ uint8_t height,
+ uint8_t *pencoded_xy_size);
+
+
+/**
+ * @brief Decodes encoded zone info into min/max limits
+ *
+ * Note both the lower left and upper right coordinated lie within
+ * the zone (inclusive)
+ *
+ * @param[in] encoded_xy_centre : Encoded zone centre (spad number)
+ * @param[in] encoded_xy_size : Encoded zone size
+ * @param[out] px_ll : Decoded zone lower left x coord
+ * @param[out] py_ll : Decoded zone lower left y coord
+ * @param[out] px_ur : Decoded zone upper right x coord
+ * @param[out] py_ur : Decoded zone upper right y coord
+ */
+
+void VL53L1_decode_zone_limits(
+ uint8_t encoded_xy_centre,
+ uint8_t encoded_xy_size,
+ int16_t *px_ll,
+ int16_t *py_ll,
+ int16_t *px_ur,
+ int16_t *py_ur);
+
+
+/**
+ * @brief Returns > 0 if input (row,col) location is an apertured SPAD
+ *
+ * @param[in] row : Row
+ * @param[in] col : Column
+ *
+ * @return is_aperture : if > 0 the location is an apertured SPAD
+ */
+
+uint8_t VL53L1_is_aperture_location(
+ uint8_t row,
+ uint8_t col);
+
+
+/**
+ * @brief Calculates the effective SPAD counts for the MM inner and outer
+ * regions based on the input MM ROI, Zone info and return good
+ * SPAD map
+ *
+ * @param[in] encoded_mm_roi_centre : Encoded MM ROI centre - spad number
+ * @param[in] encoded_mm_roi_size : Encoded MM ROI size
+ * @param[in] encoded_zone_centre : Encoded Zone centre - spad number
+ * @param[in] encoded_zone_size : Encoded Zone size
+ * @param[in] pgood_spads : Return array good SPAD map (32 bytes)
+ * @param[in] aperture_attenuation : Aperture attenuation value, Format 8.8
+ * @param[out] pmm_inner_effective_spads : MM Inner effective SPADs, Format 8.8
+ * @param[out] pmm_outer_effective_spads : MM Outer effective SPADs, Format 8.8
+ *
+ */
+
+void VL53L1_calc_mm_effective_spads(
+ uint8_t encoded_mm_roi_centre,
+ uint8_t encoded_mm_roi_size,
+ uint8_t encoded_zone_centre,
+ uint8_t encoded_zone_size,
+ uint8_t *pgood_spads,
+ uint16_t aperture_attenuation,
+ uint16_t *pmm_inner_effective_spads,
+ uint16_t *pmm_outer_effective_spads);
+
+/**
+ * @brief Function to save dynamic config data per zone at init and start range
+ *
+ * @param[in] Dev : Pointer to data structure
+ *
+ *
+ * @return VL53L1_ERROR_NONE Success
+ *
+ */
+
+VL53L1_Error VL53L1_save_cfg_data(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Encodes VL53L1_GPIO_interrupt_config_t structure to FW register format
+ *
+ * @param[in] pintconf : pointer to gpio interrupt config structure
+ * @return The encoded system__interrupt_config_gpio byte
+ */
+
+uint8_t VL53L1_encode_GPIO_interrupt_config(
+ VL53L1_GPIO_interrupt_config_t *pintconf);
+
+/**
+ * @brief Decodes FW register to VL53L1_GPIO_interrupt_config_t structure
+ *
+ * @param[in] system__interrupt_config : interrupt config register byte
+ * @return The decoded structure
+ */
+
+VL53L1_GPIO_interrupt_config_t VL53L1_decode_GPIO_interrupt_config(
+ uint8_t system__interrupt_config);
+
+/**
+ * @brief SET GPIO distance threshold
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] threshold_high : High distance threshold in mm
+ * @param[in] threshold_low : Low distance threshold in mm
+ */
+
+VL53L1_Error VL53L1_set_GPIO_distance_threshold(
+ VL53L1_DEV Dev,
+ uint16_t threshold_high,
+ uint16_t threshold_low);
+
+/**
+ * @brief SET GPIO rate threshold
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] threshold_high : High rate threshold in 9.7 Mcps
+ * @param[in] threshold_low : Low rate threshold in 9.7 Mcps
+ */
+
+VL53L1_Error VL53L1_set_GPIO_rate_threshold(
+ VL53L1_DEV Dev,
+ uint16_t threshold_high,
+ uint16_t threshold_low);
+
+/**
+ * @brief SET GPIO thresholds from structure. Sets both rate and distance
+ * thresholds
+ *
+ * @param[in] Dev : Device Handle
+ * @param[in] pintconf : Pointer to structure
+ */
+
+VL53L1_Error VL53L1_set_GPIO_thresholds_from_struct(
+ VL53L1_DEV Dev,
+ VL53L1_GPIO_interrupt_config_t *pintconf);
+
+
+/**
+ * @brief Set Ref SPAD Characterisation Config
+ *
+ * Initialises the timeout and VCSEL period for the Reference
+ * SPAD Characterisation test mode.
+ *
+ * Register Mapping:
+ *
+ * - timeout -> VL53L1_PHASECAL_CONFIG__TIMEOUT_MACROP
+ * - vcsel_period -> VL53L1_RANGE_CONFIG__VCSEL_PERIOD_A \n
+ * -> VL53L1_SD_CONFIG__WOI_SD0 \n
+ * -> VL53L1_SD_CONFIG__WOI_SD1
+ * - total_rate_target_mcps -> VL53L1_REF_SPAD_CHAR__TOTAL_RATE_TARGET_MCPS
+ * - max_count_rate_rtn_limit_mcps -> VL53L1_RANGE_CONFIG__SIGMA_THRESH
+ * - min_count_rate_rtn_limit_mcps -> VL53L1_SRANGE_CONFIG__SIGMA_THRESH
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] vcsel_period_a : VCSEL period A register value
+ * @param[in] phasecal_timeout_us : requested PhaseCal Timeout in [us]
+ * e.g 1000us
+ * @param[in] total_rate_target_mcps : Target reference rate [Mcps] 9.7 format
+ * @param[in] max_count_rate_rtn_limit_mcps : Max rate final check limit [Mcps] 9.7 format
+ * @param[in] min_count_rate_rtn_limit_mcps : Min rate final check limit [Mcps] 9.7 format
+ * @param[in] fast_osc_frequency : Fast Osc Frequency (4.12) format
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_set_ref_spad_char_config(
+ VL53L1_DEV Dev,
+ uint8_t vcsel_period_a,
+ uint32_t phasecal_timeout_us,
+ uint16_t total_rate_target_mcps,
+ uint16_t max_count_rate_rtn_limit_mcps,
+ uint16_t min_count_rate_rtn_limit_mcps,
+ uint16_t fast_osc_frequency);
+#endif
+
+
+/**
+ * @brief Applies SSC (SPAD Self Check) configuration to device.
+ *
+ * Prior to calling this function it is assumed both the Fast Osc
+ * and VCSEL have already been trimmed and the register values set.
+ *
+ * Internally the required timeout in macro periods is calculated
+ * from the input VCSEL period, fast_osc_frequency and requested
+ * timeout in microseconds.
+ *
+ * Register Mapping:
+ *
+ * - rate_select -> VL53L1_NVM_BIST__CTRL
+ * - timeout -> VL53L1_RANGE_CONFIG__TIMEOUT_MACROP_ B_HI & _LO
+ * - vcsel_period -> VL53L1_RANGE_CONFIG__VCSEL_PERIOD_B \n
+ * -> VL53L1_SD_CONFIG__WOI_SD0 \n
+ * -> VL53L1_SD_CONFIG__WOI_SD1
+ * - vcsel_start -> VL53L1_CAL_CONFIG__VCSEL_START
+ * - vcsel_width -> VL53L1_GLOBAL_CONFIG__VCSEL_WIDTH
+ * - ssc_limit_mcps -> VL53L1_RANGE_CONFIG__SIGMA_THRESH
+ *
+ * ssc_rate_limit_mcps format:
+ *
+ * - 1.15 for DCR/LCR test modes with VCSEL off
+ * - 9.7 LCR test mode with VCSEL on
+ *
+ * The configuration is set to the device via a 5-byte multi byte write.
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] pssc_cfg : pointer to VL53L1_ssc_config_t
+ * @param[in] fast_osc_frequency : Fast Osc Frequency (4.12) format
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_set_ssc_config(
+ VL53L1_DEV Dev,
+ VL53L1_ssc_config_t *pssc_cfg,
+ uint16_t fast_osc_frequency);
+#endif
+
+
+/**
+ * @brief Gets the 256 return array SSC rates from the Patch RAM
+ *
+ * Each SSC rate is 1.15 or 9.7 dependent on test run.
+ * Total of 512 bytes to read!
+ *
+ * ssc_rate_mcps buffer format:
+ *
+ * - 1.15 for DCR/LCR test modes with VCSEL off (ambient)
+ * - 9.7 LCR test mode with VCSEL on (which rate?)
+ *
+ * Assumes that power force has already been enabled
+ *
+ * Function disables firmware at start to allow patch RAM to be read
+ * and then enables the firmware before returning
+ *
+ * The order of the rates is in SPAD number order (increasing)
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] pspad_rates : pointer to VL53L1_spad_rate_data_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_get_spad_rate_data(
+ VL53L1_DEV Dev,
+ VL53L1_spad_rate_data_t *pspad_rates);
+#endif
+
+/**
+ * @brief Function to add signed margin to the
+ * xtalk plane offset value, dealing with signed and unsigned
+ * value mixing
+ *
+ * Clips output to 0 if negative
+ * Clips to max possible value of 9.9 Kcps if exceeds this limitation
+ *
+ * @param[in] plane_offset_kcps : xtalk plane offset (9.9 format) Kcps
+ * @param[in] margin_offset_kcps : margin offset signed (6.9 format) Kcps
+ *
+ * @return plane_offset_with_margin in Kcps (7.9 format)
+ */
+
+uint32_t VL53L1_calc_crosstalk_plane_offset_with_margin(
+ uint32_t plane_offset_kcps,
+ int16_t margin_offset_kcps);
+
+/**
+ * @brief Initialize the Low Power Auto data structure
+ *
+ * Patch_LowPowerAutoMode
+ *
+ * @param[in] Dev : Device Handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_low_power_auto_data_init(
+ VL53L1_DEV Dev
+ );
+
+/**
+ * @brief Reset internal state but leave low_power_auto mode intact
+ *
+ * Patch_LowPowerAutoMode
+ *
+ * @param[in] Dev : Device Handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_low_power_auto_data_stop_range(
+ VL53L1_DEV Dev
+ );
+
+/**
+ * @brief Initialize the config strcutures when low power auto preset modes are
+ * selected
+ *
+ * Patch_LowPowerAutoMode
+ *
+ * @param[in] pgeneral : pointer to the general config structure
+ * @param[in] pdynamic : pointer to the dynamic config structure
+ * @param[in] plpadata : pointer to the low power auto config structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_config_low_power_auto_mode(
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_low_power_auto_data_t *plpadata
+ );
+
+/**
+ * @brief Setup ranges after the first one in low power auto mode by turning
+ * off FW calibration steps and programming static values
+ *
+ * Patch_LowPowerAutoMode
+ *
+ * @param[out] Dev : Device handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_low_power_auto_setup_manual_calibration(
+ VL53L1_DEV Dev);
+
+/**
+ * @brief Do a DSS calculation and update manual config
+ *
+ * Patch_LowPowerAutoMode
+ *
+ * @param[out] Dev : Device handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_low_power_auto_update_DSS(
+ VL53L1_DEV Dev);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _VL53L1_API_CORE_H_ */
diff --git a/src/lib/vl53l1/core/inc/vl53l1_core_support.h b/src/lib/vl53l1/core/inc/vl53l1_core_support.h
new file mode 100644
index 0000000000..ae1b0963f7
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_core_support.h
@@ -0,0 +1,188 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*******************************************************************************/
+
+/**
+ * @file vl53l1_core_support.h
+ *
+ * @brief EwokPlus25 core function definitions
+ */
+
+#ifndef _VL53L1_CORE_SUPPORT_H_
+#define _VL53L1_CORE_SUPPORT_H_
+
+#include "vl53l1_types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+/**
+ * @brief Calculates the PLL period in [us] from the input
+ * fast_osc_frequency
+ *
+ * @param[in] fast_osc_frequency : fast oscillator frequency in 4.12 MHz format
+ *
+ * @return pll_period_us : PLL period in [us] 8.24 format
+ */
+
+uint32_t VL53L1_calc_pll_period_us(
+ uint16_t fast_osc_frequency);
+
+
+
+#ifdef PAL_EXTENDED
+/**
+ * @brief Calculates the ranging duration in ns using fixed point maths
+ * *
+ * Uses a temporary uint64_t variable internally
+ *
+ * @param[in] pll_period_us : PLL Period in [us] 0.25 format
+ * @param[in] vcsel_parm_pclks : period, width or WOI window in PLL clocks
+ * in 6.4 format.
+ * @param[in] window_vclks : ranging or ambient window duration in VCSEL clocks
+ * @param[in] periods_elapsed_mclks : elapsed time in macro clocks
+ *
+ * @return duration_us : uint32_t containing the duration time in us
+ */
+
+uint32_t VL53L1_duration_maths(
+ uint32_t pll_period_us,
+ uint32_t vcsel_parm_pclks,
+ uint32_t window_vclks,
+ uint32_t periods_elapsed_mclks);
+
+
+/**
+ * @brief Calculates the square root of the input integer
+ *
+ * Reference : http://en.wikipedia.org/wiki/Methods_of_computing_square_roots
+ *
+ * @param[in] num : input integer
+ *
+ * @return res : square root result
+ */
+
+uint32_t VL53L1_isqrt(
+ uint32_t num);
+
+/**
+ * @brief Calculates the count rate using fixed point maths
+ *
+ * Uses a temporary uint64_t variable internally
+ * Any negative negative rates are clipped to 0.
+ *
+ * @param[in] events : accumulated SPAD events
+ * @param[in] time_us : elapsed time in us
+ *
+ * @return rate_mcps : uint16_t count rate in 9.7 format
+ */
+
+uint16_t VL53L1_rate_maths(
+ int32_t events,
+ uint32_t time_us);
+
+/**
+ * @brief Calculates the Rate per spad
+ *
+ * Uses a temporary uint32_t variable internally
+ * Any output rates larger than 16 bit are clipped to 0xFFFF.
+ *
+ * @param[in] frac_bits : required output fractional precision - 7 \
+ * due to inherent resolution of pk_rate
+ * @param[in] peak_count_rate : peak signal count rate in mcps
+ * @param[in] num_spads : actual effective spads in 8.8
+ * @param[in] max_output_value : User set value to clip output
+ *
+ * @return rate_per_spad : uint16_t count rate in variable fractional format
+ */
+
+uint16_t VL53L1_rate_per_spad_maths(
+ uint32_t frac_bits,
+ uint32_t peak_count_rate,
+ uint16_t num_spads,
+ uint32_t max_output_value);
+
+
+/**
+ * @brief Calculates the range from the phase data
+ *
+ * Uses a temporary int64_t variable internally
+ *
+ * @param[in] fast_osc_frequency : Fast oscillator freq [MHz] 4.12 format
+ * @param[in] phase : phase in 5.11 format
+ * @param[in] zero_distance_phase : zero distance phase in 5.11 format
+ * @param[in] fractional_bits : valid options : 0, 1, 2
+ * @param[in] gain_factor : gain correction factor 1.11 format
+ * @param[in] range_offset_mm : range offset [mm] 14.2 format
+
+ * @return range_mm : signed range in [mm]
+ * format depends on fractional_bits input
+ */
+
+int32_t VL53L1_range_maths(
+ uint16_t fast_osc_frequency,
+ uint16_t phase,
+ uint16_t zero_distance_phase,
+ uint8_t fractional_bits,
+ int32_t gain_factor,
+ int32_t range_offset_mm);
+#endif
+
+
+/**
+ * @brief Decodes VCSEL period register value into the real period in PLL clocks
+ *
+ * @param[in] vcsel_period_reg : 8 -bit register value
+ *
+ * @return vcsel_period_pclks : 8-bit decoded value
+ *
+ */
+
+uint8_t VL53L1_decode_vcsel_period(
+ uint8_t vcsel_period_reg);
+
+/**
+ * @brief Decodes the Byte.Bit coord encoding into an (x,y) coord value
+ *
+ * @param[in] spad_number : Coord location in Byte.Bit format
+ * @param[out] prow : Decoded row
+ * @param[out] pcol : Decoded column
+ *
+ */
+
+void VL53L1_decode_row_col(
+ uint8_t spad_number,
+ uint8_t *prow,
+ uint8_t *pcol);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _VL53L1_CORE_SUPPORT_H_ */
diff --git a/src/lib/vl53l1/core/inc/vl53l1_def.h b/src/lib/vl53l1/core/inc/vl53l1_def.h
new file mode 100644
index 0000000000..0ced35f0e0
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_def.h
@@ -0,0 +1,663 @@
+/*
+* Copyright (c) 2017, STMicroelectronics - All Rights Reserved
+*
+* This file is part of VL53L1 Core and is dual licensed, either
+* 'STMicroelectronics Proprietary license'
+* or 'BSD 3-clause "New" or "Revised" License' , at your option.
+*
+********************************************************************************
+*
+* 'STMicroelectronics Proprietary license'
+*
+********************************************************************************
+*
+* License terms: STMicroelectronics Proprietary in accordance with licensing
+* terms at www.st.com/sla0044
+*
+* STMicroelectronics confidential
+* Reproduction and Communication of this document is strictly prohibited unless
+* specifically authorized in writing by STMicroelectronics.
+*
+*
+********************************************************************************
+*
+* Alternatively, VL53L1 Core may be distributed under the terms of
+* 'BSD 3-clause "New" or "Revised" License', in which case the following
+* provisions apply instead of the ones
+* mentioned above :
+*
+********************************************************************************
+*
+* License terms: BSD 3-clause "New" or "Revised" License.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions are met:
+*
+* 1. Redistributions of source code must retain the above copyright notice, this
+* list of conditions and the following disclaimer.
+*
+* 2. Redistributions in binary form must reproduce the above copyright notice,
+* this list of conditions and the following disclaimer in the documentation
+* and/or other materials provided with the distribution.
+*
+* 3. Neither the name of the copyright holder nor the names of its contributors
+* may be used to endorse or promote products derived from this software
+* without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*
+********************************************************************************
+*
+*/
+
+/**
+ * @file vl53l1_def.h
+ *
+ * @brief Type definitions for VL53L1 API.
+ *
+ */
+
+
+#ifndef _VL53L1_DEF_H_
+#define _VL53L1_DEF_H_
+
+#include "vl53l1_ll_def.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/** @defgroup VL53L1_globaldefine_group VL53L1 Defines
+ * @brief VL53L1 Defines
+ * @{
+ */
+
+
+/** VL53L1 IMPLEMENTATION major version */
+#define VL53L1_IMPLEMENTATION_VER_MAJOR 2
+/** VL53L1 IMPLEMENTATION minor version */
+#define VL53L1_IMPLEMENTATION_VER_MINOR 2
+/** VL53L1 IMPLEMENTATION sub version */
+#define VL53L1_IMPLEMENTATION_VER_SUB 1
+/** VL53L1 IMPLEMENTATION sub version */
+#define VL53L1_IMPLEMENTATION_VER_REVISION 1798
+
+/****************************************
+ * PRIVATE define do not edit
+ ****************************************/
+
+/** @brief Defines the parameters of the Get Version Functions
+ */
+typedef struct {
+ uint32_t revision; /*!< revision number */
+ uint8_t major; /*!< major number */
+ uint8_t minor; /*!< minor number */
+ uint8_t build; /*!< build number */
+} VL53L1_Version_t;
+
+
+#define VL53L1_DEVINFO_STRLEN 32
+
+/** @brief Defines the parameters of the Get Device Info Functions
+ */
+typedef struct {
+ char Name[VL53L1_DEVINFO_STRLEN];
+ /*!< Name of the Device e.g. Left_Distance */
+ char Type[VL53L1_DEVINFO_STRLEN];
+ /*!< Type of the Device e.g VL53L1 */
+ char ProductId[VL53L1_DEVINFO_STRLEN];
+ /*!< Product Identifier String
+ * @warning Not yet implemented
+ */
+ uint8_t ProductType;
+ /*!< Product Type, VL53L1 = 1, VL53L1 = 2*/
+ uint8_t ProductRevisionMajor;
+ /*!< Product revision major */
+ uint8_t ProductRevisionMinor;
+ /*!< Product revision minor */
+} VL53L1_DeviceInfo_t;
+
+
+
+/** @defgroup VL53L1_define_PresetModes_group Defines Preset modes
+ * Defines all possible preset modes for the device
+ * @{
+ */
+typedef uint8_t VL53L1_PresetModes;
+
+#define VL53L1_PRESETMODE_AUTONOMOUS ((VL53L1_PresetModes) 3)
+#define VL53L1_PRESETMODE_LITE_RANGING ((VL53L1_PresetModes) 4)
+#define VL53L1_PRESETMODE_LOWPOWER_AUTONOMOUS ((VL53L1_PresetModes) 8)
+
+ /* ... Modes to be added depending on device */
+/** @} VL53L1_define_PresetModes_group */
+
+
+/** @defgroup VL53L1_define_DistanceModes_group Defines Distance modes
+ * Defines all possible Distance modes for the device
+ * @{
+ */
+typedef uint8_t VL53L1_DistanceModes;
+
+#define VL53L1_DISTANCEMODE_SHORT ((VL53L1_DistanceModes) 1)
+#define VL53L1_DISTANCEMODE_MEDIUM ((VL53L1_DistanceModes) 2)
+#define VL53L1_DISTANCEMODE_LONG ((VL53L1_DistanceModes) 3)
+/** @} VL53L1_define_DistanceModes_group */
+
+
+/** @defgroup VL53L1_define_XtalkCal_group Defines Xtalk Calibration modes
+* Defines all possible Offset Calibration modes for the device
+* @{
+*/
+typedef uint8_t VL53L1_XtalkCalibrationModes;
+
+#define VL53L1_XTALKCALIBRATIONMODE_NO_TARGET \
+ ((VL53L1_OffsetCalibrationModes) 0)
+/*!< To perform Xtalk calibration with no target below 80 cm */
+#define VL53L1_XTALKCALIBRATIONMODE_SINGLE_TARGET \
+ ((VL53L1_OffsetCalibrationModes) 1)
+/*!< To perform Xtalk calibration with one target */
+
+/** @} VL53L1_define_XtalkCal_group */
+
+/** @defgroup VL53L1_define_OffsetCal_group Defines Offset Calibration modes
+* Defines all possible Offset Calibration modes for the device
+* @{
+*/
+typedef uint8_t VL53L1_OffsetCalibrationModes;
+
+#define VL53L1_OFFSETCALIBRATIONMODE_STANDARD \
+ ((VL53L1_OffsetCalibrationModes) 1)
+#define VL53L1_OFFSETCALIBRATIONMODE_PRERANGE_ONLY \
+ ((VL53L1_OffsetCalibrationModes) 2)
+
+/** @} VL53L1_define_OffsetCal_group */
+
+
+
+
+
+/** @defgroup VL53L1_CheckEnable_group Check Enable list
+ * @brief Check Enable code
+ *
+ * Define used to specify the LimitCheckId.
+ * Use @a VL53L1_GetLimitCheckInfo() to get the string.
+ * @{
+ */
+
+#define VL53L1_CHECKENABLE_SIGMA_FINAL_RANGE 0
+#define VL53L1_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE 1
+
+#define VL53L1_CHECKENABLE_NUMBER_OF_CHECKS 2
+
+/** @} end of VL53L1_CheckEnable_group */
+
+
+/** @defgroup VL53L1_ThresholdMode_gropup Detection Functionality
+ * @brief Defines the different functionalities for the detection feature
+ * @{
+ */
+typedef uint8_t VL53L1_ThresholdMode;
+
+#define VL53L1_THRESHOLD_CROSSED_LOW \
+ ((VL53L1_ThresholdMode) 0)
+ /*!< Trigger interrupt if value < thresh_low */
+#define VL53L1_THRESHOLD_CROSSED_HIGH \
+ ((VL53L1_ThresholdMode) 1)
+ /*!< Trigger interrupt if value > thresh_high */
+#define VL53L1_THRESHOLD_OUT_OF_WINDOW \
+ ((VL53L1_ThresholdMode) 2)
+ /*!< Trigger interrupt if value < thresh_low OR value > thresh_high */
+#define VL53L1_THRESHOLD_IN_WINDOW \
+ ((VL53L1_ThresholdMode) 3)
+ /*!< Trigger interrupt if value > thresh_low AND value < thresh_high */
+
+/** @} end of VL53L1_ThresholdMode_gropup */
+
+/** @brief Defines parameters for Distance detection Thresholds configuration
+ */
+typedef struct {
+ VL53L1_ThresholdMode CrossMode;
+ uint16_t High; /*!< Distance threshold high limit in mm */
+ uint16_t Low; /*!< Distance threshold low limit in mm */
+} VL53L1_DistanceThreshold_t;
+
+/** @brief Defines parameters for Signal rate detection Thresholds configuration
+ */
+typedef struct {
+ VL53L1_ThresholdMode CrossMode;
+ FixPoint1616_t High; /*!< Signal rate threshold high limit */
+ FixPoint1616_t Low; /*!< Signal rate threshold low limit */
+} VL53L1_RateThreshold_t;
+
+/** @defgroup VL53L1_DetectionMode_group Gpio Functionality
+ * @brief Defines conditions leading to device's IT on GPIO
+ * @{
+ */
+typedef uint8_t VL53L1_DetectionMode;
+
+#define VL53L1_DETECTION_NORMAL_RUN \
+ ((VL53L1_DetectionMode) 0)
+ /*!< Trigger interrupt on new measurement regardless of threshold
+ * just like after a VL53L1_SetPresetMode() call
+ */
+#define VL53L1_DETECTION_DISTANCE_ONLY \
+ ((VL53L1_DetectionMode) 1)
+ /*!< Trigger interrupt if "threshold event" occurs on distance */
+#define VL53L1_DETECTION_RATE_ONLY \
+ ((VL53L1_DetectionMode) 2)
+ /*!< Trigger interrupt if "threshold event" occurs on signal rate */
+#define VL53L1_DETECTION_DISTANCE_AND_RATE \
+ ((VL53L1_DetectionMode) 3)
+ /*!< Trigger interrupt if "threshold event" occurs on distance AND rate
+ */
+#define VL53L1_DETECTION_DISTANCE_OR_RATE \
+ ((VL53L1_DetectionMode) 4)
+ /*!< Trigger interrupt if "threshold event" occurs on distance OR rate
+ */
+
+/** @} end of VL53L1_DetectionMode_group */
+
+/** @brief Defines parameters for User/object Detection configuration
+ */
+typedef struct {
+ VL53L1_DetectionMode DetectionMode; /*!< See #VL53L1_DetectionMode*/
+ uint8_t IntrNoTarget; /*!< 1 to trigger IT in case of no target found */
+ VL53L1_DistanceThreshold_t Distance; /*!< limits in mm */
+ VL53L1_RateThreshold_t Rate;/*!< limits in FixPoint1616_t */
+} VL53L1_DetectionConfig_t;
+
+
+/** @brief Defines all parameters for the device
+ */
+typedef struct {
+ VL53L1_PresetModes PresetMode;
+ /*!< Defines the operating mode to be used for the next measure */
+ VL53L1_DistanceModes DistanceMode;
+ /*!< Defines the operating mode to be used for the next measure */
+ VL53L1_DistanceModes InternalDistanceMode;
+ /*!< Defines the internal operating mode to be used for the next
+ * measure
+ */
+ VL53L1_DistanceModes NewDistanceMode;
+ /*!< Defines the new operating mode to be programmed for the next
+ * measure
+ */
+ uint32_t MeasurementTimingBudgetMicroSeconds;
+ /*!< Defines the allowed total time for a single measurement */
+ uint8_t LimitChecksEnable[VL53L1_CHECKENABLE_NUMBER_OF_CHECKS];
+ /*!< This Array store all the Limit Check enable for this device. */
+ uint8_t LimitChecksStatus[VL53L1_CHECKENABLE_NUMBER_OF_CHECKS];
+ /*!< This Array stores all the Status of the check linked to last
+ * measurement.
+ */
+ FixPoint1616_t LimitChecksValue[VL53L1_CHECKENABLE_NUMBER_OF_CHECKS];
+ /*!< This Array stores all the Limit Check value for this device */
+ FixPoint1616_t LimitChecksCurrent[VL53L1_CHECKENABLE_NUMBER_OF_CHECKS];
+ /*!< This Array stores all the Limit Check current value from latest
+ * ranging
+ */
+} VL53L1_DeviceParameters_t;
+
+
+/** @defgroup VL53L1_define_State_group Defines the current status of the device
+ * Defines the current status of the device
+ * @{
+ */
+
+typedef uint8_t VL53L1_State;
+
+#define VL53L1_STATE_POWERDOWN ((VL53L1_State) 0)
+ /*!< Device is in HW reset */
+#define VL53L1_STATE_WAIT_STATICINIT ((VL53L1_State) 1)
+ /*!< Device is initialized and wait for static initialization */
+#define VL53L1_STATE_STANDBY ((VL53L1_State) 2)
+ /*!< Device is in Low power Standby mode */
+#define VL53L1_STATE_IDLE ((VL53L1_State) 3)
+ /*!< Device has been initialized and ready to do measurements */
+#define VL53L1_STATE_RUNNING ((VL53L1_State) 4)
+ /*!< Device is performing measurement */
+#define VL53L1_STATE_RESET ((VL53L1_State) 5)
+ /*!< Soft reset has been run on Device */
+#define VL53L1_STATE_UNKNOWN ((VL53L1_State) 98)
+ /*!< Device is in unknown state and need to be rebooted */
+#define VL53L1_STATE_ERROR ((VL53L1_State) 99)
+ /*!< Device is in error state and need to be rebooted */
+
+/** @} VL53L1_define_State_group */
+
+
+
+/**
+ * @struct VL53L1_RangingMeasurementData_t
+ * @brief Single Range measurement data.
+ */
+typedef struct {
+ uint32_t TimeStamp;
+ /*!< 32-bit time stamp.
+ * @warning Not yet implemented
+ */
+
+ uint8_t StreamCount;
+ /*!< 8-bit Stream Count. */
+
+ uint8_t RangeQualityLevel;
+ /*!< indicate a quality level in percentage from 0 to 100
+ * @warning Not yet implemented
+ */
+
+ FixPoint1616_t SignalRateRtnMegaCps;
+ /*!< Return signal rate (MCPS)\n these is a 16.16 fix point
+ * value, which is effectively a measure of target
+ * reflectance.
+ */
+
+ FixPoint1616_t AmbientRateRtnMegaCps;
+ /*!< Return ambient rate (MCPS)\n these is a 16.16 fix point
+ * value, which is effectively a measure of the ambien
+ * t light.
+ */
+
+ uint16_t EffectiveSpadRtnCount;
+ /*!< Return the effective SPAD count for the return signal.
+ * To obtain Real value it should be divided by 256
+ */
+
+ FixPoint1616_t SigmaMilliMeter;
+ /*!< Return the Sigma value in millimeter */
+
+ int16_t RangeMilliMeter;
+ /*!< range distance in millimeter. This should be between
+ * RangeMinMilliMeter and RangeMaxMilliMeter
+ */
+
+ uint8_t RangeFractionalPart;
+ /*!< Fractional part of range distance. Final value is a
+ * RangeMilliMeter + RangeFractionalPart/256.
+ * @warning Not yet implemented
+ */
+
+ uint8_t RangeStatus;
+ /*!< Range Status for the current measurement. This is device
+ * dependent. Value = 0 means value is valid.
+ */
+} VL53L1_RangingMeasurementData_t;
+
+
+
+/** @brief Defines User Zone(ROI) parameters
+ *
+ */
+typedef struct {
+
+ uint8_t TopLeftX; /*!< Top Left x coordinate: 0-15 range */
+ uint8_t TopLeftY; /*!< Top Left y coordinate: 0-15 range */
+ uint8_t BotRightX; /*!< Bot Right x coordinate: 0-15 range */
+ uint8_t BotRightY; /*!< Bot Right y coordinate: 0-15 range */
+
+} VL53L1_UserRoi_t;
+
+
+/** @brief Defines ROI configuration parameters
+ *
+ * Support up a max of 16 zones, Each Zone has the same size
+ *
+ */
+
+/**
+ * @struct VL53L1_CustomerNvmManaged_t
+ *
+ */
+
+typedef struct {
+ uint8_t global_config__spad_enables_ref_0;
+ uint8_t global_config__spad_enables_ref_1;
+ uint8_t global_config__spad_enables_ref_2;
+ uint8_t global_config__spad_enables_ref_3;
+ uint8_t global_config__spad_enables_ref_4;
+ uint8_t global_config__spad_enables_ref_5;
+ uint8_t global_config__ref_en_start_select;
+ uint8_t ref_spad_man__num_requested_ref_spads;
+ uint8_t ref_spad_man__ref_location;
+ uint32_t algo__crosstalk_compensation_plane_offset_kcps;
+ int16_t algo__crosstalk_compensation_x_plane_gradient_kcps;
+ int16_t algo__crosstalk_compensation_y_plane_gradient_kcps;
+ uint16_t ref_spad_char__total_rate_target_mcps;
+ int16_t algo__part_to_part_range_offset_mm;
+ int16_t mm_config__inner_offset_mm;
+ int16_t mm_config__outer_offset_mm;
+} VL53L1_CustomerNvmManaged_t;
+
+/**
+ * @struct VL53L1_CalibrationData_t
+ * @brief Structure for storing the Calibration Data
+ *
+ */
+
+typedef struct {
+
+ uint32_t struct_version;
+ VL53L1_CustomerNvmManaged_t customer;
+ VL53L1_additional_offset_cal_data_t add_off_cal_data;
+ VL53L1_optical_centre_t optical_centre;
+ VL53L1_gain_calibration_data_t gain_cal;
+ VL53L1_cal_peak_rate_map_t cal_peak_rate_map;
+
+} VL53L1_CalibrationData_t;
+
+#define VL53L1_ADDITIONAL_CALIBRATION_DATA_STRUCT_VERSION 0x10
+/** VL53L1 additional Calibration Data struct version final struct version
+ * is given by adding it to VL53L1_LL_CALIBRATION_DATA_STRUCT_VERSION
+ */
+
+#define VL53L1_CALIBRATION_DATA_STRUCT_VERSION \
+ (VL53L1_LL_CALIBRATION_DATA_STRUCT_VERSION + \
+ VL53L1_ADDITIONAL_CALIBRATION_DATA_STRUCT_VERSION)
+/* VL53L1 Calibration Data struct version */
+
+/**
+ * @struct VL53L1_AdditionalData_t
+ * @brief Structure for storing the Additional Data
+ *
+ */
+typedef VL53L1_additional_data_t VL53L1_AdditionalData_t;
+
+
+typedef uint8_t VL53L1_SequenceStepId;
+
+#define VL53L1_SEQUENCESTEP_VHV ((VL53L1_SequenceStepId) 0)
+/*!>12)&0xFFFF)
+#define VL53L1_FIXPOINT44TOFIXPOINT1616(Value) \
+ (FixPoint1616_t)(Value<<12)
+
+#define VL53L1_FIXPOINT1616TOFIXPOINT72(Value) \
+ (uint16_t)((Value>>14)&0xFFFF)
+#define VL53L1_FIXPOINT72TOFIXPOINT1616(Value) \
+ (FixPoint1616_t)(Value<<14)
+
+#define VL53L1_FIXPOINT1616TOFIXPOINT97(Value) \
+ (uint16_t)((Value>>9)&0xFFFF)
+#define VL53L1_FIXPOINT97TOFIXPOINT1616(Value) \
+ (FixPoint1616_t)(Value<<9)
+
+#define VL53L1_FIXPOINT1616TOFIXPOINT88(Value) \
+ (uint16_t)((Value>>8)&0xFFFF)
+#define VL53L1_FIXPOINT88TOFIXPOINT1616(Value) \
+ (FixPoint1616_t)(Value<<8)
+
+#define VL53L1_FIXPOINT1616TOFIXPOINT412(Value) \
+ (uint16_t)((Value>>4)&0xFFFF)
+#define VL53L1_FIXPOINT412TOFIXPOINT1616(Value) \
+ (FixPoint1616_t)(Value<<4)
+
+#define VL53L1_FIXPOINT1616TOFIXPOINT313(Value) \
+ (uint16_t)((Value>>3)&0xFFFF)
+#define VL53L1_FIXPOINT313TOFIXPOINT1616(Value) \
+ (FixPoint1616_t)(Value<<3)
+
+#define VL53L1_FIXPOINT1616TOFIXPOINT08(Value) \
+ (uint8_t)((Value>>8)&0x00FF)
+#define VL53L1_FIXPOINT08TOFIXPOINT1616(Value) \
+ (FixPoint1616_t)(Value<<8)
+
+#define VL53L1_FIXPOINT1616TOFIXPOINT53(Value) \
+ (uint8_t)((Value>>13)&0x00FF)
+#define VL53L1_FIXPOINT53TOFIXPOINT1616(Value) \
+ (FixPoint1616_t)(Value<<13)
+
+#define VL53L1_FIXPOINT1616TOFIXPOINT102(Value) \
+ (uint16_t)((Value>>14)&0x0FFF)
+#define VL53L1_FIXPOINT102TOFIXPOINT1616(Value) \
+ (FixPoint1616_t)(Value<<14)
+
+#define VL53L1_FIXPOINT1616TOFIXPOINT142(Value) \
+ (uint16_t)((Value>>14)&0xFFFF)
+#define VL53L1_FIXPOINT142TOFIXPOINT1616(Value) \
+ (FixPoint1616_t)(Value<<14)
+
+#define VL53L1_FIXPOINT1616TOFIXPOINT160(Value) \
+ (uint16_t)((Value>>16)&0xFFFF)
+#define VL53L1_FIXPOINT160TOFIXPOINT1616(Value) \
+ (FixPoint1616_t)(Value<<16)
+
+#define VL53L1_MAKEUINT16(lsb, msb) (uint16_t)((((uint16_t)msb)<<8) + \
+ (uint16_t)lsb)
+
+#ifndef SUPPRESS_UNUSED_WARNING
+#define SUPPRESS_UNUSED_WARNING(x) ((void) (x))
+#endif
+
+#define CHECK_ERROR_GO_ENDFUNC do {\
+ if (Status != VL53L1_ERROR_NONE) \
+ goto ENDFUNC; \
+ } while (0)
+
+/** @} VL53L1_define_GeneralMacro_group */
+
+/** @} VL53L1_globaldefine_group */
+
+
+
+#ifdef __cplusplus
+}
+#endif
+
+
+#endif /* _VL53L1_DEF_H_ */
diff --git a/src/lib/vl53l1/core/inc/vl53l1_error_codes.h b/src/lib/vl53l1/core/inc/vl53l1_error_codes.h
new file mode 100644
index 0000000000..16df23e0f2
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_error_codes.h
@@ -0,0 +1,219 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*******************************************************************************/
+
+/**
+ * @file vl53l1_error_codes.h
+ *
+ * @brief Error Code definitions for VL53L1 API.
+ *
+ */
+
+#ifndef _VL53L1_ERROR_CODES_H_
+#define _VL53L1_ERROR_CODES_H_
+
+#include "vl53l1_types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+/****************************************
+ * PRIVATE define do not edit
+ ****************************************/
+
+/** @defgroup VL53L1_define_Error_group Error and Warning code returned by API
+ * The following DEFINE are used to identify the PAL ERROR
+ * @{
+ */
+
+typedef int8_t VL53L1_Error;
+
+#define VL53L1_ERROR_NONE ((VL53L1_Error) 0)
+#define VL53L1_ERROR_CALIBRATION_WARNING ((VL53L1_Error) - 1)
+ /*!< Warning invalid calibration data may be in used
+ \a VL53L1_InitData()
+ \a VL53L1_GetOffsetCalibrationData
+ \a VL53L1_SetOffsetCalibrationData */
+#define VL53L1_ERROR_MIN_CLIPPED ((VL53L1_Error) - 2)
+ /*!< Warning parameter passed was clipped to min before to be applied */
+
+#define VL53L1_ERROR_UNDEFINED ((VL53L1_Error) - 3)
+ /*!< Unqualified error */
+#define VL53L1_ERROR_INVALID_PARAMS ((VL53L1_Error) - 4)
+ /*!< Parameter passed is invalid or out of range */
+#define VL53L1_ERROR_NOT_SUPPORTED ((VL53L1_Error) - 5)
+ /*!< Function is not supported in current mode or configuration */
+#define VL53L1_ERROR_RANGE_ERROR ((VL53L1_Error) - 6)
+ /*!< Device report a ranging error interrupt status */
+#define VL53L1_ERROR_TIME_OUT ((VL53L1_Error) - 7)
+ /*!< Aborted due to time out */
+#define VL53L1_ERROR_MODE_NOT_SUPPORTED ((VL53L1_Error) - 8)
+ /*!< Asked mode is not supported by the device */
+#define VL53L1_ERROR_BUFFER_TOO_SMALL ((VL53L1_Error) - 9)
+ /*!< ... */
+#define VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL ((VL53L1_Error) - 10)
+ /*!< Supplied buffer is larger than I2C supports */
+#define VL53L1_ERROR_GPIO_NOT_EXISTING ((VL53L1_Error) - 11)
+ /*!< User tried to setup a non-existing GPIO pin */
+#define VL53L1_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED ((VL53L1_Error) - 12)
+ /*!< unsupported GPIO functionality */
+#define VL53L1_ERROR_CONTROL_INTERFACE ((VL53L1_Error) - 13)
+ /*!< error reported from IO functions */
+#define VL53L1_ERROR_INVALID_COMMAND ((VL53L1_Error) - 14)
+ /*!< The command is not allowed in the current device state
+ * (power down) */
+#define VL53L1_ERROR_DIVISION_BY_ZERO ((VL53L1_Error) - 15)
+ /*!< In the function a division by zero occurs */
+#define VL53L1_ERROR_REF_SPAD_INIT ((VL53L1_Error) - 16)
+ /*!< Error during reference SPAD initialization */
+#define VL53L1_ERROR_GPH_SYNC_CHECK_FAIL ((VL53L1_Error) - 17)
+ /*!< GPH sync interrupt check fail - API out of sync with device*/
+#define VL53L1_ERROR_STREAM_COUNT_CHECK_FAIL ((VL53L1_Error) - 18)
+ /*!< Stream count check fail - API out of sync with device */
+#define VL53L1_ERROR_GPH_ID_CHECK_FAIL ((VL53L1_Error) - 19)
+ /*!< GPH ID check fail - API out of sync with device */
+#define VL53L1_ERROR_ZONE_STREAM_COUNT_CHECK_FAIL ((VL53L1_Error) - 20)
+ /*!< Zone dynamic config stream count check failed - API out of sync */
+#define VL53L1_ERROR_ZONE_GPH_ID_CHECK_FAIL ((VL53L1_Error) - 21)
+ /*!< Zone dynamic config GPH ID check failed - API out of sync */
+
+#define VL53L1_ERROR_XTALK_EXTRACTION_NO_SAMPLE_FAIL ((VL53L1_Error) - 22)
+ /*!< Thrown when run_xtalk_extraction fn has 0 succesful samples
+ * when using the full array to sample the xtalk. In this case there is
+ * not enough information to generate new Xtalk parm info. The function
+ * will exit and leave the current xtalk parameters unaltered */
+#define VL53L1_ERROR_XTALK_EXTRACTION_SIGMA_LIMIT_FAIL ((VL53L1_Error) - 23)
+ /*!< Thrown when run_xtalk_extraction fn has found that the
+ * avg sigma estimate of the full array xtalk sample is > than the
+ * maximal limit allowed. In this case the xtalk sample is too noisy for
+ * measurement. The function will exit and leave the current xtalk parameters
+ * unaltered. */
+
+
+#define VL53L1_ERROR_OFFSET_CAL_NO_SAMPLE_FAIL ((VL53L1_Error) - 24)
+ /*!< Thrown if there one of stages has no valid offset calibration
+ * samples. A fatal error calibration not valid */
+#define VL53L1_ERROR_OFFSET_CAL_NO_SPADS_ENABLED_FAIL ((VL53L1_Error) - 25)
+ /*!< Thrown if there one of stages has zero effective SPADS
+ * Traps the case when MM1 SPADs is zero.
+ * A fatal error calibration not valid */
+#define VL53L1_ERROR_ZONE_CAL_NO_SAMPLE_FAIL ((VL53L1_Error) - 26)
+ /*!< Thrown if then some of the zones have no valid samples
+ * A fatal error calibration not valid */
+
+#define VL53L1_ERROR_TUNING_PARM_KEY_MISMATCH ((VL53L1_Error) - 27)
+ /*!< Thrown if the tuning file key table version does not match with
+ * expected value. The driver expects the key table version to match
+ * the compiled default version number in the define
+ * #VL53L1_TUNINGPARM_KEY_TABLE_VERSION_DEFAULT
+ * */
+
+#define VL53L1_WARNING_REF_SPAD_CHAR_NOT_ENOUGH_SPADS ((VL53L1_Error) - 28)
+ /*!< Thrown if there are less than 5 good SPADs are available. */
+#define VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_HIGH ((VL53L1_Error) - 29)
+ /*!< Thrown if the final reference rate is greater than
+ the upper reference rate limit - default is 40 Mcps.
+ Implies a minimum Q3 (x10) SPAD (5) selected */
+#define VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_LOW ((VL53L1_Error) - 30)
+ /*!< Thrown if the final reference rate is less than
+ the lower reference rate limit - default is 10 Mcps.
+ Implies maximum Q1 (x1) SPADs selected */
+
+
+#define VL53L1_WARNING_OFFSET_CAL_MISSING_SAMPLES ((VL53L1_Error) - 31)
+ /*!< Thrown if there is less than the requested number of
+ * valid samples. */
+#define VL53L1_WARNING_OFFSET_CAL_SIGMA_TOO_HIGH ((VL53L1_Error) - 32)
+ /*!< Thrown if the offset calibration range sigma estimate is greater
+ * than 8.0 mm. This is the recommended min value to yield a stable
+ * offset measurement */
+#define VL53L1_WARNING_OFFSET_CAL_RATE_TOO_HIGH ((VL53L1_Error) - 33)
+ /*!< Thrown when VL53L1_run_offset_calibration() peak rate is greater
+ than that 50.0Mcps. This is the recommended max rate to avoid
+ pile-up influencing the offset measurement */
+#define VL53L1_WARNING_OFFSET_CAL_SPAD_COUNT_TOO_LOW ((VL53L1_Error) - 34)
+ /*!< Thrown when VL53L1_run_offset_calibration() when one of stages
+ range has less that 5.0 effective SPADS. This is the recommended
+ min value to yield a stable offset */
+
+
+#define VL53L1_WARNING_ZONE_CAL_MISSING_SAMPLES ((VL53L1_Error) - 35)
+ /*!< Thrown if one of more of the zones have less than
+ the requested number of valid samples */
+#define VL53L1_WARNING_ZONE_CAL_SIGMA_TOO_HIGH ((VL53L1_Error) - 36)
+ /*!< Thrown if one or more zones have sigma estimate value greater
+ * than 8.0 mm. This is the recommended min value to yield a stable
+ * offset measurement */
+#define VL53L1_WARNING_ZONE_CAL_RATE_TOO_HIGH ((VL53L1_Error) - 37)
+ /*!< Thrown if one of more zones have peak rate higher than
+ that 50.0Mcps. This is the recommended max rate to avoid
+ pile-up influencing the offset measurement */
+
+
+#define VL53L1_WARNING_XTALK_MISSING_SAMPLES ((VL53L1_Error) - 38)
+ /*!< Thrown to notify that some of the xtalk samples did not yield
+ * valid ranging pulse data while attempting to measure
+ * the xtalk signal in vl53l1_run_xtalk_extract(). This can signify any of
+ * the zones are missing samples, for further debug information the
+ * xtalk_results struct should be referred to. This warning is for
+ * notification only, the xtalk pulse and shape have still been generated
+ */
+#define VL53L1_WARNING_XTALK_NO_SAMPLES_FOR_GRADIENT ((VL53L1_Error) - 39)
+ /*!< Thrown to notify that some of teh xtalk samples used for gradient
+ * generation did not yield valid ranging pulse data while attempting to
+ * measure the xtalk signal in vl53l1_run_xtalk_extract(). This can signify
+ * that any one of the zones 0-3 yielded no successful samples. The
+ * xtalk_results struct should be referred to for further debug info.
+ * This warning is for notification only, the xtalk pulse and shape
+ * have still been generated.
+ */
+#define VL53L1_WARNING_XTALK_SIGMA_LIMIT_FOR_GRADIENT ((VL53L1_Error) - 40)
+/*!< Thrown to notify that some of the xtalk samples used for gradient
+ * generation did not pass the sigma limit check while attempting to
+ * measure the xtalk signal in vl53l1_run_xtalk_extract(). This can signify
+ * that any one of the zones 0-3 yielded an avg sigma_mm value > the limit.
+ * The xtalk_results struct should be referred to for further debug info.
+ * This warning is for notification only, the xtalk pulse and shape
+ * have still been generated.
+ */
+
+#define VL53L1_ERROR_NOT_IMPLEMENTED ((VL53L1_Error) - 41)
+ /*!< Tells requested functionality has not been implemented yet or
+ * not compatible with the device */
+#define VL53L1_ERROR_PLATFORM_SPECIFIC_START ((VL53L1_Error) - 60)
+ /*!< Tells the starting code for platform */
+/** @} VL53L1_define_Error_group */
+
+
+#ifdef __cplusplus
+}
+#endif
+
+
+#endif /* _VL53L1_ERROR_CODES_H_ */
diff --git a/src/lib/vl53l1/core/inc/vl53l1_error_exceptions.h b/src/lib/vl53l1/core/inc/vl53l1_error_exceptions.h
new file mode 100644
index 0000000000..a84391dea1
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_error_exceptions.h
@@ -0,0 +1,59 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*******************************************************************************/
+
+/**
+ * @file vl53l1_error_exceptions.h
+ *
+ * @brief EwokPlus25 LL Driver definitions for control of error handling in LL driver
+ */
+
+#ifndef _VL53L1_ERROR_EXCEPTIONS_H_
+#define _VL53L1_ERROR_EXCEPTIONS_H_
+
+#define IGNORE_DIVISION_BY_ZERO 0
+
+#define IGNORE_XTALK_EXTRACTION_NO_SAMPLE_FAIL 0
+#define IGNORE_XTALK_EXTRACTION_SIGMA_LIMIT_FAIL 0
+#define IGNORE_XTALK_EXTRACTION_NO_SAMPLE_FOR_GRADIENT_WARN 0
+#define IGNORE_XTALK_EXTRACTION_SIGMA_LIMIT_FOR_GRADIENT_WARN 0
+#define IGNORE_XTALK_EXTRACTION_MISSING_SAMPLES_WARN 0
+
+#define IGNORE_REF_SPAD_CHAR_NOT_ENOUGH_SPADS 0
+#define IGNORE_REF_SPAD_CHAR_RATE_TOO_HIGH 0
+#define IGNORE_REF_SPAD_CHAR_RATE_TOO_LOW 0
+
+#define IGNORE_OFFSET_CAL_MISSING_SAMPLES 0
+#define IGNORE_OFFSET_CAL_SIGMA_TOO_HIGH 0
+#define IGNORE_OFFSET_CAL_RATE_TOO_HIGH 0
+#define IGNORE_OFFSET_CAL_SPAD_COUNT_TOO_LOW 0
+
+#define IGNORE_ZONE_CAL_MISSING_SAMPLES 0
+#define IGNORE_ZONE_CAL_SIGMA_TOO_HIGH 0
+#define IGNORE_ZONE_CAL_RATE_TOO_HIGH 0
+
+#endif /* _VL53L1_ERROR_EXCEPTIONS_H_ */
diff --git a/src/lib/vl53l1/core/inc/vl53l1_error_strings.h b/src/lib/vl53l1/core/inc/vl53l1_error_strings.h
new file mode 100644
index 0000000000..3c68b0f119
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_error_strings.h
@@ -0,0 +1,175 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*******************************************************************************/
+
+/**
+ * @file vl53l1_error_strings.h
+ * @brief VL53L1 function declarations for decoding error codes to a
+ * text strings
+ */
+
+
+#ifndef VL53L1_ERROR_STRINGS_H_
+#define VL53L1_ERROR_STRINGS_H_
+
+#include "vl53l1_error_codes.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+/**
+ * @brief Generates an error string for the input PAL error code
+ *
+ * @param[in] PalErrorCode : PAL Error Code
+ * @param[out] pPalErrorString : pointer to character buffer
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_pal_error_string(
+ VL53L1_Error PalErrorCode,
+ char *pPalErrorString);
+
+
+#ifndef VL53L1_USE_EMPTY_STRING
+
+ /* PAL ERROR strings */
+ #define VL53L1_STRING_ERROR_NONE \
+ "No Error"
+ #define VL53L1_STRING_ERROR_CALIBRATION_WARNING \
+ "Calibration Warning Error"
+ #define VL53L1_STRING_ERROR_MIN_CLIPPED \
+ "Min clipped error"
+ #define VL53L1_STRING_ERROR_UNDEFINED \
+ "Undefined error"
+ #define VL53L1_STRING_ERROR_INVALID_PARAMS \
+ "Invalid parameters error"
+ #define VL53L1_STRING_ERROR_NOT_SUPPORTED \
+ "Not supported error"
+ #define VL53L1_STRING_ERROR_RANGE_ERROR \
+ "Range error"
+ #define VL53L1_STRING_ERROR_TIME_OUT \
+ "Time out error"
+ #define VL53L1_STRING_ERROR_MODE_NOT_SUPPORTED \
+ "Mode not supported error"
+ #define VL53L1_STRING_ERROR_BUFFER_TOO_SMALL \
+ "Buffer too small"
+ #define VL53L1_STRING_ERROR_COMMS_BUFFER_TOO_SMALL \
+ "Comms Buffer too small"
+ #define VL53L1_STRING_ERROR_GPIO_NOT_EXISTING \
+ "GPIO not existing"
+ #define VL53L1_STRING_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED \
+ "GPIO funct not supported"
+ #define VL53L1_STRING_ERROR_CONTROL_INTERFACE \
+ "Control Interface Error"
+ #define VL53L1_STRING_ERROR_INVALID_COMMAND \
+ "Invalid Command Error"
+ #define VL53L1_STRING_ERROR_DIVISION_BY_ZERO \
+ "Division by zero Error"
+ #define VL53L1_STRING_ERROR_REF_SPAD_INIT \
+ "Reference Spad Init Error"
+ #define VL53L1_STRING_ERROR_GPH_SYNC_CHECK_FAIL \
+ "GPH Sync Check Fail - API out of sync"
+ #define VL53L1_STRING_ERROR_STREAM_COUNT_CHECK_FAIL \
+ "Stream Count Check Fail - API out of sync"
+ #define VL53L1_STRING_ERROR_GPH_ID_CHECK_FAIL \
+ "GPH ID Check Fail - API out of sync"
+ #define VL53L1_STRING_ERROR_ZONE_STREAM_COUNT_CHECK_FAIL \
+ "Zone Stream Count Check Fail - API out of sync"
+ #define VL53L1_STRING_ERROR_ZONE_GPH_ID_CHECK_FAIL \
+ "Zone GPH ID Check Fail - API out of sync"
+
+ #define VL53L1_STRING_ERROR_XTALK_EXTRACTION_NO_SAMPLES_FAIL \
+ "No Xtalk using full array - Xtalk Extract Fail"
+ #define VL53L1_STRING_ERROR_XTALK_EXTRACTION_SIGMA_LIMIT_FAIL \
+ "Xtalk does not meet required sigma limit - Xtalk Extract Fail"
+
+ #define VL53L1_STRING_ERROR_OFFSET_CAL_NO_SAMPLE_FAIL \
+ "Offset Cal - one of more stages with no valid samples - fatal"
+ #define VL53L1_STRING_ERROR_OFFSET_CAL_NO_SPADS_ENABLED_FAIL \
+ "Offset Cal - one of more stages with no SPADS enables - fatal"
+ #define VL53L1_STRING_ERROR_ZONE_CAL_NO_SAMPLE_FAIL \
+ "Zone Cal - one of more zones with no valid samples - fatal"
+
+ #define VL53L1_STRING_WARNING_REF_SPAD_CHAR_NOT_ENOUGH_SPADS \
+ "Ref SPAD Char - Not Enough Good SPADs"
+ #define VL53L1_STRING_WARNING_REF_SPAD_CHAR_RATE_TOO_HIGH \
+ "Ref SPAD Char - Final Ref Rate too high"
+ #define VL53L1_STRING_WARNING_REF_SPAD_CHAR_RATE_TOO_LOW \
+ "Ref SPAD Char - Final Ref Rate too low"
+
+ #define VL53L1_STRING_WARNING_OFFSET_CAL_MISSING_SAMPLES \
+ "Offset Cal - Less than the requested number of valid samples"
+ #define VL53L1_STRING_WARNING_OFFSET_CAL_SIGMA_TOO_HIGH \
+ "Offset Cal - Sigma estimate value too high - offset not stable"
+ #define VL53L1_STRING_WARNING_OFFSET_CAL_RATE_TOO_HIGH \
+ "Offset Cal - Rate too high - in pile up"
+ #define VL53L1_STRING_WARNING_OFFSET_CAL_SPAD_COUNT_TOO_LOW \
+ "Offset Cal - Insufficient SPADs - offset may not be stable"
+
+ #define VL53L1_STRING_WARNING_ZONE_CAL_MISSING_SAMPLES \
+ "Zone Cal - One or more zone with less than requested valid samples"
+ #define VL53L1_STRING_WARNING_ZONE_CAL_SIGMA_TOO_HIGH \
+ "Zone Cal - One of more zones the sigma estimate too high"
+ #define VL53L1_STRING_WARNING_ZONE_CAL_RATE_TOO_HIGH \
+ "Zone Cal - One of more zones with rate too high - in pile up"
+
+ #define VL53L1_STRING_WARNING_XTALK_NO_SAMPLES_FOR_GRADIENT \
+ "Xtalk - Gradient sample num = 0"
+ #define VL53L1_STRING_WARNING_XTALK_SIGMA_LIMIT_FOR_GRADIENT \
+ "Xtalk - Gradient Sigma > Limit"
+ #define VL53L1_STRING_WARNING_XTALK_MISSING_SAMPLES \
+ "Xtalk - Some missing and invalid samples"
+
+ #define VL53L1_STRING_ERROR_DEVICE_FIRMWARE_TOO_OLD \
+ "Device Firmware too old"
+ #define VL53L1_STRING_ERROR_DEVICE_FIRMWARE_TOO_NEW \
+ "Device Firmware too new"
+ #define VL53L1_STRING_ERROR_UNIT_TEST_FAIL \
+ "Unit Test Fail"
+ #define VL53L1_STRING_ERROR_FILE_READ_FAIL \
+ "File Read Fail"
+ #define VL53L1_STRING_ERROR_FILE_WRITE_FAIL \
+ "File Write Fail"
+
+ #define VL53L1_STRING_ERROR_NOT_IMPLEMENTED \
+ "Not implemented error"
+ #define VL53L1_STRING_UNKNOW_ERROR_CODE \
+ "Unknown Error Code"
+
+#endif /* VL53L1_USE_EMPTY_STRING */
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
+
diff --git a/src/lib/vl53l1/core/inc/vl53l1_ll_def.h b/src/lib/vl53l1/core/inc/vl53l1_ll_def.h
new file mode 100644
index 0000000000..fd40c6221d
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_ll_def.h
@@ -0,0 +1,1064 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*******************************************************************************/
+
+/**
+ * @file vl53l1_ll_def.h
+ *
+ * @brief Type definitions for VL53L1 LL Driver.
+ *
+ */
+
+
+#ifndef _VL53L1_LL_DEF_H_
+#define _VL53L1_LL_DEF_H_
+
+#include "vl53l1_ll_device.h"
+#include "vl53l1_error_codes.h"
+#include "vl53l1_register_structs.h"
+#include "vl53l1_platform_user_config.h"
+#include "vl53l1_platform_user_defines.h"
+#include "vl53l1_error_exceptions.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/** @defgroup VL53L1_globalLLDriverDefine_group VL53L1 Defines
+ * @brief VL53L1 LL Driver Defines
+ * @{
+ */
+
+/** VL53L1 Low Level Driver IMPLEMENTATION major version */
+#define VL53L1_LL_API_IMPLEMENTATION_VER_MAJOR 1
+/** VL53L1 Low Level DriverI IMPLEMENTATION minor version */
+#define VL53L1_LL_API_IMPLEMENTATION_VER_MINOR 2
+/** VL53L1 Low Level DriverI IMPLEMENTATION sub version */
+#define VL53L1_LL_API_IMPLEMENTATION_VER_SUB 9
+/** VL53L1 Low Level Driver IMPLEMENTATION sub version */
+#define VL53L1_LL_API_IMPLEMENTATION_VER_REVISION 75
+
+#define VL53L1_LL_API_IMPLEMENTATION_VER_STRING "1.2.9.75"
+
+/** VL53L1_FIRMWARE min and max compatible revisions */
+#define VL53L1_FIRMWARE_VER_MINIMUM 398
+#define VL53L1_FIRMWARE_VER_MAXIMUM 400
+
+
+/****************************************
+ * PRIVATE define do not edit
+ ****************************************/
+
+#define VL53L1_LL_CALIBRATION_DATA_STRUCT_VERSION 0xECAB0102
+ /** VL53L1 Calibration Data struct version */
+
+/* Start Patch_ZoneCalDataStructVersion_11854 */
+
+#define VL53L1_LL_ZONE_CALIBRATION_DATA_STRUCT_VERSION 0xECAE0101
+ /** VL53L1 Zone Calibration Data struct version */
+
+/* End Patch_ZoneCalDataStructVersion_11854 */
+
+#define VL53L1_MAX_OFFSET_RANGE_RESULTS 3
+ /*!< Sets the maximum number of offset range results
+ required for the offset calibration.
+ Order is RANGE, MM1, MM2 */
+
+#define VL53L1_NVM_MAX_FMT_RANGE_DATA 4
+ /*!< The number of FMT range data points stored in NVM */
+
+#define VL53L1_NVM_PEAK_RATE_MAP_SAMPLES 25
+ /*!< The number of samples in the NVM peak rate signal map */
+#define VL53L1_NVM_PEAK_RATE_MAP_WIDTH 5
+ /*!< Array width of NVM peak rate signal map */
+#define VL53L1_NVM_PEAK_RATE_MAP_HEIGHT 5
+ /*!< Array height the NVM peak rate signal map */
+
+/** @defgroup VL53L1_defineExtraError_group Error and Warning code returned by API
+ * The following DEFINE are used to identify the PAL ERROR
+ * @{
+ */
+
+#define VL53L1_ERROR_DEVICE_FIRMWARE_TOO_OLD ((VL53L1_Error) - 80)
+ /*!< Device Firmware too old .. */
+#define VL53L1_ERROR_DEVICE_FIRMWARE_TOO_NEW ((VL53L1_Error) - 85)
+ /*!< Device Firmware too new .. */
+#define VL53L1_ERROR_UNIT_TEST_FAIL ((VL53L1_Error) - 90)
+ /*!< Unit Test Fail */
+#define VL53L1_ERROR_FILE_READ_FAIL ((VL53L1_Error) - 95)
+ /*!< File Read Fail */
+#define VL53L1_ERROR_FILE_WRITE_FAIL ((VL53L1_Error) - 96)
+ /*!< File Write Fail */
+ /*!< Tells requested functionality has not been implemented yet or
+ * not compatible with the device */
+/** @} VL53L1_defineExtraError_group */
+
+
+/** @brief Defines the parameters of the LL driver Get Version Functions
+ */
+typedef struct {
+ uint32_t ll_revision; /*!< revision number */
+ uint8_t ll_major; /*!< major number */
+ uint8_t ll_minor; /*!< minor number */
+ uint8_t ll_build; /*!< build number */
+} VL53L1_ll_version_t;
+
+
+/** @brief Reference SPAD Characterization (RefSpadChar) Config
+ */
+
+typedef struct {
+
+ uint8_t device_test_mode; /*!< Device test mode */
+ uint8_t vcsel_period; /*!< VCSEL period (register) value */
+ uint32_t timeout_us; /*!< timeout in [us] */
+ uint16_t target_count_rate_mcps;
+ /*!< Target reference total count rate in [Mcps] - 9.7 format */
+ uint16_t min_count_rate_limit_mcps;
+ /*!< Min valid reference rate [Mcps] - 9.7 format */
+ uint16_t max_count_rate_limit_mcps;
+ /*!< Max valid reference rate [Mcps] - 9.7 format */
+
+} VL53L1_refspadchar_config_t;
+
+
+/** @brief SPAD Self Check (SSC) Config data structure
+ */
+
+
+typedef struct {
+
+ VL53L1_DeviceSscArray array_select;
+ /*!< SPAD Array select
+ * 0 - store RTN array count rates \n
+ * 1 - store REF array count rates */
+ uint8_t vcsel_period;
+ /*!< VCSEL period (register) value */
+ uint8_t vcsel_start;
+ /*!< VCSEL start register value */
+ uint8_t vcsel_width;
+ /*!< VCSEL ssc_timeout_us width register value e.g. 2 */
+ uint32_t timeout_us;
+ /*!< requested Ranging Timeout in [us] e.g 100000us */
+ uint16_t rate_limit_mcps;
+ /*!< Rate limit for checks either 1.15 or
+ * 9.7 dependent on test_mode
+ */
+
+} VL53L1_ssc_config_t;
+
+
+/** @brief Xtalk Extraction and Paramter Config
+ */
+
+typedef struct {
+
+
+ uint32_t algo__crosstalk_compensation_plane_offset_kcps;
+ /*!< Private crosstalk_compensation_plane_offset_kcps (fixed point 9.9) */
+ int16_t algo__crosstalk_compensation_x_plane_gradient_kcps;
+ /*!< Private crosstalk_compensation_x_plane_gradient_kcps (fixed point 5.11) */
+ int16_t algo__crosstalk_compensation_y_plane_gradient_kcps;
+ /*!< Private crosstalk_compensation_y_plane_gradient_kcps (fixed point 5.11) */
+ uint32_t nvm_default__crosstalk_compensation_plane_offset_kcps;
+ /*!< NVm stored crosstalk_compensation_plane_offset_kcps (fixed point 9.9) */
+ int16_t nvm_default__crosstalk_compensation_x_plane_gradient_kcps;
+ /*!< NVM stored crosstalk_compensation_x_plane_gradient_kcps (fixed point 5.11) */
+ int16_t nvm_default__crosstalk_compensation_y_plane_gradient_kcps;
+ /*!< NVM stored crosstalk_compensation_y_plane_gradient_kcps (fixed point 5.11) */
+ uint8_t global_crosstalk_compensation_enable;
+ /*!< Enable switch for crosstalk compensation in all modes */
+ int16_t lite_mode_crosstalk_margin_kcps;
+ /*!< Additional xtalk factor rate, added to plane_offset value in both
+ * SD mode, applied as a seperate addition at point of
+ * application to the device, plane_offset
+ * value remains unaltered. (fixed point 7.9)
+ */
+ uint8_t crosstalk_range_ignore_threshold_mult;
+ /*!< User set multiplier for range ignore threshold setting (fixed point 3.5) */
+ uint16_t crosstalk_range_ignore_threshold_rate_mcps;
+ /*!< Generated range ignore threshold rate in Mcps per spad (fixed
+ * point 3.13)
+ */
+
+} VL53L1_xtalk_config_t;
+
+
+/** @brief TuningParameter Storage
+ *
+ * - Storage structure for any LLD tuning parms
+ * which are dynamically altered by low level functions
+ * mostly when programming directly to the device
+ *
+ *- Added as part of Patch_AddingTuningParmStorage_11821
+ */
+
+typedef struct {
+
+
+ uint16_t tp_tuning_parm_version;
+ /*!< Programmed Global tuning version num for debug
+ */
+ uint16_t tp_tuning_parm_key_table_version;
+ /*!< Key Table tuning structure \
+ * version
+ */
+ uint16_t tp_tuning_parm_lld_version;
+ /*!< Programmed LLD version to ensure matching tuning structure \
+ * key table
+ */
+ uint8_t tp_init_phase_rtn_lite_long;
+ /*!< initial phase value for rtn array \
+ * in Lite Long Ranging Mode
+ */
+ uint8_t tp_init_phase_rtn_lite_med;
+ /*!< initial phase value for rtn array \
+ * in Lite Medium Ranging Mode
+ */
+ uint8_t tp_init_phase_rtn_lite_short;
+ /*!< initial phase value for rtn array \
+ * in Lite Short Ranging Mode
+ */
+ uint8_t tp_init_phase_ref_lite_long;
+ /*!< initial phase value for ref array \
+ * in Lite Long Ranging Mode
+ */
+ uint8_t tp_init_phase_ref_lite_med;
+ /*!< initial phase value for ref array \
+ * in Lite Medium Ranging Mode
+ */
+ uint8_t tp_init_phase_ref_lite_short;
+ /*!< initial phase value for ref array \
+ * in Lite short Ranging Mode
+ */
+
+ uint8_t tp_consistency_lite_phase_tolerance;
+ /*!< Phase tolerance consistency value to be used \
+ * in Lite modes
+ */
+ uint8_t tp_phasecal_target;
+ /*!< Phasecal target value
+ */
+ uint16_t tp_cal_repeat_rate;
+ /*!< Auto VHV/Calibration repeat rate for \
+ * use in Lite mode
+ */
+ uint8_t tp_lite_min_clip;
+ /*!< Min Clip value in mm applied to device in Lite \
+ * modes
+ */
+
+ uint16_t tp_lite_long_sigma_thresh_mm;
+ /*!< Sigma threshold limit for Lite Long mode \
+ * in 14.2 format mm
+ */
+ uint16_t tp_lite_med_sigma_thresh_mm;
+ /*!< Sigma threshold limit for Lite Medium mode \
+ * in 14.2 format mm
+ */
+ uint16_t tp_lite_short_sigma_thresh_mm;
+ /*!< Sigma threshold limit for Lite Short mode \
+ * in 14.2 format mm
+ */
+
+ uint16_t tp_lite_long_min_count_rate_rtn_mcps;
+ /*!< Min count rate level used in lite long mode \
+ * in 9.7 Mcps format
+ */
+ uint16_t tp_lite_med_min_count_rate_rtn_mcps;
+ /*!< Min count rate level used in lite medium mode \
+ * in 9.7 Mcps format
+ */
+ uint16_t tp_lite_short_min_count_rate_rtn_mcps;
+ /*!< Min count rate level used in lite short mode \
+ * in 9.7 Mcps format
+ */
+
+ uint8_t tp_lite_sigma_est_pulse_width_ns;
+ /*!< Sigma thresholding tunign parm for Lite mode
+ */
+ uint8_t tp_lite_sigma_est_amb_width_ns;
+ /*!< Sigma thresholding tunign parm for Lite mode
+ */
+ uint8_t tp_lite_sigma_ref_mm;
+ /*!< Sigma thresholding tunign parm for Lite mode
+ */
+ uint8_t tp_lite_seed_cfg;
+ /*!< Lite Mode Seed mode switch
+ */
+ uint8_t tp_timed_seed_cfg;
+ /*!< Timed Mode Seed mode switch
+ */
+
+ uint8_t tp_lite_quantifier;
+ /*!< Low level quantifier setting for lite modes
+ */
+ uint8_t tp_lite_first_order_select;
+ /*!< Low level First order select setting for lite modes
+ */
+
+ uint16_t tp_dss_target_lite_mcps;
+ /*!< DSS Target rate in 9.7 format Mcps for lite modes
+ */
+ uint16_t tp_dss_target_timed_mcps;
+ /*!< DSS Target rate in 9.7 format Mcps for Timed modes
+ */
+
+ uint32_t tp_phasecal_timeout_lite_us;
+ /*!< Phasecal timeout in us for lite modes
+ */
+
+ uint32_t tp_phasecal_timeout_timed_us;
+ /*!< Phasecal timeout in us for Timed modes
+ */
+
+ uint32_t tp_mm_timeout_lite_us;
+ /*!< MM stage timeout in us for Lite modes
+ */
+ uint32_t tp_mm_timeout_timed_us;
+ /*!< MM stage timeout in us for Timed modes
+ */
+ uint32_t tp_mm_timeout_lpa_us;
+ /*!< MM stage timeout in us for Low Power Auto modes
+ */
+
+ uint32_t tp_range_timeout_lite_us;
+ /*!< Ranging stage timeout in us for Lite modes
+ */
+ uint32_t tp_range_timeout_timed_us;
+ /*!< Ranging stage timeout in us for Timed modes
+ */
+ uint32_t tp_range_timeout_lpa_us;
+ /*!< Ranging stage timeout in us for Low Power Auto modes
+ */
+
+} VL53L1_tuning_parm_storage_t;
+
+
+
+/** @brief Optical Centre data
+ *
+ */
+
+typedef struct {
+
+ uint8_t x_centre; /*!< Optical x centre : 4.4 format */
+ uint8_t y_centre; /*!< Optical y centre : 4.4 format */
+
+} VL53L1_optical_centre_t;
+
+
+/** @brief Defines User Zone(ROI) parameters
+ *
+ */
+
+typedef struct {
+
+ uint8_t x_centre; /*!< Zone x centre : 0-15 range */
+ uint8_t y_centre; /*!< Zone y centre : 0-15 range */
+ uint8_t width; /*!< Width of Zone 0 = 1, 7 = 8, 15 = 16 */
+ uint8_t height; /*!< Height of Zone 0 = 1, 7 = 8, 15 = 16 */
+
+} VL53L1_user_zone_t;
+
+
+/**
+ * @struct VL53L1_GPIO_interrupt_config_t
+ *
+ * @brief Structure to configure conditions when GPIO interrupt is trigerred
+ *
+ */
+
+typedef struct {
+
+ /*! Distance interrupt mode */
+ VL53L1_GPIO_Interrupt_Mode intr_mode_distance;
+
+ /*! Rate interrupt mode */
+ VL53L1_GPIO_Interrupt_Mode intr_mode_rate;
+
+ /*! trigger interrupt if a new measurement is ready
+ * __WARNING!__ will override other settings
+ */
+ uint8_t intr_new_measure_ready;
+
+ /*! Trigger interrupt if no target found */
+ uint8_t intr_no_target;
+
+ /*! If set to 0, interrupts will only be triggered if BOTH rate AND
+ * distance thresholds are triggered (combined mode). If set to 1,
+ * interrupts will be triggered if EITHER rate OR distance thresholds
+ * are triggered (independent mode). */
+ uint8_t intr_combined_mode;
+
+ /* -- thresholds -- */
+ /* The struct holds a copy of the thresholds but they are written when
+ * this structure is set using VL53L1_set_GPIO_interrupt_config/_struct
+ * */
+
+ /*! Distance threshold high limit (mm) */
+ uint16_t threshold_distance_high;
+
+ /*! Distance threshold low limit (mm) */
+ uint16_t threshold_distance_low;
+
+ /*! Rate threshold high limit (9.7 Mcps) */
+ uint16_t threshold_rate_high;
+
+ /*! Rate threshold low limit (9.7 Mcps) */
+ uint16_t threshold_rate_low;
+
+} VL53L1_GPIO_interrupt_config_t;
+
+/* Start Patch_LowPowerAutoMode */
+/**
+ * @struct VL53L1_low_power_auto_data_t
+ *
+ * @brief Structure to hold state, tuning and output variables for the low
+ * power auto mode (Presence)
+ *
+ */
+
+typedef struct {
+
+ /*! Tuning variable for the VHV loop bound setting in low power auto
+ * mode. This is zero based, so the number of loops in VHV is this + 1.
+ * Please note, the first range will run with default VHV settings.
+ * Only lower 6 bits are allowed */
+ uint8_t vhv_loop_bound;
+
+ /*! Indicates if we are or are not in low power auto mode */
+ uint8_t is_low_power_auto_mode;
+
+ /*! Used to check if we're running the first range or not. Not to be
+ * used as a stream count */
+ uint8_t low_power_auto_range_count;
+
+ /*! saved interrupt config byte to restore */
+ uint8_t saved_interrupt_config;
+
+ /*! saved vhv config init byte to restore */
+ uint8_t saved_vhv_init;
+
+ /*! saved vhv config timeout byte to restore */
+ uint8_t saved_vhv_timeout;
+
+ /*! phase cal resutl from the first range */
+ uint8_t first_run_phasecal_result;
+
+ /*! DSS. Total rate per spad given from the current range */
+ uint32_t dss__total_rate_per_spad_mcps;
+
+ /*! DSS. Calculated required SPADs value */
+ uint16_t dss__required_spads;
+
+} VL53L1_low_power_auto_data_t;
+
+/* End Patch_LowPowerAutoMode */
+
+/**
+ * @struct VL53L1_range_data_t
+ * @brief Internal data structure for storing post processed ranges
+ *
+ */
+
+typedef struct {
+
+ /* Info size */
+
+ uint8_t range_id;
+ /*!< Range Result id e.g 0, 1, 2 */
+ uint32_t time_stamp;
+ /*!< 32-bit time stamp */
+
+ uint16_t width;
+ /*!< VCSEL pulse width in [PLL clocks] 6.4 format */
+ uint8_t woi;
+ /*!< WOI width in [PLL clocks] */
+
+ uint16_t fast_osc_frequency;
+ /*!< Oscillator frequency in 4.12 format */
+ uint16_t zero_distance_phase;
+ /*!< Zero Distance phase in 5.11 format */
+ uint16_t actual_effective_spads;
+ /*!< effective SPAD count in 8.8 format */
+
+ uint32_t total_periods_elapsed;
+ /*!< Elapsed time in macro periods for readout channel */
+
+ uint32_t peak_duration_us;
+ /*!< Peak VCSEL width time in us */
+
+ uint32_t woi_duration_us;
+ /*!< WOI duration time in us */
+
+
+ /* Event counts */
+
+ uint32_t ambient_window_events;
+ /*!< Return event count for the ambient window */
+ uint32_t ranging_total_events;
+ /*!< Return ranging event count for the ranging window.
+ This includes both VCSEL and ambient contributions */
+ int32_t signal_total_events;
+ /*!< Return event count for the ranging window with ambient
+ subtracted, Note it is 32-bit signed register */
+
+ /* Rates */
+
+ uint16_t peak_signal_count_rate_mcps;
+ /*! Peak signal (VCSEL) Rate in 9.7 format */
+ uint16_t avg_signal_count_rate_mcps;
+ /*! Average signal (VCSEL) Rate in 9.7 format */
+ uint16_t ambient_count_rate_mcps;
+ /*! Ambient Rate in 9.7 format */
+ uint16_t total_rate_per_spad_mcps;
+ /*! Total Rate Per SPAD in 3.13 format */
+ uint32_t peak_rate_per_spad_kcps;
+ /*! Peak Rate Per SPAD in 13.11 format */
+
+ /* Sigma */
+
+ uint16_t sigma_mm;
+ /*!< Range sigma Estimate [mm] 9.7 format */
+
+ /* Phase */
+
+ uint16_t median_phase;
+ /*!< Median Phase in 5.11 format */
+
+ /* Range */
+
+ int16_t median_range_mm;
+ /*!< Median Range in [mm] by default there are no fractional bits
+ Optionally 1 or 2 fractional can be enabled via the
+ VL53L1_SYSTEM__FRACTIONAL_ENABLE register */
+
+ /* Range status */
+
+ uint8_t range_status;
+
+} VL53L1_range_data_t;
+
+
+/**
+ * @struct VL53L1_range_results_t
+ * @brief Structure for storing the set of range results
+ *
+ */
+
+typedef struct {
+
+ VL53L1_DeviceState cfg_device_state;
+ /*!< Configuration Device State */
+ VL53L1_DeviceState rd_device_state;
+ /*!< Read Device State */
+ uint8_t stream_count;
+ /*!< 8-bit stream count */
+
+ uint8_t device_status;
+ /*!< Global device status for result set */
+
+ VL53L1_range_data_t data[2];
+ /*!< Range data each target distance */
+
+} VL53L1_range_results_t;
+
+/**
+ * @struct VL53L1_offset_range_data_t
+ * @brief Structure for storing the set of range results
+ * required for the mm1 and mm2 offset calibration
+ * functions
+ *
+ */
+
+typedef struct {
+
+ uint8_t preset_mode;
+ /*!< Preset Mode use for range */
+ uint8_t dss_config__roi_mode_control;
+ /*!< Dynamic SPAD selection mode */
+ uint16_t dss_config__manual_effective_spads_select;
+ /*!< Requested number of manual effective SPAD's */
+ uint8_t no_of_samples;
+ /*!< Number of ranges */
+ uint32_t effective_spads;
+ /*!< Average effective SPAD's 8.8 format */
+ uint32_t peak_rate_mcps;
+ /*!< Average peak rate Mcps 9.7 format */
+ uint32_t sigma_mm;
+ /*!< Average sigma in [mm] 14.2 format */
+ int32_t median_range_mm;
+ /*!< Avg of median range over all ranges \
+ note value is signed */
+ int32_t range_mm_offset;
+ /*!< The calculated range offset value */
+
+} VL53L1_offset_range_data_t;
+
+
+/**
+ * @struct VL53L1_offset_range_results_t
+ * @brief Structure for storing the set of range results
+ * required for the offset calibration functions
+ *
+ */
+
+typedef struct {
+
+ int16_t cal_distance_mm;
+ /*!< the calibration distance in [mm]*/
+ VL53L1_Error cal_status;
+ /*!< Calibration status, check for warning codes */
+ uint8_t cal_report;
+ /*!< Stage for above cal status - 0 Pre, 1 = MM1, 2 = MM2 */
+ uint8_t max_results;
+ /*!< Array size for histogram range data i.e. max number
+ of results */
+ uint8_t active_results;
+ /*!< Number of active measurements */
+ VL53L1_offset_range_data_t data[VL53L1_MAX_OFFSET_RANGE_RESULTS];
+ /*!< Range results for each offset measurement */
+
+} VL53L1_offset_range_results_t;
+
+/**
+ * @struct VL53L1_additional_offset_cal_data_t
+ * @brief Additional Offset Calibration Data
+ *
+ * Additional offset calibration data. Contains the rate
+ * and effective SPAD counts for the MM inner and outer
+ * calibration steps.
+ */
+
+typedef struct {
+
+ uint16_t result__mm_inner_actual_effective_spads;
+ /*!< MM Inner actual effective SPADs, 8.8 format */
+ uint16_t result__mm_outer_actual_effective_spads;
+ /*!< MM Outer actual effective SPADs, 8.8 format */
+ uint16_t result__mm_inner_peak_signal_count_rtn_mcps;
+ /*!< Mean value of MM Inner return peak rate in [Mcps], 9.7 format */
+ uint16_t result__mm_outer_peak_signal_count_rtn_mcps;
+ /*!< Mean value of MM Outer return peak rate in [Mcps], 9.7 format */
+
+} VL53L1_additional_offset_cal_data_t;
+
+
+/**
+ * @struct VL53L1_cal_peak_rate_map_t
+ * @brief Structure for storing the calibration peak rate map
+ * Used by DMAX to understand the spatial roll off
+ * in the signal rate map towards the corner of the
+ * SPAD array.
+ */
+
+typedef struct {
+
+ int16_t cal_distance_mm;
+ /*!< calibration distance in [mm], 14.2 format */
+ uint16_t max_samples;
+ /*!< Array size for rate map i.e. max number samples */
+ uint16_t width;
+ /*!< Array width */
+ uint16_t height;
+ /*!< Array height */
+ uint16_t peak_rate_mcps[VL53L1_NVM_PEAK_RATE_MAP_SAMPLES];
+ /*!< Array of rate map samples */
+
+} VL53L1_cal_peak_rate_map_t;
+
+
+/**
+ * @struct VL53L1_gain_calibration_data_t
+ *
+ * @brief Gain calibration data
+ *
+ */
+
+typedef struct {
+
+ uint16_t standard_ranging_gain_factor;
+ /*!< Standard ranging gain correction factor 1.11 format */
+
+} VL53L1_gain_calibration_data_t;
+
+
+/**
+ * @struct VL53L1_ll_driver_state_t
+ *
+ * @brief Contains the driver state information
+ *
+ */
+
+typedef struct {
+
+ VL53L1_DeviceState cfg_device_state;
+ /*!< Configuration Device State */
+ uint8_t cfg_stream_count;
+ /*!< configuration stream count, becomes expected
+ stream count for zone */
+ uint8_t cfg_gph_id;
+ /*!< Config Grouped Parameter Hold ID */
+ uint8_t cfg_timing_status;
+ /*!< Timing A or B flag 0 = A, 1 = B */
+
+ VL53L1_DeviceState rd_device_state;
+ /*!< Read Device State */
+ uint8_t rd_stream_count;
+ /*!< rd stream count, used to check actual stream count */
+ uint8_t rd_gph_id;
+ /*!< Read Grouped Parameter Hold ID */
+ uint8_t rd_timing_status;
+ /*!< Timing A or B flag 0 = A, 1 = B */
+
+} VL53L1_ll_driver_state_t;
+
+/** @brief Run Offset Cal Function (offsetcal) Config
+ */
+
+typedef struct {
+
+ uint16_t dss_config__target_total_rate_mcps;
+ /*!< DSS Target rate in MCPS (9.7 format) used \
+ * during run_offset_calibration() */
+ uint32_t phasecal_config_timeout_us;
+ /*!< Phasecal timeout in us \
+ * used during run_offset_calibration() */
+ uint32_t range_config_timeout_us;
+ /*!< Range timeout in us used during \
+ * run_offset_calibration() */
+ uint32_t mm_config_timeout_us;
+ /*!< MM timeout in us used during \
+ * run_offset_calibration() \
+ * Added as part of Patch_AddedOffsetCalMMTuningParm_11791 */
+ uint8_t pre_num_of_samples;
+ /*!< Number of Ranging samples used during \
+ * run_offset_calibration() */
+ uint8_t mm1_num_of_samples;
+ /*!< Number of MM1 samples used during \
+ * run_offset_calibration() */
+ uint8_t mm2_num_of_samples;
+ /*!< Number of MM2 samples used during \
+ * run_offset_calibration() */
+
+} VL53L1_offsetcal_config_t;
+
+
+
+/**
+ * @struct VL53L1_LLDriverData_t
+ *
+ * @brief VL53L1 LL Driver ST private data structure \n
+ *
+ */
+
+typedef struct {
+
+ uint8_t wait_method;
+ /*!< Wait type : blocking or non blocking */
+ VL53L1_DevicePresetModes preset_mode;
+ /*!< Current preset mode */
+ VL53L1_DeviceMeasurementModes measurement_mode;
+ /*!< Current measurement mode */
+ VL53L1_OffsetCalibrationMode offset_calibration_mode;
+ /*!< Current offset calibration mode */
+ VL53L1_OffsetCorrectionMode offset_correction_mode;
+ /*!< Current offset_ correction mode */
+ uint32_t phasecal_config_timeout_us;
+ /*!< requested Phase Cal Timeout e.g. 1000us */
+ uint32_t mm_config_timeout_us;
+ /*!< requested MM Timeout e.g. 2000us */
+ uint32_t range_config_timeout_us;
+ /*!< requested Ranging Timeout e.g 13000us */
+ uint32_t inter_measurement_period_ms;
+ /*!< requested Timing mode repeat period e.g 100ms */
+ uint16_t dss_config__target_total_rate_mcps;
+ /*!< requested DSS Target Total Rate in 9.7 format e.g. 40.0Mcps
+ * - Patch_ChangingPresetModeInputParms_11780 */
+ uint32_t fw_ready_poll_duration_ms;
+ /*!< FW ready poll duration in ms*/
+ uint8_t fw_ready;
+ /*!< Result of FW ready check */
+ uint8_t debug_mode;
+ /*!< Internal Only - read extra debug data */
+
+ /*!< version info structure */
+ VL53L1_ll_version_t version;
+
+ /*!< version info structure */
+ VL53L1_ll_driver_state_t ll_state;
+
+ /*!< decoded GPIO interrupt config */
+ VL53L1_GPIO_interrupt_config_t gpio_interrupt_config;
+
+ /*!< public register data structures */
+ VL53L1_customer_nvm_managed_t customer;
+ VL53L1_cal_peak_rate_map_t cal_peak_rate_map;
+ VL53L1_additional_offset_cal_data_t add_off_cal_data;
+ VL53L1_gain_calibration_data_t gain_cal;
+ VL53L1_user_zone_t mm_roi;
+ VL53L1_optical_centre_t optical_centre;
+
+ /*!< tuning parameter storage */
+ VL53L1_tuning_parm_storage_t tuning_parms;
+
+ /*!< private return good SPAD map */
+ uint8_t rtn_good_spads[VL53L1_RTN_SPAD_BUFFER_SIZE];
+
+ /*!< private internal configuration structures */
+ VL53L1_refspadchar_config_t refspadchar;
+ VL53L1_ssc_config_t ssc_cfg;
+ VL53L1_xtalk_config_t xtalk_cfg;
+ VL53L1_offsetcal_config_t offsetcal_cfg;
+
+ /*!< private internal register data structures */
+ VL53L1_static_nvm_managed_t stat_nvm;
+ VL53L1_static_config_t stat_cfg;
+ VL53L1_general_config_t gen_cfg;
+ VL53L1_timing_config_t tim_cfg;
+ VL53L1_dynamic_config_t dyn_cfg;
+ VL53L1_system_control_t sys_ctrl;
+ VL53L1_system_results_t sys_results;
+ VL53L1_nvm_copy_data_t nvm_copy_data;
+
+ /*!< Private Offset structure */
+ VL53L1_offset_range_results_t offset_results;
+
+ /*!< private debug register data structures */
+ VL53L1_core_results_t core_results;
+ VL53L1_debug_results_t dbg_results;
+
+ /* Start Patch_LowPowerAutoMode */
+ /*!< Low Powr Auto Mode Data */
+ VL53L1_low_power_auto_data_t low_power_auto_data;
+ /* End Patch_LowPowerAutoMode */
+
+#ifdef PAL_EXTENDED
+ /* Patch Debug Data */
+ VL53L1_patch_results_t patch_results;
+ VL53L1_shadow_core_results_t shadow_core_results;
+ VL53L1_shadow_system_results_t shadow_sys_results;
+ VL53L1_prev_shadow_core_results_t prev_shadow_core_results;
+ VL53L1_prev_shadow_system_results_t prev_shadow_sys_results;
+#endif
+
+} VL53L1_LLDriverData_t;
+
+
+/**
+ * @struct VL53L1_LLDriverResults_t
+ *
+ * @brief VL53L1 LL Driver ST private results structure
+ *
+ */
+
+typedef struct {
+
+ /* Private last range results */
+ VL53L1_range_results_t range_results;
+
+} VL53L1_LLDriverResults_t;
+
+/**
+ * @struct VL53L1_calibration_data_t
+ *
+ * @brief Per Part calibration data
+ *
+ */
+
+typedef struct {
+
+ uint32_t struct_version;
+ VL53L1_customer_nvm_managed_t customer;
+ VL53L1_additional_offset_cal_data_t add_off_cal_data;
+ VL53L1_optical_centre_t optical_centre;
+ VL53L1_gain_calibration_data_t gain_cal;
+ VL53L1_cal_peak_rate_map_t cal_peak_rate_map;
+
+} VL53L1_calibration_data_t;
+
+
+/**
+ * @struct VL53L1_tuning_parameters_t
+ *
+ * @brief Tuning Parameters Debug data
+ *
+ */
+
+typedef struct {
+ uint16_t vl53l1_tuningparm_version;
+ uint16_t vl53l1_tuningparm_key_table_version;
+ uint16_t vl53l1_tuningparm_lld_version;
+ uint8_t vl53l1_tuningparm_consistency_lite_phase_tolerance;
+ uint8_t vl53l1_tuningparm_phasecal_target;
+ uint16_t vl53l1_tuningparm_lite_cal_repeat_rate;
+ uint16_t vl53l1_tuningparm_lite_ranging_gain_factor;
+ uint8_t vl53l1_tuningparm_lite_min_clip_mm;
+ uint16_t vl53l1_tuningparm_lite_long_sigma_thresh_mm;
+ uint16_t vl53l1_tuningparm_lite_med_sigma_thresh_mm;
+ uint16_t vl53l1_tuningparm_lite_short_sigma_thresh_mm;
+ uint16_t vl53l1_tuningparm_lite_long_min_count_rate_rtn_mcps;
+ uint16_t vl53l1_tuningparm_lite_med_min_count_rate_rtn_mcps;
+ uint16_t vl53l1_tuningparm_lite_short_min_count_rate_rtn_mcps;
+ uint8_t vl53l1_tuningparm_lite_sigma_est_pulse_width;
+ uint8_t vl53l1_tuningparm_lite_sigma_est_amb_width_ns;
+ uint8_t vl53l1_tuningparm_lite_sigma_ref_mm;
+ uint8_t vl53l1_tuningparm_lite_rit_mult;
+ uint8_t vl53l1_tuningparm_lite_seed_config;
+ uint8_t vl53l1_tuningparm_lite_quantifier;
+ uint8_t vl53l1_tuningparm_lite_first_order_select;
+ int16_t vl53l1_tuningparm_lite_xtalk_margin_kcps;
+ uint8_t vl53l1_tuningparm_initial_phase_rtn_lite_long_range;
+ uint8_t vl53l1_tuningparm_initial_phase_rtn_lite_med_range;
+ uint8_t vl53l1_tuningparm_initial_phase_rtn_lite_short_range;
+ uint8_t vl53l1_tuningparm_initial_phase_ref_lite_long_range;
+ uint8_t vl53l1_tuningparm_initial_phase_ref_lite_med_range;
+ uint8_t vl53l1_tuningparm_initial_phase_ref_lite_short_range;
+ uint8_t vl53l1_tuningparm_timed_seed_config;
+ uint8_t vl53l1_tuningparm_vhv_loopbound;
+ uint8_t vl53l1_tuningparm_refspadchar_device_test_mode;
+ uint8_t vl53l1_tuningparm_refspadchar_vcsel_period;
+ uint32_t vl53l1_tuningparm_refspadchar_phasecal_timeout_us;
+ uint16_t vl53l1_tuningparm_refspadchar_target_count_rate_mcps;
+ uint16_t vl53l1_tuningparm_refspadchar_min_countrate_limit_mcps;
+ uint16_t vl53l1_tuningparm_refspadchar_max_countrate_limit_mcps;
+ uint16_t vl53l1_tuningparm_offset_cal_dss_rate_mcps;
+ uint32_t vl53l1_tuningparm_offset_cal_phasecal_timeout_us;
+ uint32_t vl53l1_tuningparm_offset_cal_mm_timeout_us;
+ uint32_t vl53l1_tuningparm_offset_cal_range_timeout_us;
+ uint8_t vl53l1_tuningparm_offset_cal_pre_samples;
+ uint8_t vl53l1_tuningparm_offset_cal_mm1_samples;
+ uint8_t vl53l1_tuningparm_offset_cal_mm2_samples;
+ uint8_t vl53l1_tuningparm_spadmap_vcsel_period;
+ uint8_t vl53l1_tuningparm_spadmap_vcsel_start;
+ uint16_t vl53l1_tuningparm_spadmap_rate_limit_mcps;
+ uint16_t vl53l1_tuningparm_lite_dss_config_target_total_rate_mcps;
+ uint16_t vl53l1_tuningparm_timed_dss_config_target_total_rate_mcps;
+ uint32_t vl53l1_tuningparm_lite_phasecal_config_timeout_us;
+ uint32_t vl53l1_tuningparm_timed_phasecal_config_timeout_us;
+ uint32_t vl53l1_tuningparm_lite_mm_config_timeout_us;
+ uint32_t vl53l1_tuningparm_timed_mm_config_timeout_us;
+ uint32_t vl53l1_tuningparm_lite_range_config_timeout_us;
+ uint32_t vl53l1_tuningparm_timed_range_config_timeout_us;
+ uint8_t vl53l1_tuningparm_lowpowerauto_vhv_loop_bound;
+ uint32_t vl53l1_tuningparm_lowpowerauto_mm_config_timeout_us;
+ uint32_t vl53l1_tuningparm_lowpowerauto_range_config_timeout_us;
+} VL53L1_tuning_parameters_t;
+
+
+/**
+ * @struct VL53L1_spad_rate_data_t
+ * @brief SPAD Rate Data output by SSC
+ *
+ * Container for the SPAD Rate data output by SPAD select check (SSC)
+ * The data is stored in the buffer in SPAD number order and not
+ * raster order
+ *
+ * Rate data is it either 1.15 or 9.7 fixed point format
+ */
+
+typedef struct {
+
+ uint8_t spad_type;
+ /*!< Type of rate data stored */
+ uint16_t buffer_size;
+ /*!< SPAD buffer size : should be at least 256 for EwokPlus25 */
+ uint16_t rate_data[VL53L1_NO_OF_SPAD_ENABLES];
+ /*!< word buffer containing the SPAD rates */
+ uint16_t no_of_values;
+ /*!< Number of bytes used in the buffer */
+ uint8_t fractional_bits;
+ /*!< Number of fractional bits either 7 or 15 */
+ uint8_t error_status;
+ /*!< Set if supplied buffer is too small */
+
+} VL53L1_spad_rate_data_t;
+
+
+/* Start Patch_AdditionalDebugData_11823 */
+
+/**
+ * @struct VL53L1_additional_data_t
+ * @brief Additional debug data
+ *
+ * Contains the LL Driver configuration information
+ */
+
+typedef struct {
+
+ VL53L1_DevicePresetModes preset_mode;
+ /*!< Current preset mode */
+ VL53L1_DeviceMeasurementModes measurement_mode;
+ /*!< Current measurement mode */
+
+ uint32_t phasecal_config_timeout_us;
+ /*!< requested Phase Cal Timeout e.g. 1000us */
+ uint32_t mm_config_timeout_us;
+ /*!< requested MM Timeout e.g. 2000us */
+ uint32_t range_config_timeout_us;
+ /*!< requested Ranging Timeout e.g 13000us */
+ uint32_t inter_measurement_period_ms;
+ /*!< requested Timing mode repeat period e.g 100ms */
+ uint16_t dss_config__target_total_rate_mcps;
+ /*!< requested DSS Target Total Rate in 9.7 format e.g. 40.0Mcps*/
+
+} VL53L1_additional_data_t;
+
+/* End Patch_AdditionalDebugData_11823 */
+
+
+/** @} VL53L1_globalLLDriverDefine_group */
+
+
+#define SUPPRESS_UNUSED_WARNING(x) \
+ ((void) (x))
+
+
+#define IGNORE_STATUS(__FUNCTION_ID__, __ERROR_STATUS_CHECK__, __STATUS__) \
+ do { \
+ DISABLE_WARNINGS(); \
+ if (__FUNCTION_ID__) { \
+ if (__STATUS__ == __ERROR_STATUS_CHECK__) { \
+ __STATUS__ = VL53L1_ERROR_NONE; \
+ WARN_OVERRIDE_STATUS(__FUNCTION_ID__); \
+ } \
+ } \
+ ENABLE_WARNINGS(); \
+ } \
+ while (0)
+
+#define VL53L1_COPYSTRING(str, ...) \
+ (strncpy(str, ##__VA_ARGS__, VL53L1_MAX_STRING_LENGTH-1))
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _VL53L1_LL_DEF_H_ */
+
+
diff --git a/src/lib/vl53l1/core/inc/vl53l1_ll_device.h b/src/lib/vl53l1/core/inc/vl53l1_ll_device.h
new file mode 100644
index 0000000000..331ede5a00
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_ll_device.h
@@ -0,0 +1,664 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*******************************************************************************/
+
+/**
+ * @file vl53l1_ll_device.h
+ *
+ * @brief LL Driver Device specific defines. To be adapted by implementer for the
+ * targeted device.
+ */
+
+#ifndef _VL53L1_LL_DEVICE_H_
+#define _VL53L1_LL_DEVICE_H_
+
+#include "vl53l1_types.h"
+#include "vl53l1_platform_user_config.h"
+
+#define VL53L1_I2C 0x01
+#define VL53L1_SPI 0x00
+
+
+/** @defgroup VL53L1_DevSpecDefines_group VL53L1 Device Specific Defines
+ * @brief VL53L1 cut1.0 Device Specific Defines
+ * @{
+ */
+
+/** @defgroup VL53L1_define_WaitMethod_group Defines Wait method used
+ * For example blocking versus non blocking
+ * @{
+ */
+typedef uint8_t VL53L1_WaitMethod;
+
+#define VL53L1_WAIT_METHOD_BLOCKING ((VL53L1_WaitMethod) 0)
+#define VL53L1_WAIT_METHOD_NON_BLOCKING ((VL53L1_WaitMethod) 1)
+
+/** @} end of VL53L1_define_WaitMethod_group */
+
+/** @defgroup VL53L1_define_DeviceState_group Device State
+ *
+ * @brief Defines all possible device states for the device
+ * @{
+ */
+typedef uint8_t VL53L1_DeviceState;
+
+#define VL53L1_DEVICESTATE_POWERDOWN ((VL53L1_DeviceState) 0)
+#define VL53L1_DEVICESTATE_HW_STANDBY ((VL53L1_DeviceState) 1)
+#define VL53L1_DEVICESTATE_FW_COLDBOOT ((VL53L1_DeviceState) 2)
+#define VL53L1_DEVICESTATE_SW_STANDBY ((VL53L1_DeviceState) 3)
+#define VL53L1_DEVICESTATE_RANGING_DSS_AUTO ((VL53L1_DeviceState) 4)
+#define VL53L1_DEVICESTATE_RANGING_DSS_MANUAL ((VL53L1_DeviceState) 5)
+#define VL53L1_DEVICESTATE_RANGING_WAIT_GPH_SYNC ((VL53L1_DeviceState) 6)
+#define VL53L1_DEVICESTATE_RANGING_GATHER_DATA ((VL53L1_DeviceState) 7)
+#define VL53L1_DEVICESTATE_RANGING_OUTPUT_DATA ((VL53L1_DeviceState) 8)
+
+#define VL53L1_DEVICESTATE_UNKNOWN ((VL53L1_DeviceState) 98)
+#define VL53L1_DEVICESTATE_ERROR ((VL53L1_DeviceState) 99)
+
+/** @} end of VL53L1_define_DeviceState_group */
+
+
+/** @defgroup VL53L1_define_DevicePresetModes_group Device Preset Modes
+ *
+ * @brief Defines all possible device preset modes. The integer values are
+ * kept the same as main EwokPlus driver branch
+ * @{
+ */
+typedef uint8_t VL53L1_DevicePresetModes;
+
+#define VL53L1_DEVICEPRESETMODE_NONE ((VL53L1_DevicePresetModes) 0)
+#define VL53L1_DEVICEPRESETMODE_STANDARD_RANGING ((VL53L1_DevicePresetModes) 1)
+#define VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_SHORT_RANGE ((VL53L1_DevicePresetModes) 2)
+#define VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_LONG_RANGE ((VL53L1_DevicePresetModes) 3)
+#define VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM1_CAL ((VL53L1_DevicePresetModes) 4)
+#define VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM2_CAL ((VL53L1_DevicePresetModes) 5)
+#define VL53L1_DEVICEPRESETMODE_TIMED_RANGING ((VL53L1_DevicePresetModes) 6)
+#define VL53L1_DEVICEPRESETMODE_TIMED_RANGING_SHORT_RANGE ((VL53L1_DevicePresetModes) 7)
+#define VL53L1_DEVICEPRESETMODE_TIMED_RANGING_LONG_RANGE ((VL53L1_DevicePresetModes) 8)
+#define VL53L1_DEVICEPRESETMODE_OLT ((VL53L1_DevicePresetModes) 17)
+#define VL53L1_DEVICEPRESETMODE_SINGLESHOT_RANGING ((VL53L1_DevicePresetModes) 18)
+#define VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_SHORT_RANGE ((VL53L1_DevicePresetModes) 36)
+#define VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_MEDIUM_RANGE ((VL53L1_DevicePresetModes) 37)
+#define VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_LONG_RANGE ((VL53L1_DevicePresetModes) 38)
+
+/** @} end of VL53L1_define_DevicePresetModes_group */
+
+
+/** @defgroup VL53L1_define_DeviceMeasurementModes_group Device Measurement Modes
+ *
+ * @brief Defines all possible measurement modes for the device
+ * @{
+ */
+typedef uint8_t VL53L1_DeviceMeasurementModes;
+
+#define VL53L1_DEVICEMEASUREMENTMODE_STOP ((VL53L1_DeviceMeasurementModes) 0x00)
+#define VL53L1_DEVICEMEASUREMENTMODE_SINGLESHOT ((VL53L1_DeviceMeasurementModes) 0x10)
+#define VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK ((VL53L1_DeviceMeasurementModes) 0x20)
+#define VL53L1_DEVICEMEASUREMENTMODE_TIMED ((VL53L1_DeviceMeasurementModes) 0x40)
+#define VL53L1_DEVICEMEASUREMENTMODE_ABORT ((VL53L1_DeviceMeasurementModes) 0x80)
+
+/** @} VL53L1_define_DeviceMeasurementModes_group */
+
+/** @defgroup VL53L1_define_OffsetCalibrationModes_group Device Offset Calibration Mode
+ *
+ * @brief Defines possible offset calibration modes for the device
+ * @{
+ */
+typedef uint8_t VL53L1_OffsetCalibrationMode;
+
+#define VL53L1_OFFSETCALIBRATIONMODE__NONE ((VL53L1_OffsetCalibrationMode) 0)
+#define VL53L1_OFFSETCALIBRATIONMODE__MM1_MM2__STANDARD ((VL53L1_OffsetCalibrationMode) 1)
+#define VL53L1_OFFSETCALIBRATIONMODE__MM1_MM2__HISTOGRAM ((VL53L1_OffsetCalibrationMode) 2)
+#define VL53L1_OFFSETCALIBRATIONMODE__MM1_MM2__STANDARD_PRE_RANGE_ONLY ((VL53L1_OffsetCalibrationMode) 3)
+#define VL53L1_OFFSETCALIBRATIONMODE__MM1_MM2__HISTOGRAM_PRE_RANGE_ONLY ((VL53L1_OffsetCalibrationMode) 4)
+#define VL53L1_OFFSETCALIBRATIONMODE__PER_ZONE ((VL53L1_OffsetCalibrationMode) 5)
+
+/** @} VL53L1_define_OffsetCalibrationModes_group */
+
+
+/** @defgroup VL53L1_define_OffsetCalibrationModes_group Device Offset Correction Mode
+ *
+ * @brief Defines all possible offset correction modes for the device
+ * @{
+ */
+typedef uint8_t VL53L1_OffsetCorrectionMode;
+
+#define VL53L1_OFFSETCORRECTIONMODE__NONE ((VL53L1_OffsetCorrectionMode) 0)
+#define VL53L1_OFFSETCORRECTIONMODE__MM1_MM2_OFFSETS ((VL53L1_OffsetCorrectionMode) 1)
+#define VL53L1_OFFSETCORRECTIONMODE__PER_ZONE_OFFSETS ((VL53L1_OffsetCorrectionMode) 2)
+
+/** @} VL53L1_define_OffsetCalibrationModes_group */
+
+
+
+/** @defgroup VL53L1_DeviceSequenceConfig_group Device Sequence Config
+ *
+ * @brief Individual bit enables for each stage in the ranging scheduler
+ * The values below encode the bit shift for each bit
+ * @{
+ */
+typedef uint8_t VL53L1_DeviceSequenceConfig;
+
+#define VL53L1_DEVICESEQUENCECONFIG_VHV ((VL53L1_DeviceSequenceConfig) 0)
+#define VL53L1_DEVICESEQUENCECONFIG_PHASECAL ((VL53L1_DeviceSequenceConfig) 1)
+#define VL53L1_DEVICESEQUENCECONFIG_REFERENCE_PHASE ((VL53L1_DeviceSequenceConfig) 2)
+#define VL53L1_DEVICESEQUENCECONFIG_DSS1 ((VL53L1_DeviceSequenceConfig) 3)
+#define VL53L1_DEVICESEQUENCECONFIG_DSS2 ((VL53L1_DeviceSequenceConfig) 4)
+#define VL53L1_DEVICESEQUENCECONFIG_MM1 ((VL53L1_DeviceSequenceConfig) 5)
+#define VL53L1_DEVICESEQUENCECONFIG_MM2 ((VL53L1_DeviceSequenceConfig) 6)
+#define VL53L1_DEVICESEQUENCECONFIG_RANGE ((VL53L1_DeviceSequenceConfig) 7)
+
+/** @} VL53L1_DeviceSequenceConfig_group */
+
+
+/** @defgroup VL53L1_DeviceInterruptPolarity_group Device Interrupt Polarity
+ *
+ * @brief Device Interrupt Polarity
+ * @{
+ */
+typedef uint8_t VL53L1_DeviceInterruptPolarity;
+
+#define VL53L1_DEVICEINTERRUPTPOLARITY_ACTIVE_HIGH ((VL53L1_DeviceInterruptPolarity) 0x00)
+#define VL53L1_DEVICEINTERRUPTPOLARITY_ACTIVE_LOW ((VL53L1_DeviceInterruptPolarity) 0x10)
+#define VL53L1_DEVICEINTERRUPTPOLARITY_BIT_MASK ((VL53L1_DeviceInterruptPolarity) 0x10)
+#define VL53L1_DEVICEINTERRUPTPOLARITY_CLEAR_MASK ((VL53L1_DeviceInterruptPolarity) 0xEF)
+
+/** @} VL53L1_DeviceInterruptPolarity_group */
+
+
+/** @defgroup VL53L1_DeviceGpioMode_group Device GPIO Mode
+ *
+ * @brief Device Gpio Mode
+ * @{
+ */
+typedef uint8_t VL53L1_DeviceGpioMode;
+
+#define VL53L1_DEVICEGPIOMODE_OUTPUT_CONSTANT_ZERO ((VL53L1_DeviceGpioMode) 0x00)
+#define VL53L1_DEVICEGPIOMODE_OUTPUT_RANGE_AND_ERROR_INTERRUPTS ((VL53L1_DeviceGpioMode) 0x01)
+#define VL53L1_DEVICEGPIOMODE_OUTPUT_TIMIER_INTERRUPTS ((VL53L1_DeviceGpioMode) 0x02)
+#define VL53L1_DEVICEGPIOMODE_OUTPUT_RANGE_MODE_INTERRUPT_STATUS ((VL53L1_DeviceGpioMode) 0x03)
+#define VL53L1_DEVICEGPIOMODE_OUTPUT_SLOW_OSCILLATOR_CLOCK ((VL53L1_DeviceGpioMode) 0x04)
+#define VL53L1_DEVICEGPIOMODE_BIT_MASK ((VL53L1_DeviceGpioMode) 0x0F)
+#define VL53L1_DEVICEGPIOMODE_CLEAR_MASK ((VL53L1_DeviceGpioMode) 0xF0)
+
+/** @} VL53L1_DeviceGpioMode_group */
+
+
+/** @defgroup VL53L1_DeviceError_group Device Error
+ *
+ * @brief Device Error code in the range status
+ *
+ * This enum is Device specific it should be updated in the implementation
+ * Use @a VL53L1_GetStatusErrorString() to get the string.
+ * It is related to Status Register of the Device.
+ * @{
+ */
+typedef uint8_t VL53L1_DeviceError;
+
+#define VL53L1_DEVICEERROR_NOUPDATE ((VL53L1_DeviceError) 0)
+ /*!< 0 No Update */
+#define VL53L1_DEVICEERROR_VCSELCONTINUITYTESTFAILURE ((VL53L1_DeviceError) 1)
+#define VL53L1_DEVICEERROR_VCSELWATCHDOGTESTFAILURE ((VL53L1_DeviceError) 2)
+#define VL53L1_DEVICEERROR_NOVHVVALUEFOUND ((VL53L1_DeviceError) 3)
+#define VL53L1_DEVICEERROR_MSRCNOTARGET ((VL53L1_DeviceError) 4)
+#define VL53L1_DEVICEERROR_RANGEPHASECHECK ((VL53L1_DeviceError) 5)
+#define VL53L1_DEVICEERROR_SIGMATHRESHOLDCHECK ((VL53L1_DeviceError) 6)
+#define VL53L1_DEVICEERROR_PHASECONSISTENCY ((VL53L1_DeviceError) 7)
+#define VL53L1_DEVICEERROR_MINCLIP ((VL53L1_DeviceError) 8)
+#define VL53L1_DEVICEERROR_RANGECOMPLETE ((VL53L1_DeviceError) 9)
+#define VL53L1_DEVICEERROR_ALGOUNDERFLOW ((VL53L1_DeviceError) 10)
+#define VL53L1_DEVICEERROR_ALGOOVERFLOW ((VL53L1_DeviceError) 11)
+#define VL53L1_DEVICEERROR_RANGEIGNORETHRESHOLD ((VL53L1_DeviceError) 12)
+#define VL53L1_DEVICEERROR_USERROICLIP ((VL53L1_DeviceError) 13)
+#define VL53L1_DEVICEERROR_REFSPADCHARNOTENOUGHDPADS ((VL53L1_DeviceError) 14)
+#define VL53L1_DEVICEERROR_REFSPADCHARMORETHANTARGET ((VL53L1_DeviceError) 15)
+#define VL53L1_DEVICEERROR_REFSPADCHARLESSTHANTARGET ((VL53L1_DeviceError) 16)
+#define VL53L1_DEVICEERROR_MULTCLIPFAIL ((VL53L1_DeviceError) 17)
+#define VL53L1_DEVICEERROR_GPHSTREAMCOUNT0READY ((VL53L1_DeviceError) 18)
+#define VL53L1_DEVICEERROR_RANGECOMPLETE_NO_WRAP_CHECK ((VL53L1_DeviceError) 19)
+#define VL53L1_DEVICEERROR_EVENTCONSISTENCY ((VL53L1_DeviceError) 20)
+#define VL53L1_DEVICEERROR_MINSIGNALEVENTCHECK ((VL53L1_DeviceError) 21)
+#define VL53L1_DEVICEERROR_RANGECOMPLETE_MERGED_PULSE ((VL53L1_DeviceError) 22)
+
+/* Patch_NewDeviceErrorCodePrevRangeNoTargets_11786 */
+#define VL53L1_DEVICEERROR_PREV_RANGE_NO_TARGETS ((VL53L1_DeviceError) 23)
+
+/** @} end of VL53L1_DeviceError_group */
+
+
+/** @defgroup VL53L1_DeviceReportStatus_group Device Report Status
+ * @brief Device Report Status code
+ *
+ * @{
+ */
+typedef uint8_t VL53L1_DeviceReportStatus;
+
+#define VL53L1_DEVICEREPORTSTATUS_NOUPDATE ((VL53L1_DeviceReportStatus) 0)
+ /*!< 0 No Update */
+#define VL53L1_DEVICEREPORTSTATUS_ROI_SETUP ((VL53L1_DeviceReportStatus) 1)
+#define VL53L1_DEVICEREPORTSTATUS_VHV ((VL53L1_DeviceReportStatus) 2)
+#define VL53L1_DEVICEREPORTSTATUS_PHASECAL ((VL53L1_DeviceReportStatus) 3)
+#define VL53L1_DEVICEREPORTSTATUS_REFERENCE_PHASE ((VL53L1_DeviceReportStatus) 4)
+#define VL53L1_DEVICEREPORTSTATUS_DSS1 ((VL53L1_DeviceReportStatus) 5)
+#define VL53L1_DEVICEREPORTSTATUS_DSS2 ((VL53L1_DeviceReportStatus) 6)
+#define VL53L1_DEVICEREPORTSTATUS_MM1 ((VL53L1_DeviceReportStatus) 7)
+#define VL53L1_DEVICEREPORTSTATUS_MM2 ((VL53L1_DeviceReportStatus) 8)
+#define VL53L1_DEVICEREPORTSTATUS_RANGE ((VL53L1_DeviceReportStatus) 9)
+#define VL53L1_DEVICEREPORTSTATUS_HISTOGRAM ((VL53L1_DeviceReportStatus) 10)
+
+/** @} end of VL53L1_DeviceReportStatus_group */
+
+/** @defgroup VL53L1_DeviceDssMode_group Dynamic SPAD Selection Mode
+ * @brief Selects the device Dynamic SPAD Selection Mode
+ * @{
+ */
+
+typedef uint8_t VL53L1_DeviceDssMode;
+
+#define VL53L1_DEVICEDSSMODE__DISABLED \
+ ((VL53L1_DeviceDssMode) 0)
+#define VL53L1_DEVICEDSSMODE__TARGET_RATE \
+ ((VL53L1_DeviceDssMode) 1)
+#define VL53L1_DEVICEDSSMODE__REQUESTED_EFFFECTIVE_SPADS \
+ ((VL53L1_DeviceDssMode) 2)
+#define VL53L1_DEVICEDSSMODE__BLOCK_SELECT \
+ ((VL53L1_DeviceDssMode) 3)
+
+/** @} end of VL53L1_DeviceDssMode_group */
+
+/** @defgroup VL53L1_DeviceConfigLevel_group Device Config Level
+ *
+ * @brief Defines the contents of the config & start range I2C multi byte transaction
+ * @{
+ */
+typedef uint8_t VL53L1_DeviceConfigLevel;
+
+#define VL53L1_DEVICECONFIGLEVEL_SYSTEM_CONTROL \
+ ((VL53L1_DeviceConfigLevel) 0)
+ /*!< Configs system control & start range */
+#define VL53L1_DEVICECONFIGLEVEL_DYNAMIC_ONWARDS \
+ ((VL53L1_DeviceConfigLevel) 1)
+ /*!< Dynamic config onwards (dynamic_config, system_control) & start range */
+#define VL53L1_DEVICECONFIGLEVEL_TIMING_ONWARDS \
+ ((VL53L1_DeviceConfigLevel) 2)
+ /*!< Dynamic config onwards (timing config, dynamic_config, system_control) &
+ start range */
+#define VL53L1_DEVICECONFIGLEVEL_GENERAL_ONWARDS \
+ ((VL53L1_DeviceConfigLevel) 3)
+ /*!< General config onwards (general_config, timing config, dynamic_config,
+ system_control) & start range */
+#define VL53L1_DEVICECONFIGLEVEL_STATIC_ONWARDS \
+ ((VL53L1_DeviceConfigLevel) 4)
+ /*!< Static config onwards (static_config, general_config, timing_config,
+ dynamic_config, system_control) & start range */
+#define VL53L1_DEVICECONFIGLEVEL_CUSTOMER_ONWARDS \
+ ((VL53L1_DeviceConfigLevel) 5)
+ /*!< Full device config (customer_nvm_managed, static_config, general_config,
+ timing config, dynamic_config, system_control) & start range */
+#define VL53L1_DEVICECONFIGLEVEL_FULL \
+ ((VL53L1_DeviceConfigLevel) 6)
+ /*!< Full device config (static_nvm_managed, customer_nvm_managed, static_config,
+ general_config, timing config, dynamic_config, system_control) & start range */
+
+/** @} end of VL53L1_DeviceConfigLevel_group */
+
+
+/** @defgroup VL53L1_DeviceResultsLevel_group Device Results Level
+ *
+ * @brief Defines the contents of the read results I2C multi byte transaction
+ * @{
+ */
+typedef uint8_t VL53L1_DeviceResultsLevel;
+
+#define VL53L1_DEVICERESULTSLEVEL_SYSTEM_RESULTS \
+ ((VL53L1_DeviceResultsLevel) 0)
+ /*!< Read just system_results */
+#define VL53L1_DEVICERESULTSLEVEL_UPTO_CORE \
+ ((VL53L1_DeviceResultsLevel) 1)
+ /*!< Read both system and core results */
+#define VL53L1_DEVICERESULTSLEVEL_FULL \
+ ((VL53L1_DeviceResultsLevel) 2)
+ /*!< Read system, core and debug results */
+
+/** @} end of VL53L1_DeviceResultsLevel_group */
+
+
+/** @defgroup VL53L1_DeviceTestMode_group Device Test Mode
+ *
+ * @brief Values below match the the TEST_MODE__CTRL register
+ * do not change
+ * @{
+ */
+
+typedef uint8_t VL53L1_DeviceTestMode;
+
+#define VL53L1_DEVICETESTMODE_NONE \
+ ((VL53L1_DeviceTestMode) 0x00)
+ /*!< Idle */
+#define VL53L1_DEVICETESTMODE_NVM_ZERO \
+ ((VL53L1_DeviceTestMode) 0x01)
+ /*!< NVM zero */
+#define VL53L1_DEVICETESTMODE_NVM_COPY \
+ ((VL53L1_DeviceTestMode) 0x02)
+ /*!< NVM copy */
+#define VL53L1_DEVICETESTMODE_PATCH \
+ ((VL53L1_DeviceTestMode) 0x03)
+ /*!< Patch */
+#define VL53L1_DEVICETESTMODE_DCR \
+ ((VL53L1_DeviceTestMode) 0x04)
+ /*!< DCR - SPAD Self-Check (Pass if Count Rate is less than Threshold) */
+#define VL53L1_DEVICETESTMODE_LCR_VCSEL_OFF \
+ ((VL53L1_DeviceTestMode) 0x05)
+ /*!< LCR - SPAD Self-Check (Pass if Count Rate is greater than Threshold
+ and VCSEL off) */
+#define VL53L1_DEVICETESTMODE_LCR_VCSEL_ON \
+ ((VL53L1_DeviceTestMode) 0x06)
+ /*!< LCR - SPAD Self-Check (Pass if Count Rate is greater than Threshold
+ and VCSEL on) */
+#define VL53L1_DEVICETESTMODE_SPOT_CENTRE_LOCATE \
+ ((VL53L1_DeviceTestMode) 0x07)
+ /*!< Spot centre locate */
+#define VL53L1_DEVICETESTMODE_REF_SPAD_CHAR_WITH_PRE_VHV \
+ ((VL53L1_DeviceTestMode) 0x08)
+ /*! 0.200000 * 256 = 51 = 0x33
+ Measured: 4.6x -> 0.217391 * 256 = 56 = 0x38 */
+
+#define VL53L1_SPAD_TOTAL_COUNT_MAX ((0x01 << 29) - 1)
+ /*!< Maximum SPAD count - 512Mcps * 1sec = 29bits) */
+#define VL53L1_SPAD_TOTAL_COUNT_RES_THRES (0x01 << 24)
+ /*!< SPAD count threshold for reduced 3-bit fractional resolution */
+#define VL53L1_COUNT_RATE_INTERNAL_MAX ((0x01 << 24) - 1)
+ /*!< Maximum internal count rate is a 17.7 (24-b) value */
+#define VL53L1_SPEED_OF_LIGHT_IN_AIR 299704
+ /*!< Speed of light in air in mm/sec */
+#define VL53L1_SPEED_OF_LIGHT_IN_AIR_DIV_8 (299704 >> 3)
+ /*!< Speed of light in air in divided by 8, 2 for round trip
+ and 4 as an additional scaling factor */
+
+/** @} end of VL53L1_ApiCore_group */
+
+/** @} end of VL53L1_DevSpecDefines_group */
+
+/** @defgroup VL53L1_GPIO_Interrupt_Mode_group Interrupt modes
+ * @brief Selects between four interrupt modes
+ * @{
+ */
+
+typedef uint8_t VL53L1_GPIO_Interrupt_Mode;
+
+#define VL53L1_GPIOINTMODE_LEVEL_LOW \
+ ((VL53L1_GPIO_Interrupt_Mode) 0)
+ /*!< Trigger interupt if value < thresh_low */
+#define VL53L1_GPIOINTMODE_LEVEL_HIGH \
+ ((VL53L1_GPIO_Interrupt_Mode) 1)
+ /*!< Trigger interupt if value > thresh_high */
+#define VL53L1_GPIOINTMODE_OUT_OF_WINDOW \
+ ((VL53L1_GPIO_Interrupt_Mode) 2)
+ /*!< Trigger interupt if value < thresh_low OR value > thresh_high */
+#define VL53L1_GPIOINTMODE_IN_WINDOW \
+ ((VL53L1_GPIO_Interrupt_Mode) 3)
+ /*!< Trigger interupt if value > thresh_low AND value < thresh_high */
+
+/** @} end of VL53L1_GPIO_Interrupt_Mode_group */
+
+/** @defgroup VL53L1_TuningParms_group Tuning Parameters
+ * @brief Selects specific tuning parameter inputs to get/set \
+ * Added as part of Patch_AddedTuningParms_11761
+ * @{
+ */
+
+typedef uint16_t VL53L1_TuningParms;
+
+#define VL53L1_TUNINGPARMS_LLD_PUBLIC_MIN_ADDRESS \
+ ((VL53L1_TuningParms) VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS)
+#define VL53L1_TUNINGPARMS_LLD_PUBLIC_MAX_ADDRESS \
+ ((VL53L1_TuningParms) VL53L1_TUNINGPARM_LOWPOWERAUTO_RANGE_CONFIG_TIMEOUT_US)
+
+#define VL53L1_TUNINGPARMS_LLD_PRIVATE_MIN_ADDRESS \
+ ((VL53L1_TuningParms) VL53L1_TUNINGPARM_PRIVATE_PAGE_BASE_ADDRESS)
+#define VL53L1_TUNINGPARMS_LLD_PRIVATE_MAX_ADDRESS \
+ ((VL53L1_TuningParms) VL53L1_TUNINGPARMS_LLD_PRIVATE_MIN_ADDRESS)
+
+#define VL53L1_TUNINGPARM_VERSION \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 0))
+#define VL53L1_TUNINGPARM_KEY_TABLE_VERSION \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 1))
+#define VL53L1_TUNINGPARM_LLD_VERSION \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 2))
+#define VL53L1_TUNINGPARM_CONSISTENCY_LITE_PHASE_TOLERANCE \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 3))
+#define VL53L1_TUNINGPARM_PHASECAL_TARGET \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 4))
+#define VL53L1_TUNINGPARM_LITE_CAL_REPEAT_RATE \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 5))
+#define VL53L1_TUNINGPARM_LITE_RANGING_GAIN_FACTOR \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 6))
+#define VL53L1_TUNINGPARM_LITE_MIN_CLIP_MM \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 7))
+#define VL53L1_TUNINGPARM_LITE_LONG_SIGMA_THRESH_MM \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 8))
+#define VL53L1_TUNINGPARM_LITE_MED_SIGMA_THRESH_MM \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 9))
+#define VL53L1_TUNINGPARM_LITE_SHORT_SIGMA_THRESH_MM \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 10))
+#define VL53L1_TUNINGPARM_LITE_LONG_MIN_COUNT_RATE_RTN_MCPS \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 11))
+#define VL53L1_TUNINGPARM_LITE_MED_MIN_COUNT_RATE_RTN_MCPS \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 12))
+#define VL53L1_TUNINGPARM_LITE_SHORT_MIN_COUNT_RATE_RTN_MCPS \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 13))
+#define VL53L1_TUNINGPARM_LITE_SIGMA_EST_PULSE_WIDTH \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 14))
+#define VL53L1_TUNINGPARM_LITE_SIGMA_EST_AMB_WIDTH_NS \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 15))
+#define VL53L1_TUNINGPARM_LITE_SIGMA_REF_MM \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 16))
+#define VL53L1_TUNINGPARM_LITE_RIT_MULT \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 17))
+#define VL53L1_TUNINGPARM_LITE_SEED_CONFIG \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 18))
+#define VL53L1_TUNINGPARM_LITE_QUANTIFIER \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 19))
+#define VL53L1_TUNINGPARM_LITE_FIRST_ORDER_SELECT \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 20))
+#define VL53L1_TUNINGPARM_LITE_XTALK_MARGIN_KCPS \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 21))
+#define VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_LONG_RANGE \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 22))
+#define VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_MED_RANGE \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 23))
+#define VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_SHORT_RANGE \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 24))
+#define VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_LONG_RANGE \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 25))
+#define VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_MED_RANGE \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 26))
+#define VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_SHORT_RANGE \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 27))
+#define VL53L1_TUNINGPARM_TIMED_SEED_CONFIG \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 28))
+#define VL53L1_TUNINGPARM_VHV_LOOPBOUND \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 29))
+#define VL53L1_TUNINGPARM_REFSPADCHAR_DEVICE_TEST_MODE \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 30))
+#define VL53L1_TUNINGPARM_REFSPADCHAR_VCSEL_PERIOD \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 31))
+#define VL53L1_TUNINGPARM_REFSPADCHAR_PHASECAL_TIMEOUT_US \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 32))
+#define VL53L1_TUNINGPARM_REFSPADCHAR_TARGET_COUNT_RATE_MCPS \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 33))
+#define VL53L1_TUNINGPARM_REFSPADCHAR_MIN_COUNTRATE_LIMIT_MCPS \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 34))
+#define VL53L1_TUNINGPARM_REFSPADCHAR_MAX_COUNTRATE_LIMIT_MCPS \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 35))
+#define VL53L1_TUNINGPARM_OFFSET_CAL_DSS_RATE_MCPS \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 36))
+#define VL53L1_TUNINGPARM_OFFSET_CAL_PHASECAL_TIMEOUT_US \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 37))
+#define VL53L1_TUNINGPARM_OFFSET_CAL_MM_TIMEOUT_US \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 38))
+#define VL53L1_TUNINGPARM_OFFSET_CAL_RANGE_TIMEOUT_US \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 39))
+#define VL53L1_TUNINGPARM_OFFSET_CAL_PRE_SAMPLES \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 40))
+#define VL53L1_TUNINGPARM_OFFSET_CAL_MM1_SAMPLES \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 41))
+#define VL53L1_TUNINGPARM_OFFSET_CAL_MM2_SAMPLES \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 42))
+#define VL53L1_TUNINGPARM_SPADMAP_VCSEL_PERIOD \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 43))
+#define VL53L1_TUNINGPARM_SPADMAP_VCSEL_START \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 44))
+#define VL53L1_TUNINGPARM_SPADMAP_RATE_LIMIT_MCPS \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 45))
+#define VL53L1_TUNINGPARM_LITE_DSS_CONFIG_TARGET_TOTAL_RATE_MCPS \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 46))
+#define VL53L1_TUNINGPARM_TIMED_DSS_CONFIG_TARGET_TOTAL_RATE_MCPS \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 47))
+#define VL53L1_TUNINGPARM_LITE_PHASECAL_CONFIG_TIMEOUT_US \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 48))
+#define VL53L1_TUNINGPARM_TIMED_PHASECAL_CONFIG_TIMEOUT_US \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 49))
+#define VL53L1_TUNINGPARM_LITE_MM_CONFIG_TIMEOUT_US \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 50))
+#define VL53L1_TUNINGPARM_TIMED_MM_CONFIG_TIMEOUT_US \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 51))
+#define VL53L1_TUNINGPARM_LITE_RANGE_CONFIG_TIMEOUT_US \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 52))
+#define VL53L1_TUNINGPARM_TIMED_RANGE_CONFIG_TIMEOUT_US \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 53))
+#define VL53L1_TUNINGPARM_LOWPOWERAUTO_VHV_LOOP_BOUND \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 54))
+#define VL53L1_TUNINGPARM_LOWPOWERAUTO_MM_CONFIG_TIMEOUT_US \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 55))
+#define VL53L1_TUNINGPARM_LOWPOWERAUTO_RANGE_CONFIG_TIMEOUT_US \
+ ((VL53L1_TuningParms) (VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS + 56))
+
+
+/** @} end of VL53L1_TuningParms_group */
+
+
+#endif
+
+/* _VL53L1_DEVICE_H_ */
+
+
diff --git a/src/lib/vl53l1/core/inc/vl53l1_nvm_map.h b/src/lib/vl53l1/core/inc/vl53l1_nvm_map.h
new file mode 100644
index 0000000000..64a085b070
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_nvm_map.h
@@ -0,0 +1,2988 @@
+/*******************************************************************************
+ Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ ******************************************************************************/
+
+/**
+ * @file vl53l1_nvm_map.h
+ * @brief NVM Map definitions for EwokPlus25 NVM Interface Functions.
+ *
+ */
+
+/*
+ * Include platform specific and register map definitions
+ */
+
+
+#ifndef _VL53L1_NVM_MAP_H_
+#define _VL53L1_NVM_MAP_H_
+
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+
+/** @defgroup VL53L1_nvm_DefineRegisters_group Define Registers * @brief List of all the defined registers
+ * @{
+ */
+
+#define VL53L1_NVM__IDENTIFICATION__MODEL_ID 0x0008
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__identification_model_id
+*/
+#define VL53L1_NVM__IDENTIFICATION__MODULE_TYPE 0x000C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__identification_module_type
+*/
+#define VL53L1_NVM__IDENTIFICATION__REVISION_ID 0x000D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [3:0] = nvm__identification_revision_id
+*/
+#define VL53L1_NVM__IDENTIFICATION__MODULE_ID 0x000E
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [15:0] = nvm__identification_module_id
+*/
+#define VL53L1_NVM__I2C_VALID 0x0010
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__i2c_valid
+*/
+#define VL53L1_NVM__I2C_SLAVE__DEVICE_ADDRESS 0x0011
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__i2c_device_address_ews
+*/
+#define VL53L1_NVM__EWS__OSC_MEASURED__FAST_OSC_FREQUENCY 0x0014
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [15:0] = nvm__ews__fast_osc_frequency (fixed point 4.12)
+*/
+#define VL53L1_NVM__EWS__FAST_OSC_TRIM_MAX 0x0016
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [6:0] = nvm__ews__fast_osc_trim_max
+*/
+#define VL53L1_NVM__EWS__FAST_OSC_FREQ_SET 0x0017
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [2:0] = nvm__ews__fast_osc_freq_set
+*/
+#define VL53L1_NVM__EWS__SLOW_OSC_CALIBRATION 0x0018
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 9
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [9:0] = nvm__ews__slow_osc_calibration
+*/
+#define VL53L1_NVM__FMT__OSC_MEASURED__FAST_OSC_FREQUENCY 0x001C
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [15:0] = nvm__fmt__fast_osc_frequency (fixed point 4.12)
+*/
+#define VL53L1_NVM__FMT__FAST_OSC_TRIM_MAX 0x001E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [6:0] = nvm__fmt__fast_osc_trim_max
+*/
+#define VL53L1_NVM__FMT__FAST_OSC_FREQ_SET 0x001F
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [2:0] = nvm__fmt__fast_osc_freq_set
+*/
+#define VL53L1_NVM__FMT__SLOW_OSC_CALIBRATION 0x0020
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 9
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [9:0] = nvm__fmt__slow_osc_calibration
+*/
+#define VL53L1_NVM__VHV_CONFIG_UNLOCK 0x0028
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__vhv_config_unlock
+*/
+#define VL53L1_NVM__REF_SELVDDPIX 0x0029
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [3:0] = nvm__ref_selvddpix
+*/
+#define VL53L1_NVM__REF_SELVQUENCH 0x002A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 6
+ - lsb = 3
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [6:3] = nvm__ref_selvquench
+*/
+#define VL53L1_NVM__REGAVDD1V2_SEL_REGDVDD1V2_SEL 0x002B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [3:2] = nvm__regavdd1v2_sel
+ - [1:0] = nvm__regdvdd1v2_sel
+*/
+#define VL53L1_NVM__VHV_CONFIG__TIMEOUT_MACROP_LOOP_BOUND 0x002C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [1:0] = nvm__vhv_timeout__macrop
+ - [7:2] = nvm__vhv_loop_bound
+*/
+#define VL53L1_NVM__VHV_CONFIG__COUNT_THRESH 0x002D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__vhv_count_threshold
+*/
+#define VL53L1_NVM__VHV_CONFIG__OFFSET 0x002E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [5:0] = nvm__vhv_offset
+*/
+#define VL53L1_NVM__VHV_CONFIG__INIT 0x002F
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7] = nvm__vhv_init_enable
+ - [5:0] = nvm__vhv_init_value
+*/
+#define VL53L1_NVM__LASER_SAFETY__VCSEL_TRIM_LL 0x0030
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [2:0] = nvm__laser_safety_vcsel_trim_ll
+*/
+#define VL53L1_NVM__LASER_SAFETY__VCSEL_SELION_LL 0x0031
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [5:0] = nvm__laser_safety_vcsel_selion_ll
+*/
+#define VL53L1_NVM__LASER_SAFETY__VCSEL_SELION_MAX_LL 0x0032
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [5:0] = nvm__laser_safety_vcsel_selion_max_ll
+*/
+#define VL53L1_NVM__LASER_SAFETY__MULT_LL 0x0034
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [5:0] = nvm__laser_safety_mult_ll
+*/
+#define VL53L1_NVM__LASER_SAFETY__CLIP_LL 0x0035
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [5:0] = nvm__laser_safety_clip_ll
+*/
+#define VL53L1_NVM__LASER_SAFETY__VCSEL_TRIM_LD 0x0038
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [2:0] = nvm__laser_safety_vcsel_trim_ld
+*/
+#define VL53L1_NVM__LASER_SAFETY__VCSEL_SELION_LD 0x0039
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [5:0] = nvm__laser_safety_vcsel_selion_ld
+*/
+#define VL53L1_NVM__LASER_SAFETY__VCSEL_SELION_MAX_LD 0x003A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [5:0] = nvm__laser_safety_vcsel_selion_max_ld
+*/
+#define VL53L1_NVM__LASER_SAFETY__MULT_LD 0x003C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [5:0] = nvm__laser_safety_mult_ld
+*/
+#define VL53L1_NVM__LASER_SAFETY__CLIP_LD 0x003D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [5:0] = nvm__laser_safety_clip_ld
+*/
+#define VL53L1_NVM__LASER_SAFETY_LOCK_BYTE 0x0040
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__laser_safety_lock_byte
+*/
+#define VL53L1_NVM__LASER_SAFETY_UNLOCK_BYTE 0x0044
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__laser_safety_unlock_byte
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_0_ 0x0048
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_0_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_1_ 0x0049
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_1_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_2_ 0x004A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_2_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_3_ 0x004B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_3_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_4_ 0x004C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_4_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_5_ 0x004D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_5_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_6_ 0x004E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_6_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_7_ 0x004F
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_7_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_8_ 0x0050
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_8_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_9_ 0x0051
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_9_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_10_ 0x0052
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_10_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_11_ 0x0053
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_11_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_12_ 0x0054
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_12_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_13_ 0x0055
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_13_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_14_ 0x0056
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_14_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_15_ 0x0057
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_15_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_16_ 0x0058
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_16_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_17_ 0x0059
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_17_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_18_ 0x005A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_18_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_19_ 0x005B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_19_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_20_ 0x005C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_20_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_21_ 0x005D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_21_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_22_ 0x005E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_22_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_23_ 0x005F
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_23_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_24_ 0x0060
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_24_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_25_ 0x0061
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_25_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_26_ 0x0062
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_26_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_27_ 0x0063
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_27_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_28_ 0x0064
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_28_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_29_ 0x0065
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_29_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_30_ 0x0066
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_30_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_RTN_31_ 0x0067
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_rtn_31_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC1_0_ 0x0068
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc1_0_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC1_1_ 0x0069
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc1_1_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC1_2_ 0x006A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc1_2_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC1_3_ 0x006B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc1_3_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC1_4_ 0x006C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc1_4_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC1_5_ 0x006D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc1_5_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC2_0_ 0x0070
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc2_0_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC2_1_ 0x0071
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc2_1_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC2_2_ 0x0072
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc2_2_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC2_3_ 0x0073
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc2_3_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC2_4_ 0x0074
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc2_4_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC2_5_ 0x0075
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc2_5_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC3_0_ 0x0078
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc3_0_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC3_1_ 0x0079
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc3_1_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC3_2_ 0x007A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc3_2_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC3_3_ 0x007B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc3_3_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC3_4_ 0x007C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc3_4_
+*/
+#define VL53L1_NVM__EWS__SPAD_ENABLES_REF__LOC3_5_ 0x007D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__spad_enables_ref__loc3_5_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_0_ 0x0080
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_0_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_1_ 0x0081
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_1_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_2_ 0x0082
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_2_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_3_ 0x0083
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_3_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_4_ 0x0084
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_4_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_5_ 0x0085
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_5_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_6_ 0x0086
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_6_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_7_ 0x0087
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_7_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_8_ 0x0088
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_8_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_9_ 0x0089
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_9_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_10_ 0x008A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_10_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_11_ 0x008B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_11_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_12_ 0x008C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_12_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_13_ 0x008D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_13_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_14_ 0x008E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_14_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_15_ 0x008F
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_15_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_16_ 0x0090
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_16_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_17_ 0x0091
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_17_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_18_ 0x0092
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_18_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_19_ 0x0093
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_19_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_20_ 0x0094
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_20_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_21_ 0x0095
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_21_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_22_ 0x0096
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_22_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_23_ 0x0097
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_23_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_24_ 0x0098
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_24_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_25_ 0x0099
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_25_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_26_ 0x009A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_26_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_27_ 0x009B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_27_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_28_ 0x009C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_28_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_29_ 0x009D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_29_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_30_ 0x009E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_30_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_RTN_31_ 0x009F
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_rtn_31_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC1_0_ 0x00A0
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc1_0_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC1_1_ 0x00A1
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc1_1_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC1_2_ 0x00A2
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc1_2_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC1_3_ 0x00A3
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc1_3_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC1_4_ 0x00A4
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc1_4_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC1_5_ 0x00A5
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc1_5_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC2_0_ 0x00A8
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc2_0_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC2_1_ 0x00A9
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc2_1_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC2_2_ 0x00AA
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc2_2_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC2_3_ 0x00AB
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc2_3_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC2_4_ 0x00AC
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc2_4_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC2_5_ 0x00AD
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc2_5_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC3_0_ 0x00B0
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc3_0_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC3_1_ 0x00B1
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc3_1_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC3_2_ 0x00B2
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc3_2_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC3_3_ 0x00B3
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc3_3_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC3_4_ 0x00B4
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc3_4_
+*/
+#define VL53L1_NVM__FMT__SPAD_ENABLES_REF__LOC3_5_ 0x00B5
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spad_enables_ref__loc3_5_
+*/
+#define VL53L1_NVM__FMT__ROI_CONFIG__MODE_ROI_CENTRE_SPAD 0x00B8
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__roi_config__mode_roi_centre_spad
+*/
+#define VL53L1_NVM__FMT__ROI_CONFIG__MODE_ROI_XY_SIZE 0x00B9
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:4] = nvm__fmt__roi_config__mode_roi_x_size
+ - [3:0] = nvm__fmt__roi_config__mode_roi_y_size
+*/
+#define VL53L1_NVM__FMT__REF_SPAD_APPLY__NUM_REQUESTED_REF_SPAD 0x00BC
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__ref_spad_apply__num_requested_ref_spad
+*/
+#define VL53L1_NVM__FMT__REF_SPAD_MAN__REF_LOCATION 0x00BD
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [1:0] = nvm__fmt__ref_spad_man__ref_location
+*/
+#define VL53L1_NVM__FMT__MM_CONFIG__INNER_OFFSET_MM 0x00C0
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [15:0] = nvm__fmt__mm_config__inner_offset_mm
+*/
+#define VL53L1_NVM__FMT__MM_CONFIG__OUTER_OFFSET_MM 0x00C2
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [15:0] = nvm__fmt__mm_config__outer_offset_mm
+*/
+#define VL53L1_NVM__FMT__ALGO__PART_TO_PART_RANGE_OFFSET_MM 0x00C4
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 11
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [11:0] = nvm__fmt__algo_part_to_part_range_offset_mm (fixed point 10.2)
+*/
+#define VL53L1_NVM__FMT__ALGO__CROSSTALK_COMPENSATION_PLANE_OFFSET_KCPS 0x00C8
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [15:0] = nvm__fmt__algo__crosstalk_compensation_plane_offset_kcps (fixed point 7.9)
+*/
+#define VL53L1_NVM__FMT__ALGO__CROSSTALK_COMPENSATION_X_PLANE_GRADIENT_KCPS 0x00CA
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [15:0] = nvm__fmt__algo__crosstalk_compensation_x_plane_gradient_kcps (fixed point 5.11)
+*/
+#define VL53L1_NVM__FMT__ALGO__CROSSTALK_COMPENSATION_Y_PLANE_GRADIENT_KCPS 0x00CC
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [15:0] = nvm__fmt__algo__crosstalk_compensation_y_plane_gradient_kcps (fixed point 5.11)
+*/
+#define VL53L1_NVM__FMT__SPARE_HOST_CONFIG__NVM_CONFIG_SPARE_0 0x00CE
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spare__host_config__nvm_config_spare_0
+*/
+#define VL53L1_NVM__FMT__SPARE_HOST_CONFIG__NVM_CONFIG_SPARE_1 0x00CF
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__spare__host_config__nvm_config_spare_1
+*/
+#define VL53L1_NVM__CUSTOMER_NVM_SPACE_PROGRAMMED 0x00E0
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__customer_space_programmed
+*/
+#define VL53L1_NVM__CUST__I2C_SLAVE__DEVICE_ADDRESS 0x00E4
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__cust__i2c_device_address
+*/
+#define VL53L1_NVM__CUST__REF_SPAD_APPLY__NUM_REQUESTED_REF_SPAD 0x00E8
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__cust__ref_spad_apply__num_requested_ref_spad
+*/
+#define VL53L1_NVM__CUST__REF_SPAD_MAN__REF_LOCATION 0x00E9
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [1:0] = nvm__cust__ref_spad_man__ref_location
+*/
+#define VL53L1_NVM__CUST__MM_CONFIG__INNER_OFFSET_MM 0x00EC
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [15:0] = nvm__cust__mm_config__inner_offset_mm
+*/
+#define VL53L1_NVM__CUST__MM_CONFIG__OUTER_OFFSET_MM 0x00EE
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [15:0] = nvm__cust__mm_config__outer_offset_mm
+*/
+#define VL53L1_NVM__CUST__ALGO__PART_TO_PART_RANGE_OFFSET_MM 0x00F0
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 11
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [11:0] = nvm__cust__algo_part_to_part_range_offset_mm (fixed point 10.2)
+*/
+#define VL53L1_NVM__CUST__ALGO__CROSSTALK_COMPENSATION_PLANE_OFFSET_KCPS 0x00F4
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [15:0] = nvm__cust__algo__crosstalk_compensation_plane_offset_kcps (fixed point 7.9)
+*/
+#define VL53L1_NVM__CUST__ALGO__CROSSTALK_COMPENSATION_X_PLANE_GRADIENT_KCPS 0x00F6
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [15:0] = nvm__cust__algo__crosstalk_compensation_x_plane_gradient_kcps (fixed point 5.11)
+*/
+#define VL53L1_NVM__CUST__ALGO__CROSSTALK_COMPENSATION_Y_PLANE_GRADIENT_KCPS 0x00F8
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [15:0] = nvm__cust__algo__crosstalk_compensation_y_plane_gradient_kcps (fixed point 5.11)
+*/
+#define VL53L1_NVM__CUST__SPARE_HOST_CONFIG__NVM_CONFIG_SPARE_0 0x00FA
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__cust__spare__host_config__nvm_config_spare_0
+*/
+#define VL53L1_NVM__CUST__SPARE_HOST_CONFIG__NVM_CONFIG_SPARE_1 0x00FB
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__cust__spare__host_config__nvm_config_spare_1
+*/
+#define VL53L1_NVM__FMT__FGC__BYTE_0 0x01DC
+/*!<
+ type: char \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 1
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:1] = nvm__fmt__fgc_0_
+*/
+#define VL53L1_NVM__FMT__FGC__BYTE_1 0x01DD
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 8
+ - lsb = 2
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [8:2] = nvm__fmt__fgc_1_
+*/
+#define VL53L1_NVM__FMT__FGC__BYTE_2 0x01DE
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 9
+ - lsb = 3
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [9:3] = nvm__fmt__fgc_2_
+*/
+#define VL53L1_NVM__FMT__FGC__BYTE_3 0x01DF
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 10
+ - lsb = 4
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [10:4] = nvm__fmt__fgc_3_
+*/
+#define VL53L1_NVM__FMT__FGC__BYTE_4 0x01E0
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 11
+ - lsb = 5
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [11:5] = nvm__fmt__fgc_4_
+*/
+#define VL53L1_NVM__FMT__FGC__BYTE_5 0x01E1
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 12
+ - lsb = 6
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [12:6] = nvm__fmt__fgc_5_
+*/
+#define VL53L1_NVM__FMT__FGC__BYTE_6 0x01E2
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 13
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [13:7] = nvm__fmt__fgc_6_
+ - [6:0] = nvm__fmt__fgc_7_
+*/
+#define VL53L1_NVM__FMT__FGC__BYTE_7 0x01E3
+/*!<
+ type: char \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 1
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:1] = nvm__fmt__fgc_8_
+*/
+#define VL53L1_NVM__FMT__FGC__BYTE_8 0x01E4
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 8
+ - lsb = 2
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [8:2] = nvm__fmt__fgc_9_
+*/
+#define VL53L1_NVM__FMT__FGC__BYTE_9 0x01E5
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 9
+ - lsb = 3
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [9:3] = nvm__fmt__fgc_10_
+*/
+#define VL53L1_NVM__FMT__FGC__BYTE_10 0x01E6
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 10
+ - lsb = 4
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [10:4] = nvm__fmt__fgc_11_
+*/
+#define VL53L1_NVM__FMT__FGC__BYTE_11 0x01E7
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 11
+ - lsb = 5
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [11:5] = nvm__fmt__fgc_12_
+*/
+#define VL53L1_NVM__FMT__FGC__BYTE_12 0x01E8
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 12
+ - lsb = 6
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [12:6] = nvm__fmt__fgc_13_
+*/
+#define VL53L1_NVM__FMT__FGC__BYTE_13 0x01E9
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 13
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [13:7] = nvm__fmt__fgc_14_
+ - [6:0] = nvm__fmt__fgc_15_
+*/
+#define VL53L1_NVM__FMT__FGC__BYTE_14 0x01EA
+/*!<
+ type: char \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 1
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:1] = nvm__fmt__fgc_16_
+*/
+#define VL53L1_NVM__FMT__FGC__BYTE_15 0x01EB
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 8
+ - lsb = 2
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [8:2] = nvm__fmt__fgc_17_
+*/
+#define VL53L1_NVM__FMT__TEST_PROGRAM_MAJOR_MINOR 0x01EC
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:5] = nvm__fmt__test_program_major
+ - [4:0] = nvm__fmt__test_program_minor
+*/
+#define VL53L1_NVM__FMT__MAP_MAJOR_MINOR 0x01ED
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:5] = nvm__fmt__map_major
+ - [4:0] = nvm__fmt__map_minor
+*/
+#define VL53L1_NVM__FMT__YEAR_MONTH 0x01EE
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:4] = nvm__fmt__year
+ - [3:0] = nvm__fmt__month
+*/
+#define VL53L1_NVM__FMT__DAY_MODULE_DATE_PHASE 0x01EF
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:3] = nvm__fmt__day
+ - [2:0] = nvm__fmt__module_date_phase
+*/
+#define VL53L1_NVM__FMT__TIME 0x01F0
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [15:0] = nvm__fmt__time
+*/
+#define VL53L1_NVM__FMT__TESTER_ID 0x01F2
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__tester_id
+*/
+#define VL53L1_NVM__FMT__SITE_ID 0x01F3
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__fmt__site_id
+*/
+#define VL53L1_NVM__EWS__TEST_PROGRAM_MAJOR_MINOR 0x01F4
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:5] = nvm__ews__test_program_major
+ - [4:0] = nvm__ews__test_program_minor
+*/
+#define VL53L1_NVM__EWS__PROBE_CARD_MAJOR_MINOR 0x01F5
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:4] = nvm__ews__probe_card_major
+ - [3:0] = nvm__ews__probe_card_minor
+*/
+#define VL53L1_NVM__EWS__TESTER_ID 0x01F6
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__tester_id
+*/
+#define VL53L1_NVM__EWS__LOT__BYTE_0 0x01F8
+/*!<
+ type: char \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 2
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:2] = nvm__ews__lot_6_
+*/
+#define VL53L1_NVM__EWS__LOT__BYTE_1 0x01F9
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 9
+ - lsb = 4
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [9:4] = nvm__ews__lot_5_
+*/
+#define VL53L1_NVM__EWS__LOT__BYTE_2 0x01FA
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 11
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [11:6] = nvm__ews__lot_4_
+ - [5:0] = nvm__ews__lot_3_
+*/
+#define VL53L1_NVM__EWS__LOT__BYTE_3 0x01FB
+/*!<
+ type: char \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 2
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:2] = nvm__ews__lot_2_
+*/
+#define VL53L1_NVM__EWS__LOT__BYTE_4 0x01FC
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 9
+ - lsb = 4
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [9:4] = nvm__ews__lot_1_
+*/
+#define VL53L1_NVM__EWS__LOT__BYTE_5 0x01FD
+/*!<
+ type: char \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 11
+ - lsb = 6
+ - i2c_size = 2
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [11:6] = nvm__ews__lot_0_
+*/
+#define VL53L1_NVM__EWS__WAFER 0x01FD
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 4
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [4:0] = nvm__ews__wafer
+*/
+#define VL53L1_NVM__EWS__XCOORD 0x01FE
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__xcoord
+*/
+#define VL53L1_NVM__EWS__YCOORD 0x01FF
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['decoded_nvm_data']
+
+ fields: \n
+ - [7:0] = nvm__ews__ycoord
+*/
+
+#define VL53L1_NVM__FMT__OPTICAL_CENTRE_DATA_INDEX 0x00B8
+#define VL53L1_NVM__FMT__OPTICAL_CENTRE_DATA_SIZE 4
+
+#define VL53L1_NVM__FMT__CAL_PEAK_RATE_MAP_DATA_INDEX 0x015C
+#define VL53L1_NVM__FMT__CAL_PEAK_RATE_MAP_DATA_SIZE 56
+
+#define VL53L1_NVM__FMT__ADDITIONAL_OFFSET_CAL_DATA_INDEX 0x0194
+#define VL53L1_NVM__FMT__ADDITIONAL_OFFSET_CAL_DATA_SIZE 8
+
+#define VL53L1_NVM__FMT__RANGE_RESULTS__140MM_MM_PRE_RANGE 0x019C
+#define VL53L1_NVM__FMT__RANGE_RESULTS__140MM_DARK 0x01AC
+#define VL53L1_NVM__FMT__RANGE_RESULTS__400MM_DARK 0x01BC
+#define VL53L1_NVM__FMT__RANGE_RESULTS__400MM_AMBIENT 0x01CC
+#define VL53L1_NVM__FMT__RANGE_RESULTS__SIZE_BYTES 16
+
+/** @} VL53L1_nvm_DefineRegisters_group */
+
+
+
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/src/lib/vl53l1/core/inc/vl53l1_preset_setup.h b/src/lib/vl53l1/core/inc/vl53l1_preset_setup.h
new file mode 100644
index 0000000000..c641a7f5f3
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_preset_setup.h
@@ -0,0 +1,94 @@
+/*
+* Copyright (c) 2017, STMicroelectronics - All Rights Reserved
+*
+* This file is part of VL53L1 Core and is dual licensed, either
+* 'STMicroelectronics Proprietary license'
+* or 'BSD 3-clause "New" or "Revised" License' , at your option.
+*
+********************************************************************************
+*
+* 'STMicroelectronics Proprietary license'
+*
+********************************************************************************
+*
+* License terms: STMicroelectronics Proprietary in accordance with licensing
+* terms at www.st.com/sla0044
+*
+* STMicroelectronics confidential
+* Reproduction and Communication of this document is strictly prohibited unless
+* specifically authorized in writing by STMicroelectronics.
+*
+*
+********************************************************************************
+*
+* Alternatively, VL53L1 Core may be distributed under the terms of
+* 'BSD 3-clause "New" or "Revised" License', in which case the following
+* provisions apply instead of the ones
+* mentioned above :
+*
+********************************************************************************
+*
+* License terms: BSD 3-clause "New" or "Revised" License.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions are met:
+*
+* 1. Redistributions of source code must retain the above copyright notice, this
+* list of conditions and the following disclaimer.
+*
+* 2. Redistributions in binary form must reproduce the above copyright notice,
+* this list of conditions and the following disclaimer in the documentation
+* and/or other materials provided with the distribution.
+*
+* 3. Neither the name of the copyright holder nor the names of its contributors
+* may be used to endorse or promote products derived from this software
+* without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*
+********************************************************************************
+*
+*/
+
+#ifndef _VL53L1_PRESET_SETUP_H_
+#define _VL53L1_PRESET_SETUP_H_
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/* indexes for the bare driver tuning setting API function */
+enum VL53L1_Tuning_t {
+ VL53L1_TUNING_VERSION = 0,
+ VL53L1_TUNING_PROXY_MIN,
+ VL53L1_TUNING_SINGLE_TARGET_XTALK_TARGET_DISTANCE_MM,
+ VL53L1_TUNING_SINGLE_TARGET_XTALK_SAMPLE_NUMBER,
+ VL53L1_TUNING_MIN_AMBIENT_DMAX_VALID,
+ VL53L1_TUNING_MAX_SIMPLE_OFFSET_CALIBRATION_SAMPLE_NUMBER,
+
+ VL53L1_TUNING_MAX_TUNABLE_KEY
+};
+
+/* default values for the tuning settings parameters */
+#define TUNING_VERSION 0x0002
+
+/* the following table should actually be defined as static and shall be part
+ * of the VL53L1_StaticInit() function code
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _VL53L1_PRESET_SETUP_H_ */
diff --git a/src/lib/vl53l1/core/inc/vl53l1_register_funcs.h b/src/lib/vl53l1/core/inc/vl53l1_register_funcs.h
new file mode 100644
index 0000000000..e0fa3baace
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_register_funcs.h
@@ -0,0 +1,1605 @@
+/*******************************************************************************
+ * #endif
+Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+******************************************************************************/
+
+/**
+ * @file vl53l1_register_funcs.h
+ * @brief VL53L1 Register Function declarations
+ */
+
+#ifndef _VL53L1_REGISTER_FUNCS_H_
+#define _VL53L1_REGISTER_FUNCS_H_
+
+#include "vl53l1_platform.h"
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+
+/**
+ * @brief Encodes data structure VL53L1_static_nvm_managed_t into a I2C write buffer
+ *
+ * Buffer must be at least 11 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_static_nvm_managed_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+VL53L1_Error VL53L1_i2c_encode_static_nvm_managed(
+ VL53L1_static_nvm_managed_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes data structure VL53L1_static_nvm_managed_t from the input I2C read buffer
+ *
+ * Buffer must be at least 11 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_static_nvm_managed_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_i2c_decode_static_nvm_managed(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_static_nvm_managed_t *pdata);
+
+
+/**
+ * @brief Sets static_nvm_managed register group
+ *
+ * Serailises (encodes) VL53L1_static_nvm_managed_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_static_nvm_managed_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_static_nvm_managed(
+ VL53L1_DEV Dev,
+ VL53L1_static_nvm_managed_t *pdata);
+
+
+/**
+ * @brief Gets static_nvm_managed register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_static_nvm_managed_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_static_nvm_managed_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_static_nvm_managed(
+ VL53L1_DEV Dev,
+ VL53L1_static_nvm_managed_t *pdata);
+
+
+/**
+ * @brief Encodes data structure VL53L1_customer_nvm_managed_t into a I2C write buffer
+ *
+ * Buffer must be at least 23 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_customer_nvm_managed_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+VL53L1_Error VL53L1_i2c_encode_customer_nvm_managed(
+ VL53L1_customer_nvm_managed_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes data structure VL53L1_customer_nvm_managed_t from the input I2C read buffer
+ *
+ * Buffer must be at least 23 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_customer_nvm_managed_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_i2c_decode_customer_nvm_managed(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_customer_nvm_managed_t *pdata);
+
+
+/**
+ * @brief Sets customer_nvm_managed register group
+ *
+ * Serailises (encodes) VL53L1_customer_nvm_managed_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_customer_nvm_managed_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_customer_nvm_managed(
+ VL53L1_DEV Dev,
+ VL53L1_customer_nvm_managed_t *pdata);
+
+
+/**
+ * @brief Gets customer_nvm_managed register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_customer_nvm_managed_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_customer_nvm_managed_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_customer_nvm_managed(
+ VL53L1_DEV Dev,
+ VL53L1_customer_nvm_managed_t *pdata);
+
+
+/**
+ * @brief Encodes data structure VL53L1_static_config_t into a I2C write buffer
+ *
+ * Buffer must be at least 32 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_static_config_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+VL53L1_Error VL53L1_i2c_encode_static_config(
+ VL53L1_static_config_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes data structure VL53L1_static_config_t from the input I2C read buffer
+ *
+ * Buffer must be at least 32 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_static_config_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_i2c_decode_static_config(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_static_config_t *pdata);
+
+
+/**
+ * @brief Sets static_config register group
+ *
+ * Serailises (encodes) VL53L1_static_config_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_static_config_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_static_config(
+ VL53L1_DEV Dev,
+ VL53L1_static_config_t *pdata);
+
+
+/**
+ * @brief Gets static_config register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_static_config_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_static_config_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_get_static_config(
+ VL53L1_DEV Dev,
+ VL53L1_static_config_t *pdata);
+#endif
+
+
+/**
+ * @brief Encodes data structure VL53L1_general_config_t into a I2C write buffer
+ *
+ * Buffer must be at least 22 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_general_config_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+VL53L1_Error VL53L1_i2c_encode_general_config(
+ VL53L1_general_config_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes data structure VL53L1_general_config_t from the input I2C read buffer
+ *
+ * Buffer must be at least 22 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_general_config_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_i2c_decode_general_config(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_general_config_t *pdata);
+
+
+/**
+ * @brief Sets general_config register group
+ *
+ * Serailises (encodes) VL53L1_general_config_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_general_config_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_general_config(
+ VL53L1_DEV Dev,
+ VL53L1_general_config_t *pdata);
+
+
+/**
+ * @brief Gets general_config register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_general_config_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_general_config_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_get_general_config(
+ VL53L1_DEV Dev,
+ VL53L1_general_config_t *pdata);
+#endif
+
+
+/**
+ * @brief Encodes data structure VL53L1_timing_config_t into a I2C write buffer
+ *
+ * Buffer must be at least 23 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_timing_config_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+VL53L1_Error VL53L1_i2c_encode_timing_config(
+ VL53L1_timing_config_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes data structure VL53L1_timing_config_t from the input I2C read buffer
+ *
+ * Buffer must be at least 23 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_timing_config_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_decode_timing_config(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_timing_config_t *pdata);
+#endif
+
+
+/**
+ * @brief Sets timing_config register group
+ *
+ * Serailises (encodes) VL53L1_timing_config_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_timing_config_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_set_timing_config(
+ VL53L1_DEV Dev,
+ VL53L1_timing_config_t *pdata);
+#endif
+
+
+/**
+ * @brief Gets timing_config register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_timing_config_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_timing_config_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_get_timing_config(
+ VL53L1_DEV Dev,
+ VL53L1_timing_config_t *pdata);
+#endif
+
+
+/**
+ * @brief Encodes data structure VL53L1_dynamic_config_t into a I2C write buffer
+ *
+ * Buffer must be at least 18 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_dynamic_config_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+VL53L1_Error VL53L1_i2c_encode_dynamic_config(
+ VL53L1_dynamic_config_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes data structure VL53L1_dynamic_config_t from the input I2C read buffer
+ *
+ * Buffer must be at least 18 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_dynamic_config_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_decode_dynamic_config(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_dynamic_config_t *pdata);
+#endif
+
+
+/**
+ * @brief Sets dynamic_config register group
+ *
+ * Serailises (encodes) VL53L1_dynamic_config_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_dynamic_config_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_dynamic_config(
+ VL53L1_DEV Dev,
+ VL53L1_dynamic_config_t *pdata);
+
+
+/**
+ * @brief Gets dynamic_config register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_dynamic_config_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_dynamic_config_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_get_dynamic_config(
+ VL53L1_DEV Dev,
+ VL53L1_dynamic_config_t *pdata);
+#endif
+
+/**
+ * @brief Encodes data structure VL53L1_system_control_t into a I2C write buffer
+ *
+ * Buffer must be at least 5 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_system_control_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+VL53L1_Error VL53L1_i2c_encode_system_control(
+ VL53L1_system_control_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes data structure VL53L1_system_control_t from the input I2C read buffer
+ *
+ * Buffer must be at least 5 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_system_control_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_decode_system_control(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_system_control_t *pdata);
+#endif
+
+
+/**
+ * @brief Sets system_control register group
+ *
+ * Serailises (encodes) VL53L1_system_control_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_system_control_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_system_control(
+ VL53L1_DEV Dev,
+ VL53L1_system_control_t *pdata);
+
+
+/**
+ * @brief Gets system_control register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_system_control_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_system_control_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_get_system_control(
+ VL53L1_DEV Dev,
+ VL53L1_system_control_t *pdata);
+#endif
+
+
+/**
+ * @brief Encodes data structure VL53L1_system_results_t into a I2C write buffer
+ *
+ * Buffer must be at least 44 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_system_results_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_encode_system_results(
+ VL53L1_system_results_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+#endif
+
+
+/**
+ * @brief Decodes data structure VL53L1_system_results_t from the input I2C read buffer
+ *
+ * Buffer must be at least 44 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_system_results_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_i2c_decode_system_results(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_system_results_t *pdata);
+
+
+/**
+ * @brief Sets system_results register group
+ *
+ * Serailises (encodes) VL53L1_system_results_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_system_results_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_set_system_results(
+ VL53L1_DEV Dev,
+ VL53L1_system_results_t *pdata);
+#endif
+
+
+/**
+ * @brief Gets system_results register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_system_results_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_system_results_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_system_results(
+ VL53L1_DEV Dev,
+ VL53L1_system_results_t *pdata);
+
+
+/**
+ * @brief Encodes data structure VL53L1_core_results_t into a I2C write buffer
+ *
+ * Buffer must be at least 33 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_core_results_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_encode_core_results(
+ VL53L1_core_results_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+#endif
+
+
+/**
+ * @brief Decodes data structure VL53L1_core_results_t from the input I2C read buffer
+ *
+ * Buffer must be at least 33 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_core_results_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_i2c_decode_core_results(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_core_results_t *pdata);
+
+
+/**
+ * @brief Sets core_results register group
+ *
+ * Serailises (encodes) VL53L1_core_results_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_core_results_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_set_core_results(
+ VL53L1_DEV Dev,
+ VL53L1_core_results_t *pdata);
+#endif
+
+
+/**
+ * @brief Gets core_results register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_core_results_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_core_results_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_get_core_results(
+ VL53L1_DEV Dev,
+ VL53L1_core_results_t *pdata);
+#endif
+
+
+/**
+ * @brief Encodes data structure VL53L1_debug_results_t into a I2C write buffer
+ *
+ * Buffer must be at least 56 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_debug_results_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_i2c_encode_debug_results(
+ VL53L1_debug_results_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+#endif
+
+/**
+ * @brief Decodes data structure VL53L1_debug_results_t from the input I2C read buffer
+ *
+ * Buffer must be at least 56 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_debug_results_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_i2c_decode_debug_results(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_debug_results_t *pdata);
+
+
+/**
+ * @brief Sets debug_results register group
+ *
+ * Serailises (encodes) VL53L1_debug_results_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_debug_results_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_set_debug_results(
+ VL53L1_DEV Dev,
+ VL53L1_debug_results_t *pdata);
+
+/**
+ * @brief Gets debug_results register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_debug_results_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_debug_results_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_debug_results(
+ VL53L1_DEV Dev,
+ VL53L1_debug_results_t *pdata);
+
+#endif
+
+/**
+ * @brief Encodes data structure VL53L1_nvm_copy_data_t into a I2C write buffer
+ *
+ * Buffer must be at least 49 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_nvm_copy_data_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_encode_nvm_copy_data(
+ VL53L1_nvm_copy_data_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+#endif
+
+
+/**
+ * @brief Decodes data structure VL53L1_nvm_copy_data_t from the input I2C read buffer
+ *
+ * Buffer must be at least 49 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_nvm_copy_data_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_i2c_decode_nvm_copy_data(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_nvm_copy_data_t *pdata);
+
+
+/**
+ * @brief Sets nvm_copy_data register group
+ *
+ * Serailises (encodes) VL53L1_nvm_copy_data_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_nvm_copy_data_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_set_nvm_copy_data(
+ VL53L1_DEV Dev,
+ VL53L1_nvm_copy_data_t *pdata);
+#endif
+
+
+/**
+ * @brief Gets nvm_copy_data register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_nvm_copy_data_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_nvm_copy_data_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_nvm_copy_data(
+ VL53L1_DEV Dev,
+ VL53L1_nvm_copy_data_t *pdata);
+
+
+/**
+ * @brief Encodes data structure VL53L1_prev_shadow_system_results_t into a I2C write buffer
+ *
+ * Buffer must be at least 44 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_prev_shadow_system_results_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_i2c_encode_prev_shadow_system_results(
+ VL53L1_prev_shadow_system_results_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes data structure VL53L1_prev_shadow_system_results_t from the input I2C read buffer
+ *
+ * Buffer must be at least 44 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_prev_shadow_system_results_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_i2c_decode_prev_shadow_system_results(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_prev_shadow_system_results_t *pdata);
+
+
+/**
+ * @brief Sets prev_shadow_system_results register group
+ *
+ * Serailises (encodes) VL53L1_prev_shadow_system_results_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_prev_shadow_system_results_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_prev_shadow_system_results(
+ VL53L1_DEV Dev,
+ VL53L1_prev_shadow_system_results_t *pdata);
+
+
+/**
+ * @brief Gets prev_shadow_system_results register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_prev_shadow_system_results_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_prev_shadow_system_results_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_prev_shadow_system_results(
+ VL53L1_DEV Dev,
+ VL53L1_prev_shadow_system_results_t *pdata);
+
+/**
+ * @brief Encodes data structure VL53L1_prev_shadow_core_results_t into a I2C write buffer
+ *
+ * Buffer must be at least 33 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_prev_shadow_core_results_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+VL53L1_Error VL53L1_i2c_encode_prev_shadow_core_results(
+ VL53L1_prev_shadow_core_results_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes data structure VL53L1_prev_shadow_core_results_t from the input I2C read buffer
+ *
+ * Buffer must be at least 33 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_prev_shadow_core_results_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_i2c_decode_prev_shadow_core_results(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_prev_shadow_core_results_t *pdata);
+
+
+/**
+ * @brief Sets prev_shadow_core_results register group
+ *
+ * Serailises (encodes) VL53L1_prev_shadow_core_results_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_prev_shadow_core_results_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_prev_shadow_core_results(
+ VL53L1_DEV Dev,
+ VL53L1_prev_shadow_core_results_t *pdata);
+
+
+/**
+ * @brief Gets prev_shadow_core_results register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_prev_shadow_core_results_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_prev_shadow_core_results_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+VL53L1_Error VL53L1_get_prev_shadow_core_results(
+ VL53L1_DEV Dev,
+ VL53L1_prev_shadow_core_results_t *pdata);
+
+
+/**
+ * @brief Encodes data structure VL53L1_patch_debug_t into a I2C write buffer
+ *
+ * Buffer must be at least 2 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_patch_debug_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+VL53L1_Error VL53L1_i2c_encode_patch_debug(
+ VL53L1_patch_debug_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes data structure VL53L1_patch_debug_t from the input I2C read buffer
+ *
+ * Buffer must be at least 2 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_patch_debug_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_i2c_decode_patch_debug(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_patch_debug_t *pdata);
+
+
+/**
+ * @brief Sets patch_debug register group
+ *
+ * Serailises (encodes) VL53L1_patch_debug_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_patch_debug_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_patch_debug(
+ VL53L1_DEV Dev,
+ VL53L1_patch_debug_t *pdata);
+
+
+/**
+ * @brief Gets patch_debug register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_patch_debug_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_patch_debug_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_patch_debug(
+ VL53L1_DEV Dev,
+ VL53L1_patch_debug_t *pdata);
+
+#endif
+
+/**
+ * @brief Encodes data structure VL53L1_gph_general_config_t into a I2C write buffer
+ *
+ * Buffer must be at least 5 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_gph_general_config_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_encode_gph_general_config(
+ VL53L1_gph_general_config_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+#endif
+
+
+/**
+ * @brief Decodes data structure VL53L1_gph_general_config_t from the input I2C read buffer
+ *
+ * Buffer must be at least 5 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_gph_general_config_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_decode_gph_general_config(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_gph_general_config_t *pdata);
+#endif
+
+
+/**
+ * @brief Sets gph_general_config register group
+ *
+ * Serailises (encodes) VL53L1_gph_general_config_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_gph_general_config_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_set_gph_general_config(
+ VL53L1_DEV Dev,
+ VL53L1_gph_general_config_t *pdata);
+#endif
+
+/**
+ * @brief Gets gph_general_config register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_gph_general_config_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_gph_general_config_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_get_gph_general_config(
+ VL53L1_DEV Dev,
+ VL53L1_gph_general_config_t *pdata);
+#endif
+
+
+/**
+ * @brief Encodes data structure VL53L1_gph_static_config_t into a I2C write buffer
+ *
+ * Buffer must be at least 6 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_gph_static_config_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_encode_gph_static_config(
+ VL53L1_gph_static_config_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+#endif
+
+
+/**
+ * @brief Decodes data structure VL53L1_gph_static_config_t from the input I2C read buffer
+ *
+ * Buffer must be at least 6 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_gph_static_config_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_decode_gph_static_config(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_gph_static_config_t *pdata);
+#endif
+
+
+/**
+ * @brief Sets gph_static_config register group
+ *
+ * Serailises (encodes) VL53L1_gph_static_config_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_gph_static_config_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_set_gph_static_config(
+ VL53L1_DEV Dev,
+ VL53L1_gph_static_config_t *pdata);
+#endif
+
+
+/**
+ * @brief Gets gph_static_config register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_gph_static_config_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_gph_static_config_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_get_gph_static_config(
+ VL53L1_DEV Dev,
+ VL53L1_gph_static_config_t *pdata);
+#endif
+
+
+/**
+ * @brief Encodes data structure VL53L1_gph_timing_config_t into a I2C write buffer
+ *
+ * Buffer must be at least 16 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_gph_timing_config_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_encode_gph_timing_config(
+ VL53L1_gph_timing_config_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+#endif
+
+
+/**
+ * @brief Decodes data structure VL53L1_gph_timing_config_t from the input I2C read buffer
+ *
+ * Buffer must be at least 16 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_gph_timing_config_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_decode_gph_timing_config(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_gph_timing_config_t *pdata);
+#endif
+
+
+/**
+ * @brief Sets gph_timing_config register group
+ *
+ * Serailises (encodes) VL53L1_gph_timing_config_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_gph_timing_config_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_set_gph_timing_config(
+ VL53L1_DEV Dev,
+ VL53L1_gph_timing_config_t *pdata);
+#endif
+
+
+/**
+ * @brief Gets gph_timing_config register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_gph_timing_config_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_gph_timing_config_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_get_gph_timing_config(
+ VL53L1_DEV Dev,
+ VL53L1_gph_timing_config_t *pdata);
+#endif
+
+
+/**
+ * @brief Encodes data structure VL53L1_fw_internal_t into a I2C write buffer
+ *
+ * Buffer must be at least 2 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_fw_internal_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_i2c_encode_fw_internal(
+ VL53L1_fw_internal_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes data structure VL53L1_fw_internal_t from the input I2C read buffer
+ *
+ * Buffer must be at least 2 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_fw_internal_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_i2c_decode_fw_internal(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_fw_internal_t *pdata);
+
+
+/**
+ * @brief Sets fw_internal register group
+ *
+ * Serailises (encodes) VL53L1_fw_internal_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_fw_internal_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_fw_internal(
+ VL53L1_DEV Dev,
+ VL53L1_fw_internal_t *pdata);
+
+
+/**
+ * @brief Gets fw_internal register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_fw_internal_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_fw_internal_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_fw_internal(
+ VL53L1_DEV Dev,
+ VL53L1_fw_internal_t *pdata);
+
+
+
+/**
+ * @brief Encodes data structure VL53L1_patch_results_t into a I2C write buffer
+ *
+ * Buffer must be at least 90 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_patch_results_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+VL53L1_Error VL53L1_i2c_encode_patch_results(
+ VL53L1_patch_results_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes data structure VL53L1_patch_results_t from the input I2C read buffer
+ *
+ * Buffer must be at least 90 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_patch_results_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_i2c_decode_patch_results(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_patch_results_t *pdata);
+
+
+/**
+ * @brief Sets patch_results register group
+ *
+ * Serailises (encodes) VL53L1_patch_results_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_patch_results_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_patch_results(
+ VL53L1_DEV Dev,
+ VL53L1_patch_results_t *pdata);
+
+
+/**
+ * @brief Gets patch_results register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_patch_results_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_patch_results_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_patch_results(
+ VL53L1_DEV Dev,
+ VL53L1_patch_results_t *pdata);
+#endif
+
+
+/**
+ * @brief Encodes data structure VL53L1_shadow_system_results_t into a I2C write buffer
+ *
+ * Buffer must be at least 82 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_shadow_system_results_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_i2c_encode_shadow_system_results(
+ VL53L1_shadow_system_results_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes data structure VL53L1_shadow_system_results_t from the input I2C read buffer
+ *
+ * Buffer must be at least 82 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_shadow_system_results_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_i2c_decode_shadow_system_results(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_shadow_system_results_t *pdata);
+
+
+/**
+ * @brief Sets shadow_system_results register group
+ *
+ * Serailises (encodes) VL53L1_shadow_system_results_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_shadow_system_results_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_shadow_system_results(
+ VL53L1_DEV Dev,
+ VL53L1_shadow_system_results_t *pdata);
+
+
+/**
+ * @brief Gets shadow_system_results register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_shadow_system_results_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_shadow_system_results_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_shadow_system_results(
+ VL53L1_DEV Dev,
+ VL53L1_shadow_system_results_t *pdata);
+
+
+/**
+ * @brief Encodes data structure VL53L1_shadow_core_results_t into a I2C write buffer
+ *
+ * Buffer must be at least 33 bytes
+ *
+ * @param[in] pdata : pointer to VL53L1_shadow_core_results_t data structure
+ * @param[in] buf_size : size of input buffer
+ * @param[out] pbuffer : uint8_t buffer to write serialised data into (I2C Write Buffer)
+ */
+
+VL53L1_Error VL53L1_i2c_encode_shadow_core_results(
+ VL53L1_shadow_core_results_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer);
+
+
+/**
+ * @brief Decodes data structure VL53L1_shadow_core_results_t from the input I2C read buffer
+ *
+ * Buffer must be at least 33 bytes
+ *
+ * @param[in] buf_size : size of input buffer
+ * @param[in] pbuffer : uint8_t buffer contain input serialised data (I2C read buffer)
+ * @param[out] pdata : pointer to VL53L1_shadow_core_results_t data structure
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_i2c_decode_shadow_core_results(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_shadow_core_results_t *pdata);
+
+
+/**
+ * @brief Sets shadow_core_results register group
+ *
+ * Serailises (encodes) VL53L1_shadow_core_results_t structure into a I2C write data buffer
+ * and sends the buffer to the device via a multi byte I2C write transaction
+ *
+ * @param[in] Dev : device handle
+ * @param[in] pdata : pointer to VL53L1_shadow_core_results_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_set_shadow_core_results(
+ VL53L1_DEV Dev,
+ VL53L1_shadow_core_results_t *pdata);
+
+
+/**
+ * @brief Gets shadow_core_results register group
+ *
+ * Reads register info from the device via a multi byte I2C read transaction and
+ * deserialises (decodes) the data into the VL53L1_shadow_core_results_t structure
+ *
+ * @param[in] Dev : device handle
+ * @param[out] pdata : pointer to VL53L1_shadow_core_results_t
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_get_shadow_core_results(
+ VL53L1_DEV Dev,
+ VL53L1_shadow_core_results_t *pdata);
+#endif
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
+
diff --git a/src/lib/vl53l1/core/inc/vl53l1_register_map.h b/src/lib/vl53l1/core/inc/vl53l1_register_map.h
new file mode 100644
index 0000000000..a551bbdd7b
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_register_map.h
@@ -0,0 +1,11864 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+******************************************************************************/
+
+/**
+ * @file vl53l1_register_map.h
+ * @brief VL53L1 Register Map definitions
+ */
+
+#ifndef _VL53L1_REGISTER_MAP_H_
+#define _VL53L1_REGISTER_MAP_H_
+
+/** @defgroup VL53L1_register_DefineRegisters_group Define Registers * @brief List of all the defined registers
+ * @{
+ */
+
+#define VL53L1_SOFT_RESET 0x0000
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_I2C_SLAVE__DEVICE_ADDRESS 0x0001
+/*!<
+ type: uint8_t \n
+ default: EWOK_I2C_DEV_ADDR_DEFAULT \n
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_nvm_managed', 'system_config']
+
+ fields: \n
+ - [6:0] = i2c_slave_device_address
+*/
+#define VL53L1_ANA_CONFIG__VHV_REF_SEL_VDDPIX 0x0002
+/*!<
+ type: uint8_t \n
+ default: 0x02 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_nvm_managed', 'analog_config']
+
+ fields: \n
+ - [3:0] = ref_sel_vddpix
+*/
+#define VL53L1_ANA_CONFIG__VHV_REF_SEL_VQUENCH 0x0003
+/*!<
+ type: uint8_t \n
+ default: 0x10 \n
+ info: \n
+ - msb = 6
+ - lsb = 3
+ - i2c_size = 1
+
+ groups: \n
+ ['static_nvm_managed', 'analog_config']
+
+ fields: \n
+ - [6:3] = ref_sel_vquench
+*/
+#define VL53L1_ANA_CONFIG__REG_AVDD1V2_SEL 0x0004
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_nvm_managed', 'analog_config']
+
+ fields: \n
+ - [1:0] = reg_avdd1v2_sel
+*/
+#define VL53L1_ANA_CONFIG__FAST_OSC__TRIM 0x0005
+/*!<
+ type: uint8_t \n
+ default: 0x48 \n
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_nvm_managed', 'analog_config']
+
+ fields: \n
+ - [6:0] = fast_osc_trim
+*/
+#define VL53L1_OSC_MEASURED__FAST_OSC__FREQUENCY 0x0006
+/*!<
+ type: uint16_t \n
+ default: OSC_FREQUENCY \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['static_nvm_managed', 'analog_config']
+
+ fields: \n
+ - [15:0] = osc_frequency (fixed point 4.12)
+*/
+#define VL53L1_OSC_MEASURED__FAST_OSC__FREQUENCY_HI 0x0006
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_OSC_MEASURED__FAST_OSC__FREQUENCY_LO 0x0007
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_VHV_CONFIG__TIMEOUT_MACROP_LOOP_BOUND 0x0008
+/*!<
+ type: uint8_t \n
+ default: 0x81 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_nvm_managed', 'vhv_config']
+
+ fields: \n
+ - [1:0] = vhv_timeout__macrop
+ - [7:2] = vhv_loop_bound
+*/
+#define VL53L1_VHV_CONFIG__COUNT_THRESH 0x0009
+/*!<
+ type: uint8_t \n
+ default: 0x80 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_nvm_managed', 'vhv_config']
+
+ fields: \n
+ - [7:0] = vhv_count_thresh
+*/
+#define VL53L1_VHV_CONFIG__OFFSET 0x000A
+/*!<
+ type: uint8_t \n
+ default: 0x07 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_nvm_managed', 'vhv_config']
+
+ fields: \n
+ - [5:0] = vhv_step_val
+*/
+#define VL53L1_VHV_CONFIG__INIT 0x000B
+/*!<
+ type: uint8_t \n
+ default: 0x20 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_nvm_managed', 'vhv_config']
+
+ fields: \n
+ - [7] = vhv0_init_enable
+ - [5:0] = vhv0_init_value
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_REF_0 0x000D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['customer_nvm_managed', 'ref_spad_en']
+
+ fields: \n
+ - [7:0] = spad_enables_ref_0
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_REF_1 0x000E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['customer_nvm_managed', 'ref_spad_en']
+
+ fields: \n
+ - [7:0] = spad_enables_ref_1
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_REF_2 0x000F
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['customer_nvm_managed', 'ref_spad_en']
+
+ fields: \n
+ - [7:0] = spad_enables_ref_2
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_REF_3 0x0010
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['customer_nvm_managed', 'ref_spad_en']
+
+ fields: \n
+ - [7:0] = spad_enables_ref_3
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_REF_4 0x0011
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['customer_nvm_managed', 'ref_spad_en']
+
+ fields: \n
+ - [7:0] = spad_enables_ref_4
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_REF_5 0x0012
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['customer_nvm_managed', 'ref_spad_en']
+
+ fields: \n
+ - [3:0] = spad_enables_ref_5
+*/
+#define VL53L1_GLOBAL_CONFIG__REF_EN_START_SELECT 0x0013
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['customer_nvm_managed', 'ref_spad_start']
+
+ fields: \n
+ - [7:0] = ref_en_start_select
+*/
+#define VL53L1_REF_SPAD_MAN__NUM_REQUESTED_REF_SPADS 0x0014
+/*!<
+ type: uint8_t \n
+ default: 0x2C \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['customer_nvm_managed', 'ref_spad_config']
+
+ fields: \n
+ - [5:0] = ref_spad_man__num_requested_ref_spad
+*/
+#define VL53L1_REF_SPAD_MAN__REF_LOCATION 0x0015
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['customer_nvm_managed', 'ref_spad_config']
+
+ fields: \n
+ - [1:0] = ref_spad_man__ref_location
+*/
+#define VL53L1_ALGO__CROSSTALK_COMPENSATION_PLANE_OFFSET_KCPS 0x0016
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['customer_nvm_managed', 'algo_config']
+
+ fields: \n
+ - [15:0] = crosstalk_compensation_plane_offset_kcps (fixed point 7.9)
+*/
+#define VL53L1_ALGO__CROSSTALK_COMPENSATION_PLANE_OFFSET_KCPS_HI 0x0016
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_ALGO__CROSSTALK_COMPENSATION_PLANE_OFFSET_KCPS_LO 0x0017
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_ALGO__CROSSTALK_COMPENSATION_X_PLANE_GRADIENT_KCPS 0x0018
+/*!<
+ type: int16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['customer_nvm_managed', 'algo_config']
+
+ fields: \n
+ - [15:0] = crosstalk_compensation_x_plane_gradient_kcps (fixed point 5.11)
+*/
+#define VL53L1_ALGO__CROSSTALK_COMPENSATION_X_PLANE_GRADIENT_KCPS_HI 0x0018
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_ALGO__CROSSTALK_COMPENSATION_X_PLANE_GRADIENT_KCPS_LO 0x0019
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_ALGO__CROSSTALK_COMPENSATION_Y_PLANE_GRADIENT_KCPS 0x001A
+/*!<
+ type: int16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['customer_nvm_managed', 'algo_config']
+
+ fields: \n
+ - [15:0] = crosstalk_compensation_y_plane_gradient_kcps (fixed point 5.11)
+*/
+#define VL53L1_ALGO__CROSSTALK_COMPENSATION_Y_PLANE_GRADIENT_KCPS_HI 0x001A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_ALGO__CROSSTALK_COMPENSATION_Y_PLANE_GRADIENT_KCPS_LO 0x001B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_REF_SPAD_CHAR__TOTAL_RATE_TARGET_MCPS 0x001C
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['customer_nvm_managed', 'ref_spad_char']
+
+ fields: \n
+ - [15:0] = ref_spad_char__total_rate_target_mcps (fixed point 9.7)
+*/
+#define VL53L1_REF_SPAD_CHAR__TOTAL_RATE_TARGET_MCPS_HI 0x001C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_REF_SPAD_CHAR__TOTAL_RATE_TARGET_MCPS_LO 0x001D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_ALGO__PART_TO_PART_RANGE_OFFSET_MM 0x001E
+/*!<
+ type: int16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 12
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['customer_nvm_managed', 'algo_config']
+
+ fields: \n
+ - [12:0] = part_to_part_offset_mm (fixed point 11.2)
+*/
+#define VL53L1_ALGO__PART_TO_PART_RANGE_OFFSET_MM_HI 0x001E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_ALGO__PART_TO_PART_RANGE_OFFSET_MM_LO 0x001F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MM_CONFIG__INNER_OFFSET_MM 0x0020
+/*!<
+ type: int16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['customer_nvm_managed', 'mm_config']
+
+ fields: \n
+ - [15:0] = mm_config__inner_offset_mm
+*/
+#define VL53L1_MM_CONFIG__INNER_OFFSET_MM_HI 0x0020
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MM_CONFIG__INNER_OFFSET_MM_LO 0x0021
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MM_CONFIG__OUTER_OFFSET_MM 0x0022
+/*!<
+ type: int16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['customer_nvm_managed', 'mm_config']
+
+ fields: \n
+ - [15:0] = mm_config__outer_offset_mm
+*/
+#define VL53L1_MM_CONFIG__OUTER_OFFSET_MM_HI 0x0022
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MM_CONFIG__OUTER_OFFSET_MM_LO 0x0023
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_DSS_CONFIG__TARGET_TOTAL_RATE_MCPS 0x0024
+/*!<
+ type: uint16_t \n
+ default: 0x0380 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['static_config', 'dss_config']
+
+ fields: \n
+ - [15:0] = dss_config__target_total_rate_mcps (fixed point 9.7)
+*/
+#define VL53L1_DSS_CONFIG__TARGET_TOTAL_RATE_MCPS_HI 0x0024
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_DSS_CONFIG__TARGET_TOTAL_RATE_MCPS_LO 0x0025
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_DEBUG__CTRL 0x0026
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'debug_config']
+
+ fields: \n
+ - [0] = enable_result_logging
+*/
+#define VL53L1_TEST_MODE__CTRL 0x0027
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'test_mode_config']
+
+ fields: \n
+ - [3:0] = test_mode__cmd
+*/
+#define VL53L1_CLK_GATING__CTRL 0x0028
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'clk_config']
+
+ fields: \n
+ - [0] = clk_gate_en__mcu_bank
+ - [1] = clk_gate_en__mcu_patch_ctrl
+ - [2] = clk_gate_en__mcu_timers
+ - [3] = clk_gate_en__mcu_mult_div
+*/
+#define VL53L1_NVM_BIST__CTRL 0x0029
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 4
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'nvm_bist_config']
+
+ fields: \n
+ - [2:0] = nvm_bist__cmd
+ - [4] = nvm_bist__ctrl
+*/
+#define VL53L1_NVM_BIST__NUM_NVM_WORDS 0x002A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'nvm_bist_config']
+
+ fields: \n
+ - [6:0] = nvm_bist__num_nvm_words
+*/
+#define VL53L1_NVM_BIST__START_ADDRESS 0x002B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'nvm_bist_config']
+
+ fields: \n
+ - [6:0] = nvm_bist__start_address
+*/
+#define VL53L1_HOST_IF__STATUS 0x002C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'system_status']
+
+ fields: \n
+ - [0] = host_interface
+*/
+#define VL53L1_PAD_I2C_HV__CONFIG 0x002D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'gpio_config']
+
+ fields: \n
+ - [0] = pad_scl_sda__vmodeint_hv
+ - [1] = i2c_pad__test_hv
+ - [2] = pad_scl__fpen_hv
+ - [4:3] = pad_scl__progdel_hv
+ - [5] = pad_sda__fpen_hv
+ - [7:6] = pad_sda__progdel_hv
+*/
+#define VL53L1_PAD_I2C_HV__EXTSUP_CONFIG 0x002E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'gpio_config']
+
+ fields: \n
+ - [0] = pad_scl_sda__extsup_hv
+*/
+#define VL53L1_GPIO_HV_PAD__CTRL 0x002F
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'gpio_config']
+
+ fields: \n
+ - [0] = gpio__extsup_hv
+ - [1] = gpio__vmodeint_hv
+*/
+#define VL53L1_GPIO_HV_MUX__CTRL 0x0030
+/*!<
+ type: uint8_t \n
+ default: 0x11 \n
+ info: \n
+ - msb = 4
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'gpio_config']
+
+ fields: \n
+ - [3:0] = gpio__mux_select_hv
+ - [4] = gpio__mux_active_high_hv
+*/
+#define VL53L1_GPIO__TIO_HV_STATUS 0x0031
+/*!<
+ type: uint8_t \n
+ default: 0x02 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'gpio_config']
+
+ fields: \n
+ - [0] = gpio__tio_hv
+ - [1] = fresh_out_of_reset
+*/
+#define VL53L1_GPIO__FIO_HV_STATUS 0x0032
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 1
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'gpio_config']
+
+ fields: \n
+ - [1] = gpio__fio_hv
+*/
+#define VL53L1_ANA_CONFIG__SPAD_SEL_PSWIDTH 0x0033
+/*!<
+ type: uint8_t \n
+ default: 0x02 \n
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'analog_config']
+
+ fields: \n
+ - [2:0] = spad_sel_pswidth
+*/
+#define VL53L1_ANA_CONFIG__VCSEL_PULSE_WIDTH_OFFSET 0x0034
+/*!<
+ type: uint8_t \n
+ default: 0x08 \n
+ info: \n
+ - msb = 4
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'analog_config']
+
+ fields: \n
+ - [4:0] = vcsel_pulse_width_offset (fixed point 1.4)
+*/
+#define VL53L1_ANA_CONFIG__FAST_OSC__CONFIG_CTRL 0x0035
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'analog_config']
+
+ fields: \n
+ - [0] = osc_config__latch_bypass
+*/
+#define VL53L1_SIGMA_ESTIMATOR__EFFECTIVE_PULSE_WIDTH_NS 0x0036
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'algo_config']
+
+ fields: \n
+ - [7:0] = sigma_estimator__eff_pulse_width
+*/
+#define VL53L1_SIGMA_ESTIMATOR__EFFECTIVE_AMBIENT_WIDTH_NS 0x0037
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'algo_config']
+
+ fields: \n
+ - [7:0] = sigma_estimator__eff_ambient_width
+*/
+#define VL53L1_SIGMA_ESTIMATOR__SIGMA_REF_MM 0x0038
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'algo_config']
+
+ fields: \n
+ - [7:0] = sigma_estimator__sigma_ref
+*/
+#define VL53L1_ALGO__CROSSTALK_COMPENSATION_VALID_HEIGHT_MM 0x0039
+/*!<
+ type: uint8_t \n
+ default: 0x14 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'algo_config']
+
+ fields: \n
+ - [7:0] = crosstalk_compensation_valid_height_mm
+*/
+#define VL53L1_SPARE_HOST_CONFIG__STATIC_CONFIG_SPARE_0 0x003A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'algo_config']
+
+ fields: \n
+ - [7:0] = static_config_spare_0
+*/
+#define VL53L1_SPARE_HOST_CONFIG__STATIC_CONFIG_SPARE_1 0x003B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'algo_config']
+
+ fields: \n
+ - [7:0] = static_config_spare_1
+*/
+#define VL53L1_ALGO__RANGE_IGNORE_THRESHOLD_MCPS 0x003C
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['static_config', 'algo_config']
+
+ fields: \n
+ - [15:0] = range_ignore_thresh_mcps (fixed point 3.13)
+*/
+#define VL53L1_ALGO__RANGE_IGNORE_THRESHOLD_MCPS_HI 0x003C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_ALGO__RANGE_IGNORE_THRESHOLD_MCPS_LO 0x003D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_ALGO__RANGE_IGNORE_VALID_HEIGHT_MM 0x003E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'algo_config']
+
+ fields: \n
+ - [7:0] = range_ignore_height_mm
+*/
+#define VL53L1_ALGO__RANGE_MIN_CLIP 0x003F
+/*!<
+ type: uint8_t \n
+ default: 0x8D \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'algo_config']
+
+ fields: \n
+ - [0] = algo__range_min_clip_enable
+ - [7:1] = algo__range_min_clip_value_mm
+*/
+#define VL53L1_ALGO__CONSISTENCY_CHECK__TOLERANCE 0x0040
+/*!<
+ type: uint8_t \n
+ default: 0x08 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'algo_config']
+
+ fields: \n
+ - [3:0] = consistency_check_tolerance (fixed point 1.3)
+*/
+#define VL53L1_SPARE_HOST_CONFIG__STATIC_CONFIG_SPARE_2 0x0041
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'algo_config']
+
+ fields: \n
+ - [7:0] = static_config_spare_2
+*/
+#define VL53L1_SD_CONFIG__RESET_STAGES_MSB 0x0042
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'sigmadelta_config']
+
+ fields: \n
+ - [3:0] = loop_init__clear_stage
+*/
+#define VL53L1_SD_CONFIG__RESET_STAGES_LSB 0x0043
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['static_config', 'sigmadelta_config']
+
+ fields: \n
+ - [7:4] = accum_reset__clear_stage
+ - [3:0] = count_reset__clear_stage
+*/
+#define VL53L1_GPH_CONFIG__STREAM_COUNT_UPDATE_VALUE 0x0044
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['general_config', 'roi_config']
+
+ fields: \n
+ - [7:0] = stream_count_update_value
+*/
+#define VL53L1_GLOBAL_CONFIG__STREAM_DIVIDER 0x0045
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['general_config', 'roi_config']
+
+ fields: \n
+ - [7:0] = stream_count_internal_div
+*/
+#define VL53L1_SYSTEM__INTERRUPT_CONFIG_GPIO 0x0046
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['general_config', 'gph_config']
+
+ fields: \n
+ - [1:0] = int_mode_distance
+ - [3:2] = int_mode_rate
+ - [4] = int_spare
+ - [5] = int_new_measure_ready
+ - [6] = int_no_target_en
+ - [7] = int_combined_mode
+*/
+#define VL53L1_CAL_CONFIG__VCSEL_START 0x0047
+/*!<
+ type: uint8_t \n
+ default: 0x0B \n
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['general_config', 'cal_config']
+
+ fields: \n
+ - [6:0] = cal_config__vcsel_start
+*/
+#define VL53L1_CAL_CONFIG__REPEAT_RATE 0x0048
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 11
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['general_config', 'cal_config']
+
+ fields: \n
+ - [11:0] = cal_config__repeat_rate
+*/
+#define VL53L1_CAL_CONFIG__REPEAT_RATE_HI 0x0048
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_CAL_CONFIG__REPEAT_RATE_LO 0x0049
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_GLOBAL_CONFIG__VCSEL_WIDTH 0x004A
+/*!<
+ type: uint8_t \n
+ default: 0x02 \n
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['general_config', 'global_config']
+
+ fields: \n
+ - [6:0] = global_config__vcsel_width
+*/
+#define VL53L1_PHASECAL_CONFIG__TIMEOUT_MACROP 0x004B
+/*!<
+ type: uint8_t \n
+ default: 0x04 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['general_config', 'phasecal_config']
+
+ fields: \n
+ - [7:0] = phasecal_config__timeout_macrop
+*/
+#define VL53L1_PHASECAL_CONFIG__TARGET 0x004C
+/*!<
+ type: uint8_t \n
+ default: 0x21 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['general_config', 'phasecal_config']
+
+ fields: \n
+ - [7:0] = algo_phasecal_lim
+*/
+#define VL53L1_PHASECAL_CONFIG__OVERRIDE 0x004D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['general_config', 'phasecal_config']
+
+ fields: \n
+ - [0] = phasecal_config__override
+*/
+#define VL53L1_DSS_CONFIG__ROI_MODE_CONTROL 0x004F
+/*!<
+ type: uint8_t \n
+ default: 0x01 \n
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['general_config', 'dss_config']
+
+ fields: \n
+ - [1:0] = dss_config__input_mode
+ - [2] = calculate_roi_enable
+*/
+#define VL53L1_SYSTEM__THRESH_RATE_HIGH 0x0050
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['general_config', 'gph_config']
+
+ fields: \n
+ - [15:0] = thresh_rate_high (fixed point 9.7)
+*/
+#define VL53L1_SYSTEM__THRESH_RATE_HIGH_HI 0x0050
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SYSTEM__THRESH_RATE_HIGH_LO 0x0051
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SYSTEM__THRESH_RATE_LOW 0x0052
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['general_config', 'gph_config']
+
+ fields: \n
+ - [15:0] = thresh_rate_low (fixed point 9.7)
+*/
+#define VL53L1_SYSTEM__THRESH_RATE_LOW_HI 0x0052
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SYSTEM__THRESH_RATE_LOW_LO 0x0053
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_DSS_CONFIG__MANUAL_EFFECTIVE_SPADS_SELECT 0x0054
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['general_config', 'dss_config']
+
+ fields: \n
+ - [15:0] = dss_config__manual_effective_spads_select
+*/
+#define VL53L1_DSS_CONFIG__MANUAL_EFFECTIVE_SPADS_SELECT_HI 0x0054
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_DSS_CONFIG__MANUAL_EFFECTIVE_SPADS_SELECT_LO 0x0055
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_DSS_CONFIG__MANUAL_BLOCK_SELECT 0x0056
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['general_config', 'dss_config']
+
+ fields: \n
+ - [7:0] = dss_config__manual_block_select
+*/
+#define VL53L1_DSS_CONFIG__APERTURE_ATTENUATION 0x0057
+/*!<
+ type: uint8_t \n
+ default: 0x33 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['general_config', 'dss_config']
+
+ fields: \n
+ - [7:0] = dss_config__aperture_attenuation
+*/
+#define VL53L1_DSS_CONFIG__MAX_SPADS_LIMIT 0x0058
+/*!<
+ type: uint8_t \n
+ default: 0xFF \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['general_config', 'dss_config']
+
+ fields: \n
+ - [7:0] = dss_config__max_spads_limit
+*/
+#define VL53L1_DSS_CONFIG__MIN_SPADS_LIMIT 0x0059
+/*!<
+ type: uint8_t \n
+ default: 0x01 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['general_config', 'dss_config']
+
+ fields: \n
+ - [7:0] = dss_config__min_spads_limit
+*/
+#define VL53L1_MM_CONFIG__TIMEOUT_MACROP_A_HI 0x005A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['timing_config', 'mm_config']
+
+ fields: \n
+ - [3:0] = mm_config__config_timeout_macrop_a_hi
+*/
+#define VL53L1_MM_CONFIG__TIMEOUT_MACROP_A_LO 0x005B
+/*!<
+ type: uint8_t \n
+ default: 0x06 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['timing_config', 'mm_config']
+
+ fields: \n
+ - [7:0] = mm_config__config_timeout_macrop_a_lo
+*/
+#define VL53L1_MM_CONFIG__TIMEOUT_MACROP_B_HI 0x005C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['timing_config', 'mm_config']
+
+ fields: \n
+ - [3:0] = mm_config__config_timeout_macrop_b_hi
+*/
+#define VL53L1_MM_CONFIG__TIMEOUT_MACROP_B_LO 0x005D
+/*!<
+ type: uint8_t \n
+ default: 0x06 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['timing_config', 'mm_config']
+
+ fields: \n
+ - [7:0] = mm_config__config_timeout_macrop_b_lo
+*/
+#define VL53L1_RANGE_CONFIG__TIMEOUT_MACROP_A_HI 0x005E
+/*!<
+ type: uint8_t \n
+ default: 0x01 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['timing_config', 'range_config']
+
+ fields: \n
+ - [3:0] = range_timeout_overall_periods_macrop_a_hi
+*/
+#define VL53L1_RANGE_CONFIG__TIMEOUT_MACROP_A_LO 0x005F
+/*!<
+ type: uint8_t \n
+ default: 0x92 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['timing_config', 'range_config']
+
+ fields: \n
+ - [7:0] = range_timeout_overall_periods_macrop_a_lo
+*/
+#define VL53L1_RANGE_CONFIG__VCSEL_PERIOD_A 0x0060
+/*!<
+ type: uint8_t \n
+ default: 0x0B \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['timing_config', 'range_config']
+
+ fields: \n
+ - [5:0] = range_config__vcsel_period_a
+*/
+#define VL53L1_RANGE_CONFIG__TIMEOUT_MACROP_B_HI 0x0061
+/*!<
+ type: uint8_t \n
+ default: 0x01 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['timing_config', 'range_config']
+
+ fields: \n
+ - [3:0] = range_timeout_overall_periods_macrop_b_hi
+*/
+#define VL53L1_RANGE_CONFIG__TIMEOUT_MACROP_B_LO 0x0062
+/*!<
+ type: uint8_t \n
+ default: 0x92 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['timing_config', 'range_config']
+
+ fields: \n
+ - [7:0] = range_timeout_overall_periods_macrop_b_lo
+*/
+#define VL53L1_RANGE_CONFIG__VCSEL_PERIOD_B 0x0063
+/*!<
+ type: uint8_t \n
+ default: 0x09 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['timing_config', 'range_config']
+
+ fields: \n
+ - [5:0] = range_config__vcsel_period_b
+*/
+#define VL53L1_RANGE_CONFIG__SIGMA_THRESH 0x0064
+/*!<
+ type: uint16_t \n
+ default: 0x0080 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['timing_config', 'range_config']
+
+ fields: \n
+ - [15:0] = range_config__sigma_thresh (fixed point 14.2)
+*/
+#define VL53L1_RANGE_CONFIG__SIGMA_THRESH_HI 0x0064
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGE_CONFIG__SIGMA_THRESH_LO 0x0065
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGE_CONFIG__MIN_COUNT_RATE_RTN_LIMIT_MCPS 0x0066
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['timing_config', 'range_config']
+
+ fields: \n
+ - [15:0] = range_config__min_count_rate_rtn_limit_mcps (fixed point 9.7)
+*/
+#define VL53L1_RANGE_CONFIG__MIN_COUNT_RATE_RTN_LIMIT_MCPS_HI 0x0066
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGE_CONFIG__MIN_COUNT_RATE_RTN_LIMIT_MCPS_LO 0x0067
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGE_CONFIG__VALID_PHASE_LOW 0x0068
+/*!<
+ type: uint8_t \n
+ default: 0x08 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['timing_config', 'range_config']
+
+ fields: \n
+ - [7:0] = range_config__valid_phase_low (fixed point 5.3)
+*/
+#define VL53L1_RANGE_CONFIG__VALID_PHASE_HIGH 0x0069
+/*!<
+ type: uint8_t \n
+ default: 0x80 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['timing_config', 'range_config']
+
+ fields: \n
+ - [7:0] = range_config__valid_phase_high (fixed point 5.3)
+*/
+#define VL53L1_SYSTEM__INTERMEASUREMENT_PERIOD 0x006C
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['timing_config', 'system_config']
+
+ fields: \n
+ - [31:0] = intermeasurement_period
+*/
+#define VL53L1_SYSTEM__INTERMEASUREMENT_PERIOD_3 0x006C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SYSTEM__INTERMEASUREMENT_PERIOD_2 0x006D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SYSTEM__INTERMEASUREMENT_PERIOD_1 0x006E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SYSTEM__INTERMEASUREMENT_PERIOD_0 0x006F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SYSTEM__FRACTIONAL_ENABLE 0x0070
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['timing_config', 'system_config']
+
+ fields: \n
+ - [0] = range_fractional_enable
+*/
+#define VL53L1_SYSTEM__GROUPED_PARAMETER_HOLD_0 0x0071
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['dynamic_config', 'gph_config']
+
+ fields: \n
+ - [0] = grouped_parameter_hold
+ - [1] = grouped_parameter_hold_id
+*/
+#define VL53L1_SYSTEM__THRESH_HIGH 0x0072
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['dynamic_config', 'gph_config']
+
+ fields: \n
+ - [15:0] = thresh_high
+*/
+#define VL53L1_SYSTEM__THRESH_HIGH_HI 0x0072
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SYSTEM__THRESH_HIGH_LO 0x0073
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SYSTEM__THRESH_LOW 0x0074
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['dynamic_config', 'gph_config']
+
+ fields: \n
+ - [15:0] = thresh_low
+*/
+#define VL53L1_SYSTEM__THRESH_LOW_HI 0x0074
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SYSTEM__THRESH_LOW_LO 0x0075
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SYSTEM__ENABLE_XTALK_PER_QUADRANT 0x0076
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['dynamic_config', 'gph_config']
+
+ fields: \n
+ - [0] = system__enable_xtalk_per_quadrant
+*/
+#define VL53L1_SYSTEM__SEED_CONFIG 0x0077
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['dynamic_config', 'gph_config']
+
+ fields: \n
+ - [1:0] = system__seed_config
+ - [2] = system__fw_pause_ctrl
+*/
+#define VL53L1_SD_CONFIG__WOI_SD0 0x0078
+/*!<
+ type: uint8_t \n
+ default: 0x04 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['dynamic_config', 'gph_config']
+
+ fields: \n
+ - [7:0] = sd_config__woi_sd0
+*/
+#define VL53L1_SD_CONFIG__WOI_SD1 0x0079
+/*!<
+ type: uint8_t \n
+ default: 0x04 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['dynamic_config', 'gph_config']
+
+ fields: \n
+ - [7:0] = sd_config__woi_sd1
+*/
+#define VL53L1_SD_CONFIG__INITIAL_PHASE_SD0 0x007A
+/*!<
+ type: uint8_t \n
+ default: 0x03 \n
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['dynamic_config', 'gph_config']
+
+ fields: \n
+ - [6:0] = sd_config__initial_phase_sd0
+*/
+#define VL53L1_SD_CONFIG__INITIAL_PHASE_SD1 0x007B
+/*!<
+ type: uint8_t \n
+ default: 0x03 \n
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['dynamic_config', 'gph_config']
+
+ fields: \n
+ - [6:0] = sd_config__initial_phase_sd1
+*/
+#define VL53L1_SYSTEM__GROUPED_PARAMETER_HOLD_1 0x007C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['dynamic_config', 'gph_config']
+
+ fields: \n
+ - [0] = grouped_parameter_hold
+ - [1] = grouped_parameter_hold_id
+*/
+#define VL53L1_SD_CONFIG__FIRST_ORDER_SELECT 0x007D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['dynamic_config', 'gph_config']
+
+ fields: \n
+ - [0] = sd_config__first_order_select_rtn
+ - [1] = sd_config__first_order_select_ref
+*/
+#define VL53L1_SD_CONFIG__QUANTIFIER 0x007E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['dynamic_config', 'gph_config']
+
+ fields: \n
+ - [3:0] = sd_config__quantifier
+*/
+#define VL53L1_ROI_CONFIG__USER_ROI_CENTRE_SPAD 0x007F
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['dynamic_config', 'gph_config']
+
+ fields: \n
+ - [7:0] = user_roi_center_spad
+*/
+#define VL53L1_ROI_CONFIG__USER_ROI_REQUESTED_GLOBAL_XY_SIZE 0x0080
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['dynamic_config', 'gph_config']
+
+ fields: \n
+ - [7:0] = roi_config__user_roi_requested_global_xy_size
+*/
+#define VL53L1_SYSTEM__SEQUENCE_CONFIG 0x0081
+/*!<
+ type: uint8_t \n
+ default: 0xFF \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['dynamic_config', 'gph_config']
+
+ fields: \n
+ - [0] = sequence_vhv_en
+ - [1] = sequence_phasecal_en
+ - [2] = sequence_reference_phase_en
+ - [3] = sequence_dss1_en
+ - [4] = sequence_dss2_en
+ - [5] = sequence_mm1_en
+ - [6] = sequence_mm2_en
+ - [7] = sequence_range_en
+*/
+#define VL53L1_SYSTEM__GROUPED_PARAMETER_HOLD 0x0082
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['dynamic_config', 'gph_config']
+
+ fields: \n
+ - [0] = grouped_parameter_hold
+ - [1] = grouped_parameter_hold_id
+*/
+#define VL53L1_POWER_MANAGEMENT__GO1_POWER_FORCE 0x0083
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['system_control', 'pwrman_ctrl']
+
+ fields: \n
+ - [0] = go1_dig_powerforce
+*/
+#define VL53L1_SYSTEM__STREAM_COUNT_CTRL 0x0084
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['system_control', 'stream_ctrl']
+
+ fields: \n
+ - [0] = retain_stream_count
+*/
+#define VL53L1_FIRMWARE__ENABLE 0x0085
+/*!<
+ type: uint8_t \n
+ default: 0x01 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['system_control', 'firmware_ctrl']
+
+ fields: \n
+ - [0] = firmware_enable
+*/
+#define VL53L1_SYSTEM__INTERRUPT_CLEAR 0x0086
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['system_control', 'system_int_clr']
+
+ fields: \n
+ - [0] = sys_interrupt_clear_range
+ - [1] = sys_interrupt_clear_error
+*/
+#define VL53L1_SYSTEM__MODE_START 0x0087
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['system_control', 'system_start']
+
+ fields: \n
+ - [1:0] = scheduler_mode
+ - [3:2] = readout_mode
+ - [4] = mode_range__single_shot
+ - [5] = mode_range__back_to_back
+ - [6] = mode_range__timed
+ - [7] = mode_range__abort
+*/
+#define VL53L1_RESULT__INTERRUPT_STATUS 0x0088
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [2:0] = int_status
+ - [4:3] = int_error_status
+ - [5] = gph_id_gpio_status
+*/
+#define VL53L1_RESULT__RANGE_STATUS 0x0089
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [4:0] = range_status
+ - [5] = max_threshold_hit
+ - [6] = min_threshold_hit
+ - [7] = gph_id_range_status
+*/
+#define VL53L1_RESULT__REPORT_STATUS 0x008A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [3:0] = report_status
+*/
+#define VL53L1_RESULT__STREAM_COUNT 0x008B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [7:0] = result__stream_count
+*/
+#define VL53L1_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0 0x008C
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__dss_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+#define VL53L1_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0_HI 0x008C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0_LO 0x008D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD0 0x008E
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__peak_signal_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+#define VL53L1_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD0_HI 0x008E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD0_LO 0x008F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__AMBIENT_COUNT_RATE_MCPS_SD0 0x0090
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__ambient_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+#define VL53L1_RESULT__AMBIENT_COUNT_RATE_MCPS_SD0_HI 0x0090
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__AMBIENT_COUNT_RATE_MCPS_SD0_LO 0x0091
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__SIGMA_SD0 0x0092
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__sigma_sd0 (fixed point 14.2)
+*/
+#define VL53L1_RESULT__SIGMA_SD0_HI 0x0092
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__SIGMA_SD0_LO 0x0093
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__PHASE_SD0 0x0094
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__phase_sd0 (fixed point 5.11)
+*/
+#define VL53L1_RESULT__PHASE_SD0_HI 0x0094
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__PHASE_SD0_LO 0x0095
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0 0x0096
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__final_crosstalk_corrected_range_mm_sd0
+*/
+#define VL53L1_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0_HI 0x0096
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0_LO 0x0097
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__PEAK_SIGNAL_COUNT_RATE_CROSSTALK_CORRECTED_MCPS_SD0 0x0098
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0 (fixed point 9.7)
+*/
+#define VL53L1_RESULT__PEAK_SIGNAL_COUNT_RATE_CROSSTALK_CORRECTED_MCPS_SD0_HI 0x0098
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__PEAK_SIGNAL_COUNT_RATE_CROSSTALK_CORRECTED_MCPS_SD0_LO 0x0099
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__MM_INNER_ACTUAL_EFFECTIVE_SPADS_SD0 0x009A
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__mm_inner_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+#define VL53L1_RESULT__MM_INNER_ACTUAL_EFFECTIVE_SPADS_SD0_HI 0x009A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__MM_INNER_ACTUAL_EFFECTIVE_SPADS_SD0_LO 0x009B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__MM_OUTER_ACTUAL_EFFECTIVE_SPADS_SD0 0x009C
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__mm_outer_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+#define VL53L1_RESULT__MM_OUTER_ACTUAL_EFFECTIVE_SPADS_SD0_HI 0x009C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__MM_OUTER_ACTUAL_EFFECTIVE_SPADS_SD0_LO 0x009D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__AVG_SIGNAL_COUNT_RATE_MCPS_SD0 0x009E
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__avg_signal_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+#define VL53L1_RESULT__AVG_SIGNAL_COUNT_RATE_MCPS_SD0_HI 0x009E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__AVG_SIGNAL_COUNT_RATE_MCPS_SD0_LO 0x009F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD1 0x00A0
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__dss_actual_effective_spads_sd1 (fixed point 8.8)
+*/
+#define VL53L1_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD1_HI 0x00A0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD1_LO 0x00A1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD1 0x00A2
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__peak_signal_count_rate_mcps_sd1 (fixed point 9.7)
+*/
+#define VL53L1_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD1_HI 0x00A2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD1_LO 0x00A3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__AMBIENT_COUNT_RATE_MCPS_SD1 0x00A4
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__ambient_count_rate_mcps_sd1 (fixed point 9.7)
+*/
+#define VL53L1_RESULT__AMBIENT_COUNT_RATE_MCPS_SD1_HI 0x00A4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__AMBIENT_COUNT_RATE_MCPS_SD1_LO 0x00A5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__SIGMA_SD1 0x00A6
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__sigma_sd1 (fixed point 14.2)
+*/
+#define VL53L1_RESULT__SIGMA_SD1_HI 0x00A6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__SIGMA_SD1_LO 0x00A7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__PHASE_SD1 0x00A8
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__phase_sd1 (fixed point 5.11)
+*/
+#define VL53L1_RESULT__PHASE_SD1_HI 0x00A8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__PHASE_SD1_LO 0x00A9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD1 0x00AA
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__final_crosstalk_corrected_range_mm_sd1
+*/
+#define VL53L1_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD1_HI 0x00AA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD1_LO 0x00AB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__SPARE_0_SD1 0x00AC
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__spare_0_sd1
+*/
+#define VL53L1_RESULT__SPARE_0_SD1_HI 0x00AC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__SPARE_0_SD1_LO 0x00AD
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__SPARE_1_SD1 0x00AE
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__spare_1_sd1
+*/
+#define VL53L1_RESULT__SPARE_1_SD1_HI 0x00AE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__SPARE_1_SD1_LO 0x00AF
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__SPARE_2_SD1 0x00B0
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [15:0] = result__spare_2_sd1
+*/
+#define VL53L1_RESULT__SPARE_2_SD1_HI 0x00B0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__SPARE_2_SD1_LO 0x00B1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__SPARE_3_SD1 0x00B2
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [7:0] = result__spare_3_sd1
+*/
+#define VL53L1_RESULT__THRESH_INFO 0x00B3
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['system_results', 'results']
+
+ fields: \n
+ - [3:0] = result__distance_int_info
+ - [7:4] = result__rate_int_info
+*/
+#define VL53L1_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0 0x00B4
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = result_core__ambient_window_events_sd0
+*/
+#define VL53L1_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0_3 0x00B4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0_2 0x00B5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0_1 0x00B6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0_0 0x00B7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__RANGING_TOTAL_EVENTS_SD0 0x00B8
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = result_core__ranging_total_events_sd0
+*/
+#define VL53L1_RESULT_CORE__RANGING_TOTAL_EVENTS_SD0_3 0x00B8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__RANGING_TOTAL_EVENTS_SD0_2 0x00B9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__RANGING_TOTAL_EVENTS_SD0_1 0x00BA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__RANGING_TOTAL_EVENTS_SD0_0 0x00BB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD0 0x00BC
+/*!<
+ type: int32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = result_core__signal_total_events_sd0
+*/
+#define VL53L1_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD0_3 0x00BC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD0_2 0x00BD
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD0_1 0x00BE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD0_0 0x00BF
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD0 0x00C0
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = result_core__total_periods_elapsed_sd0
+*/
+#define VL53L1_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD0_3 0x00C0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD0_2 0x00C1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD0_1 0x00C2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD0_0 0x00C3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD1 0x00C4
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = result_core__ambient_window_events_sd1
+*/
+#define VL53L1_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD1_3 0x00C4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD1_2 0x00C5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD1_1 0x00C6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD1_0 0x00C7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__RANGING_TOTAL_EVENTS_SD1 0x00C8
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = result_core__ranging_total_events_sd1
+*/
+#define VL53L1_RESULT_CORE__RANGING_TOTAL_EVENTS_SD1_3 0x00C8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__RANGING_TOTAL_EVENTS_SD1_2 0x00C9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__RANGING_TOTAL_EVENTS_SD1_1 0x00CA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__RANGING_TOTAL_EVENTS_SD1_0 0x00CB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD1 0x00CC
+/*!<
+ type: int32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = result_core__signal_total_events_sd1
+*/
+#define VL53L1_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD1_3 0x00CC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD1_2 0x00CD
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD1_1 0x00CE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD1_0 0x00CF
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD1 0x00D0
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = result_core__total_periods_elapsed_sd1
+*/
+#define VL53L1_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD1_3 0x00D0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD1_2 0x00D1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD1_1 0x00D2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD1_0 0x00D3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT_CORE__SPARE_0 0x00D4
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['core_results', 'ranging_core_results']
+
+ fields: \n
+ - [7:0] = result_core__spare_0
+*/
+#define VL53L1_PHASECAL_RESULT__REFERENCE_PHASE 0x00D6
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['debug_results', 'phasecal_results']
+
+ fields: \n
+ - [15:0] = result_phasecal__reference_phase (fixed point 5.11)
+*/
+#define VL53L1_PHASECAL_RESULT__REFERENCE_PHASE_HI 0x00D6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PHASECAL_RESULT__REFERENCE_PHASE_LO 0x00D7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PHASECAL_RESULT__VCSEL_START 0x00D8
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'phasecal_results']
+
+ fields: \n
+ - [6:0] = result_phasecal__vcsel_start
+*/
+#define VL53L1_REF_SPAD_CHAR_RESULT__NUM_ACTUAL_REF_SPADS 0x00D9
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'ref_spad_status']
+
+ fields: \n
+ - [5:0] = ref_spad_char_result__num_actual_ref_spads
+*/
+#define VL53L1_REF_SPAD_CHAR_RESULT__REF_LOCATION 0x00DA
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'ref_spad_status']
+
+ fields: \n
+ - [1:0] = ref_spad_char_result__ref_location
+*/
+#define VL53L1_VHV_RESULT__COLDBOOT_STATUS 0x00DB
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'vhv_results']
+
+ fields: \n
+ - [0] = vhv_result__coldboot_status
+*/
+#define VL53L1_VHV_RESULT__SEARCH_RESULT 0x00DC
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'vhv_results']
+
+ fields: \n
+ - [5:0] = cp_sel_result
+*/
+#define VL53L1_VHV_RESULT__LATEST_SETTING 0x00DD
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'vhv_results']
+
+ fields: \n
+ - [5:0] = cp_sel_latest_setting
+*/
+#define VL53L1_RESULT__OSC_CALIBRATE_VAL 0x00DE
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 9
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['debug_results', 'misc_results']
+
+ fields: \n
+ - [9:0] = osc_calibrate_val
+*/
+#define VL53L1_RESULT__OSC_CALIBRATE_VAL_HI 0x00DE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RESULT__OSC_CALIBRATE_VAL_LO 0x00DF
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_ANA_CONFIG__POWERDOWN_GO1 0x00E0
+/*!<
+ type: uint8_t \n
+ default: 0x02 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'analog_config']
+
+ fields: \n
+ - [0] = go2_ref_bg_disable_avdd
+ - [1] = go2_regdvdd1v2_enable_avdd
+*/
+#define VL53L1_ANA_CONFIG__REF_BG_CTRL 0x00E1
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'analog_config']
+
+ fields: \n
+ - [0] = go2_ref_overdrvbg_avdd
+ - [1] = go2_ref_forcebgison_avdd
+*/
+#define VL53L1_ANA_CONFIG__REGDVDD1V2_CTRL 0x00E2
+/*!<
+ type: uint8_t \n
+ default: 0x01 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'analog_config']
+
+ fields: \n
+ - [0] = go2_regdvdd1v2_sel_pulldown_avdd
+ - [1] = go2_regdvdd1v2_sel_boost_avdd
+ - [3:2] = go2_regdvdd1v2_selv_avdd
+*/
+#define VL53L1_ANA_CONFIG__OSC_SLOW_CTRL 0x00E3
+/*!<
+ type: uint8_t \n
+ default: 0x02 \n
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'analog_config']
+
+ fields: \n
+ - [0] = osc_slow_en
+ - [1] = osc_slow_op_en
+ - [2] = osc_slow_freq_sel
+*/
+#define VL53L1_TEST_MODE__STATUS 0x00E4
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'test_mode_status']
+
+ fields: \n
+ - [0] = test_mode_status
+*/
+#define VL53L1_FIRMWARE__SYSTEM_STATUS 0x00E5
+/*!<
+ type: uint8_t \n
+ default: 0x02 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'firmware_status']
+
+ fields: \n
+ - [0] = firmware_bootup
+ - [1] = firmware_first_range
+*/
+#define VL53L1_FIRMWARE__MODE_STATUS 0x00E6
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'firmware_status']
+
+ fields: \n
+ - [7:0] = firmware_mode_status
+*/
+#define VL53L1_FIRMWARE__SECONDARY_MODE_STATUS 0x00E7
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'firmware_status']
+
+ fields: \n
+ - [7:0] = fw_secondary_mode_status
+*/
+#define VL53L1_FIRMWARE__CAL_REPEAT_RATE_COUNTER 0x00E8
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 11
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['debug_results', 'firmware_status']
+
+ fields: \n
+ - [11:0] = firmware_cal_repeat_rate
+*/
+#define VL53L1_FIRMWARE__CAL_REPEAT_RATE_COUNTER_HI 0x00E8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_FIRMWARE__CAL_REPEAT_RATE_COUNTER_LO 0x00E9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_FIRMWARE__HISTOGRAM_BIN 0x00EA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_GPH__SYSTEM__THRESH_HIGH 0x00EC
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['debug_results', 'gph_actual']
+
+ fields: \n
+ - [15:0] = shadow_thresh_high
+*/
+#define VL53L1_GPH__SYSTEM__THRESH_HIGH_HI 0x00EC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_GPH__SYSTEM__THRESH_HIGH_LO 0x00ED
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_GPH__SYSTEM__THRESH_LOW 0x00EE
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['debug_results', 'gph_actual']
+
+ fields: \n
+ - [15:0] = shadow_thresh_low
+*/
+#define VL53L1_GPH__SYSTEM__THRESH_LOW_HI 0x00EE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_GPH__SYSTEM__THRESH_LOW_LO 0x00EF
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_GPH__SYSTEM__ENABLE_XTALK_PER_QUADRANT 0x00F0
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'gph_actual']
+
+ fields: \n
+ - [0] = shadow__enable_xtalk_per_quadrant
+*/
+#define VL53L1_GPH__SPARE_0 0x00F1
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'gph_actual']
+
+ fields: \n
+ - [0] = fw_safe_to_disable
+ - [1] = shadow__spare_0
+ - [2] = shadow__spare_1
+*/
+#define VL53L1_GPH__SD_CONFIG__WOI_SD0 0x00F2
+/*!<
+ type: uint8_t \n
+ default: 0x04 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'gph_actual']
+
+ fields: \n
+ - [7:0] = shadow_sd_config__woi_sd0
+*/
+#define VL53L1_GPH__SD_CONFIG__WOI_SD1 0x00F3
+/*!<
+ type: uint8_t \n
+ default: 0x04 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'gph_actual']
+
+ fields: \n
+ - [7:0] = shadow_sd_config__woi_sd1
+*/
+#define VL53L1_GPH__SD_CONFIG__INITIAL_PHASE_SD0 0x00F4
+/*!<
+ type: uint8_t \n
+ default: 0x03 \n
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'gph_actual']
+
+ fields: \n
+ - [6:0] = shadow_sd_config__initial_phase_sd0
+*/
+#define VL53L1_GPH__SD_CONFIG__INITIAL_PHASE_SD1 0x00F5
+/*!<
+ type: uint8_t \n
+ default: 0x03 \n
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'gph_actual']
+
+ fields: \n
+ - [6:0] = shadow_sd_config__initial_phase_sd1
+*/
+#define VL53L1_GPH__SD_CONFIG__FIRST_ORDER_SELECT 0x00F6
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'gph_actual']
+
+ fields: \n
+ - [0] = shadow_sd_config__first_order_select_rtn
+ - [1] = shadow_sd_config__first_order_select_ref
+*/
+#define VL53L1_GPH__SD_CONFIG__QUANTIFIER 0x00F7
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'gph_actual']
+
+ fields: \n
+ - [3:0] = shadow_sd_config__quantifier
+*/
+#define VL53L1_GPH__ROI_CONFIG__USER_ROI_CENTRE_SPAD 0x00F8
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'gph_actual']
+
+ fields: \n
+ - [7:0] = shadow_user_roi_center_spad_q0
+*/
+#define VL53L1_GPH__ROI_CONFIG__USER_ROI_REQUESTED_GLOBAL_XY_SIZE 0x00F9
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'gph_actual']
+
+ fields: \n
+ - [7:0] = shadow_user_roi_requested_global_xy_size
+*/
+#define VL53L1_GPH__SYSTEM__SEQUENCE_CONFIG 0x00FA
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'gph_actual']
+
+ fields: \n
+ - [0] = shadow_sequence_vhv_en
+ - [1] = shadow_sequence_phasecal_en
+ - [2] = shadow_sequence_reference_phase_en
+ - [3] = shadow_sequence_dss1_en
+ - [4] = shadow_sequence_dss2_en
+ - [5] = shadow_sequence_mm1_en
+ - [6] = shadow_sequence_mm2_en
+ - [7] = shadow_sequence_range_en
+*/
+#define VL53L1_GPH__GPH_ID 0x00FB
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'gph_actual']
+
+ fields: \n
+ - [0] = shadow_gph_id
+*/
+#define VL53L1_SYSTEM__INTERRUPT_SET 0x00FC
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'system_int_set']
+
+ fields: \n
+ - [0] = sys_interrupt_set_range
+ - [1] = sys_interrupt_set_error
+*/
+#define VL53L1_INTERRUPT_MANAGER__ENABLES 0x00FD
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 4
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'interrupt_manager']
+
+ fields: \n
+ - [0] = interrupt_enable__single_shot
+ - [1] = interrupt_enable__back_to_back
+ - [2] = interrupt_enable__timed
+ - [3] = interrupt_enable__abort
+ - [4] = interrupt_enable__test
+*/
+#define VL53L1_INTERRUPT_MANAGER__CLEAR 0x00FE
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 4
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'interrupt_manager']
+
+ fields: \n
+ - [0] = interrupt_clear__single_shot
+ - [1] = interrupt_clear__back_to_back
+ - [2] = interrupt_clear__timed
+ - [3] = interrupt_clear__abort
+ - [4] = interrupt_clear__test
+*/
+#define VL53L1_INTERRUPT_MANAGER__STATUS 0x00FF
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 4
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'interrupt_manager']
+
+ fields: \n
+ - [0] = interrupt_status__single_shot
+ - [1] = interrupt_status__back_to_back
+ - [2] = interrupt_status__timed
+ - [3] = interrupt_status__abort
+ - [4] = interrupt_status__test
+*/
+#define VL53L1_MCU_TO_HOST_BANK__WR_ACCESS_EN 0x0100
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'host_bank_ctrl']
+
+ fields: \n
+ - [0] = mcu_to_host_bank_wr_en
+*/
+#define VL53L1_POWER_MANAGEMENT__GO1_RESET_STATUS 0x0101
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'power_man_status']
+
+ fields: \n
+ - [0] = go1_status
+*/
+#define VL53L1_PAD_STARTUP_MODE__VALUE_RO 0x0102
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'pad_config']
+
+ fields: \n
+ - [0] = pad_atest1_val_ro
+ - [1] = pad_atest2_val_ro
+*/
+#define VL53L1_PAD_STARTUP_MODE__VALUE_CTRL 0x0103
+/*!<
+ type: uint8_t \n
+ default: 0x30 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'pad_config']
+
+ fields: \n
+ - [0] = pad_atest1_val
+ - [1] = pad_atest2_val
+ - [4] = pad_atest1_dig_enable
+ - [5] = pad_atest2_dig_enable
+*/
+#define VL53L1_PLL_PERIOD_US 0x0104
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 17
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['debug_results', 'pll_config']
+
+ fields: \n
+ - [17:0] = pll_period_us (fixed point 0.24)
+*/
+#define VL53L1_PLL_PERIOD_US_3 0x0104
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PLL_PERIOD_US_2 0x0105
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PLL_PERIOD_US_1 0x0106
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PLL_PERIOD_US_0 0x0107
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_INTERRUPT_SCHEDULER__DATA_OUT 0x0108
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['debug_results', 'debug_timer']
+
+ fields: \n
+ - [31:0] = interrupt_scheduler_data_out
+*/
+#define VL53L1_INTERRUPT_SCHEDULER__DATA_OUT_3 0x0108
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_INTERRUPT_SCHEDULER__DATA_OUT_2 0x0109
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_INTERRUPT_SCHEDULER__DATA_OUT_1 0x010A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_INTERRUPT_SCHEDULER__DATA_OUT_0 0x010B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_NVM_BIST__COMPLETE 0x010C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'nvm_bist_status']
+
+ fields: \n
+ - [0] = nvm_bist__complete
+*/
+#define VL53L1_NVM_BIST__STATUS 0x010D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['debug_results', 'nvm_bist_status']
+
+ fields: \n
+ - [0] = nvm_bist__status
+*/
+#define VL53L1_IDENTIFICATION__MODEL_ID 0x010F
+/*!<
+ type: uint8_t \n
+ default: 0xEA \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'identification']
+
+ fields: \n
+ - [7:0] = model_id
+*/
+#define VL53L1_IDENTIFICATION__MODULE_TYPE 0x0110
+/*!<
+ type: uint8_t \n
+ default: 0xAA \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'identification']
+
+ fields: \n
+ - [7:0] = module_type
+*/
+#define VL53L1_IDENTIFICATION__REVISION_ID 0x0111
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'identification']
+
+ fields: \n
+ - [3:0] = nvm_revision_id
+ - [7:4] = mask_revision_id
+*/
+#define VL53L1_IDENTIFICATION__MODULE_ID 0x0112
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['nvm_copy_data', 'identification']
+
+ fields: \n
+ - [15:0] = module_id
+*/
+#define VL53L1_IDENTIFICATION__MODULE_ID_HI 0x0112
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_IDENTIFICATION__MODULE_ID_LO 0x0113
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_ANA_CONFIG__FAST_OSC__TRIM_MAX 0x0114
+/*!<
+ type: uint8_t \n
+ default: OSC_TRIM_DEFAULT \n
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'analog_config']
+
+ fields: \n
+ - [6:0] = osc_trim_max
+*/
+#define VL53L1_ANA_CONFIG__FAST_OSC__FREQ_SET 0x0115
+/*!<
+ type: uint8_t \n
+ default: OSC_FREQ_SET_DEFAULT \n
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'analog_config']
+
+ fields: \n
+ - [2:0] = osc_freq_set
+*/
+#define VL53L1_ANA_CONFIG__VCSEL_TRIM 0x0116
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'analog_config']
+
+ fields: \n
+ - [2:0] = vcsel_trim
+*/
+#define VL53L1_ANA_CONFIG__VCSEL_SELION 0x0117
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'analog_config']
+
+ fields: \n
+ - [5:0] = vcsel_selion
+*/
+#define VL53L1_ANA_CONFIG__VCSEL_SELION_MAX 0x0118
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'analog_config']
+
+ fields: \n
+ - [5:0] = vcsel_selion_max
+*/
+#define VL53L1_PROTECTED_LASER_SAFETY__LOCK_BIT 0x0119
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'laser_safety']
+
+ fields: \n
+ - [0] = laser_safety__lock_bit
+*/
+#define VL53L1_LASER_SAFETY__KEY 0x011A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'laser_safety']
+
+ fields: \n
+ - [6:0] = laser_safety__key
+*/
+#define VL53L1_LASER_SAFETY__KEY_RO 0x011B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'laser_safety']
+
+ fields: \n
+ - [0] = laser_safety__key_ro
+*/
+#define VL53L1_LASER_SAFETY__CLIP 0x011C
+/*!<
+ type: uint8_t \n
+ default: 0x02 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'laser_safety']
+
+ fields: \n
+ - [5:0] = vcsel_pulse_width_clip
+*/
+#define VL53L1_LASER_SAFETY__MULT 0x011D
+/*!<
+ type: uint8_t \n
+ default: 0x32 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'laser_safety']
+
+ fields: \n
+ - [5:0] = vcsel_pulse_width_mult
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_0 0x011E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_0
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_1 0x011F
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_1
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_2 0x0120
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_2
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_3 0x0121
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_3
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_4 0x0122
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_4
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_5 0x0123
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_5
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_6 0x0124
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_6
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_7 0x0125
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_7
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_8 0x0126
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_8
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_9 0x0127
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_9
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_10 0x0128
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_10
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_11 0x0129
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_11
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_12 0x012A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_12
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_13 0x012B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_13
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_14 0x012C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_14
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_15 0x012D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_15
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_16 0x012E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_16
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_17 0x012F
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_17
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_18 0x0130
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_18
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_19 0x0131
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_19
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_20 0x0132
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_20
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_21 0x0133
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_21
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_22 0x0134
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_22
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_23 0x0135
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_23
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_24 0x0136
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_24
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_25 0x0137
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_25
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_26 0x0138
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_26
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_27 0x0139
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_27
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_28 0x013A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_28
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_29 0x013B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_29
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_30 0x013C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_30
+*/
+#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_RTN_31 0x013D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'ret_spad_config']
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_31
+*/
+#define VL53L1_ROI_CONFIG__MODE_ROI_CENTRE_SPAD 0x013E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'roi_config']
+
+ fields: \n
+ - [7:0] = mode_roi_center_spad
+*/
+#define VL53L1_ROI_CONFIG__MODE_ROI_XY_SIZE 0x013F
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['nvm_copy_data', 'roi_config']
+
+ fields: \n
+ - [7:0] = mode_roi_xy_size
+*/
+#define VL53L1_GO2_HOST_BANK_ACCESS__OVERRIDE 0x0300
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__MULTIPLICAND 0x0400
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__MULTIPLICAND_3 0x0400
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__MULTIPLICAND_2 0x0401
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__MULTIPLICAND_1 0x0402
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__MULTIPLICAND_0 0x0403
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__MULTIPLIER 0x0404
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__MULTIPLIER_3 0x0404
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__MULTIPLIER_2 0x0405
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__MULTIPLIER_1 0x0406
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__MULTIPLIER_0 0x0407
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__PRODUCT_HI 0x0408
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__PRODUCT_HI_3 0x0408
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__PRODUCT_HI_2 0x0409
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__PRODUCT_HI_1 0x040A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__PRODUCT_HI_0 0x040B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__PRODUCT_LO 0x040C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__PRODUCT_LO_3 0x040C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__PRODUCT_LO_2 0x040D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__PRODUCT_LO_1 0x040E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__PRODUCT_LO_0 0x040F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__START 0x0410
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_MULTIPLIER__STATUS 0x0411
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__START 0x0412
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__STATUS 0x0413
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__DIVIDEND 0x0414
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__DIVIDEND_3 0x0414
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__DIVIDEND_2 0x0415
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__DIVIDEND_1 0x0416
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__DIVIDEND_0 0x0417
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__DIVISOR 0x0418
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__DIVISOR_3 0x0418
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__DIVISOR_2 0x0419
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__DIVISOR_1 0x041A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__DIVISOR_0 0x041B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__QUOTIENT 0x041C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__QUOTIENT_3 0x041C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__QUOTIENT_2 0x041D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__QUOTIENT_1 0x041E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_UTIL_DIVIDER__QUOTIENT_0 0x041F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TIMER0__VALUE_IN 0x0420
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TIMER0__VALUE_IN_3 0x0420
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TIMER0__VALUE_IN_2 0x0421
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TIMER0__VALUE_IN_1 0x0422
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TIMER0__VALUE_IN_0 0x0423
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TIMER1__VALUE_IN 0x0424
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TIMER1__VALUE_IN_3 0x0424
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TIMER1__VALUE_IN_2 0x0425
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TIMER1__VALUE_IN_1 0x0426
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TIMER1__VALUE_IN_0 0x0427
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TIMER0__CTRL 0x0428
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TIMER1__CTRL 0x0429
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_GENERAL_PURPOSE__GP_0 0x042C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [7:0] = mcu_gp_0
+*/
+#define VL53L1_MCU_GENERAL_PURPOSE__GP_1 0x042D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [7:0] = mcu_gp_1
+*/
+#define VL53L1_MCU_GENERAL_PURPOSE__GP_2 0x042E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [7:0] = mcu_gp_2
+*/
+#define VL53L1_MCU_GENERAL_PURPOSE__GP_3 0x042F
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [7:0] = mcu_gp_3
+*/
+#define VL53L1_MCU_RANGE_CALC__CONFIG 0x0430
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [0] = fw_calc__sigma_delta_sel
+ - [2] = fw_calc__phase_output_en
+ - [3] = fw_calc__peak_signal_rate_en
+ - [4] = fw_calc__ambient_rate_en
+ - [5] = fw_calc__total_rate_per_spad_en
+ - [6] = fw_calc__snr_avg_signal_rate_en
+ - [7] = fw_calc__sigma_en
+*/
+#define VL53L1_MCU_RANGE_CALC__OFFSET_CORRECTED_RANGE 0x0432
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [15:0] = offset_corrected_range
+*/
+#define VL53L1_MCU_RANGE_CALC__OFFSET_CORRECTED_RANGE_HI 0x0432
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__OFFSET_CORRECTED_RANGE_LO 0x0433
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__SPARE_4 0x0434
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 16
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [16:0] = mcu_calc__spare_4
+*/
+#define VL53L1_MCU_RANGE_CALC__SPARE_4_3 0x0434
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__SPARE_4_2 0x0435
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__SPARE_4_1 0x0436
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__SPARE_4_0 0x0437
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__AMBIENT_DURATION_PRE_CALC 0x0438
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 13
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [13:0] = ambient_duration_prec_calc
+*/
+#define VL53L1_MCU_RANGE_CALC__AMBIENT_DURATION_PRE_CALC_HI 0x0438
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__AMBIENT_DURATION_PRE_CALC_LO 0x0439
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_VCSEL_PERIOD 0x043C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [7:0] = algo_vcsel_period
+*/
+#define VL53L1_MCU_RANGE_CALC__SPARE_5 0x043D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [7:0] = mcu_calc__spare_5
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_TOTAL_PERIODS 0x043E
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [15:0] = algo_total_periods
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_TOTAL_PERIODS_HI 0x043E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_TOTAL_PERIODS_LO 0x043F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_ACCUM_PHASE 0x0440
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [31:0] = algo_accum_phase
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_ACCUM_PHASE_3 0x0440
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_ACCUM_PHASE_2 0x0441
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_ACCUM_PHASE_1 0x0442
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_ACCUM_PHASE_0 0x0443
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_SIGNAL_EVENTS 0x0444
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [31:0] = algo_signal_events
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_SIGNAL_EVENTS_3 0x0444
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_SIGNAL_EVENTS_2 0x0445
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_SIGNAL_EVENTS_1 0x0446
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_SIGNAL_EVENTS_0 0x0447
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_AMBIENT_EVENTS 0x0448
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [31:0] = algo_ambient_events
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_AMBIENT_EVENTS_3 0x0448
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_AMBIENT_EVENTS_2 0x0449
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_AMBIENT_EVENTS_1 0x044A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_AMBIENT_EVENTS_0 0x044B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__SPARE_6 0x044C
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [15:0] = mcu_calc__spare_6
+*/
+#define VL53L1_MCU_RANGE_CALC__SPARE_6_HI 0x044C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__SPARE_6_LO 0x044D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_ADJUST_VCSEL_PERIOD 0x044E
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [15:0] = algo_adjust_vcsel_period
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_ADJUST_VCSEL_PERIOD_HI 0x044E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__ALGO_ADJUST_VCSEL_PERIOD_LO 0x044F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__NUM_SPADS 0x0450
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [15:0] = num_spads
+*/
+#define VL53L1_MCU_RANGE_CALC__NUM_SPADS_HI 0x0450
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__NUM_SPADS_LO 0x0451
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__PHASE_OUTPUT 0x0452
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [15:0] = phase_output
+*/
+#define VL53L1_MCU_RANGE_CALC__PHASE_OUTPUT_HI 0x0452
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__PHASE_OUTPUT_LO 0x0453
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__RATE_PER_SPAD_MCPS 0x0454
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 19
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [19:0] = rate_per_spad_mcps
+*/
+#define VL53L1_MCU_RANGE_CALC__RATE_PER_SPAD_MCPS_3 0x0454
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__RATE_PER_SPAD_MCPS_2 0x0455
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__RATE_PER_SPAD_MCPS_1 0x0456
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__RATE_PER_SPAD_MCPS_0 0x0457
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__SPARE_7 0x0458
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [7:0] = mcu_calc__spare_7
+*/
+#define VL53L1_MCU_RANGE_CALC__SPARE_8 0x0459
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [7:0] = mcu_calc__spare_8
+*/
+#define VL53L1_MCU_RANGE_CALC__PEAK_SIGNAL_RATE_MCPS 0x045A
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [15:0] = peak_signal_rate
+*/
+#define VL53L1_MCU_RANGE_CALC__PEAK_SIGNAL_RATE_MCPS_HI 0x045A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__PEAK_SIGNAL_RATE_MCPS_LO 0x045B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__AVG_SIGNAL_RATE_MCPS 0x045C
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [15:0] = avg_signal_rate
+*/
+#define VL53L1_MCU_RANGE_CALC__AVG_SIGNAL_RATE_MCPS_HI 0x045C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__AVG_SIGNAL_RATE_MCPS_LO 0x045D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__AMBIENT_RATE_MCPS 0x045E
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [15:0] = ambient_rate
+*/
+#define VL53L1_MCU_RANGE_CALC__AMBIENT_RATE_MCPS_HI 0x045E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__AMBIENT_RATE_MCPS_LO 0x045F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__XTALK 0x0460
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [15:0] = crosstalk (fixed point 9.7)
+*/
+#define VL53L1_MCU_RANGE_CALC__XTALK_HI 0x0460
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__XTALK_LO 0x0461
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__CALC_STATUS 0x0462
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [7:0] = calc_status
+*/
+#define VL53L1_MCU_RANGE_CALC__DEBUG 0x0463
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [0] = calc_debug__divide_by_zero
+*/
+#define VL53L1_MCU_RANGE_CALC__PEAK_SIGNAL_RATE_XTALK_CORR_MCPS 0x0464
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [15:0] = peak_signal_rate_xtalk_corr
+*/
+#define VL53L1_MCU_RANGE_CALC__PEAK_SIGNAL_RATE_XTALK_CORR_MCPS_HI 0x0464
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__PEAK_SIGNAL_RATE_XTALK_CORR_MCPS_LO 0x0465
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MCU_RANGE_CALC__SPARE_0 0x0468
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [7:0] = mcu_calc__spare_0
+*/
+#define VL53L1_MCU_RANGE_CALC__SPARE_1 0x0469
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [7:0] = mcu_calc__spare_1
+*/
+#define VL53L1_MCU_RANGE_CALC__SPARE_2 0x046A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [7:0] = mcu_calc__spare_2
+*/
+#define VL53L1_MCU_RANGE_CALC__SPARE_3 0x046B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [7:0] = mcu_calc__spare_3
+*/
+#define VL53L1_PATCH__CTRL 0x0470
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__JMP_ENABLES 0x0472
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__JMP_ENABLES_HI 0x0472
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__JMP_ENABLES_LO 0x0473
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__DATA_ENABLES 0x0474
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__DATA_ENABLES_HI 0x0474
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__DATA_ENABLES_LO 0x0475
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_0 0x0476
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_0_HI 0x0476
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_0_LO 0x0477
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_1 0x0478
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_1_HI 0x0478
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_1_LO 0x0479
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_2 0x047A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_2_HI 0x047A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_2_LO 0x047B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_3 0x047C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_3_HI 0x047C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_3_LO 0x047D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_4 0x047E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_4_HI 0x047E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_4_LO 0x047F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_5 0x0480
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_5_HI 0x0480
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_5_LO 0x0481
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_6 0x0482
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_6_HI 0x0482
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_6_LO 0x0483
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_7 0x0484
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_7_HI 0x0484
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_7_LO 0x0485
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_8 0x0486
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_8_HI 0x0486
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_8_LO 0x0487
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_9 0x0488
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_9_HI 0x0488
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_9_LO 0x0489
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_10 0x048A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_10_HI 0x048A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_10_LO 0x048B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_11 0x048C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_11_HI 0x048C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_11_LO 0x048D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_12 0x048E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_12_HI 0x048E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_12_LO 0x048F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_13 0x0490
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_13_HI 0x0490
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_13_LO 0x0491
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_14 0x0492
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_14_HI 0x0492
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_14_LO 0x0493
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_15 0x0494
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_15_HI 0x0494
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__OFFSET_15_LO 0x0495
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_0 0x0496
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_0_HI 0x0496
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_0_LO 0x0497
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_1 0x0498
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_1_HI 0x0498
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_1_LO 0x0499
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_2 0x049A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_2_HI 0x049A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_2_LO 0x049B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_3 0x049C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_3_HI 0x049C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_3_LO 0x049D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_4 0x049E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_4_HI 0x049E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_4_LO 0x049F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_5 0x04A0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_5_HI 0x04A0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_5_LO 0x04A1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_6 0x04A2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_6_HI 0x04A2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_6_LO 0x04A3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_7 0x04A4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_7_HI 0x04A4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_7_LO 0x04A5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_8 0x04A6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_8_HI 0x04A6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_8_LO 0x04A7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_9 0x04A8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_9_HI 0x04A8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_9_LO 0x04A9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_10 0x04AA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_10_HI 0x04AA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_10_LO 0x04AB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_11 0x04AC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_11_HI 0x04AC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_11_LO 0x04AD
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_12 0x04AE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_12_HI 0x04AE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_12_LO 0x04AF
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_13 0x04B0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_13_HI 0x04B0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_13_LO 0x04B1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_14 0x04B2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_14_HI 0x04B2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_14_LO 0x04B3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_15 0x04B4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_15_HI 0x04B4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PATCH__ADDRESS_15_LO 0x04B5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SPI_ASYNC_MUX__CTRL 0x04C0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_CLK__CONFIG 0x04C4
+/*!<
+ type: uint8_t \n
+ default: 0x01 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [0] = clk_mcu_en
+*/
+#define VL53L1_GPIO_LV_MUX__CTRL 0x04CC
+/*!<
+ type: uint8_t \n
+ default: 0x08 \n
+ info: \n
+ - msb = 4
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [3:0] = gpio__mux_select_lv
+ - [4] = gpio__mux_active_high_lv
+*/
+#define VL53L1_GPIO_LV_PAD__CTRL 0x04CD
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [0] = gpio__extsup_lv
+*/
+#define VL53L1_PAD_I2C_LV__CONFIG 0x04D0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PAD_STARTUP_MODE__VALUE_RO_GO1 0x04D4
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [0] = pad_spi_csn_val_ro
+*/
+#define VL53L1_HOST_IF__STATUS_GO1 0x04D5
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [0] = host_interface_lv
+*/
+#define VL53L1_MCU_CLK_GATING__CTRL 0x04D8
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['']
+
+ fields: \n
+ - [0] = clk_gate_en__go1_mcu_bank
+ - [1] = clk_gate_en__go1_mcu_patch_ctrl
+ - [2] = clk_gate_en__go1_mcu_timers
+ - [3] = clk_gate_en__go1_mcu_mult_div
+*/
+#define VL53L1_TEST__BIST_ROM_CTRL 0x04E0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__BIST_ROM_RESULT 0x04E1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__BIST_ROM_MCU_SIG 0x04E2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__BIST_ROM_MCU_SIG_HI 0x04E2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__BIST_ROM_MCU_SIG_LO 0x04E3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__BIST_RAM_CTRL 0x04E4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__BIST_RAM_RESULT 0x04E5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__TMC 0x04E8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__PLL_BIST_MIN_THRESHOLD 0x04F0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__PLL_BIST_MIN_THRESHOLD_HI 0x04F0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__PLL_BIST_MIN_THRESHOLD_LO 0x04F1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__PLL_BIST_MAX_THRESHOLD 0x04F2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__PLL_BIST_MAX_THRESHOLD_HI 0x04F2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__PLL_BIST_MAX_THRESHOLD_LO 0x04F3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__PLL_BIST_COUNT_OUT 0x04F4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__PLL_BIST_COUNT_OUT_HI 0x04F4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__PLL_BIST_COUNT_OUT_LO 0x04F5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__PLL_BIST_GONOGO 0x04F6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_TEST__PLL_BIST_CTRL 0x04F7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__DEVICE_ID 0x0680
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__REVISION_ID 0x0681
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__CLK_CTRL1 0x0683
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__CLK_CTRL2 0x0684
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__WOI_1 0x0685
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__WOI_REF_1 0x0686
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__START_RANGING 0x0687
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__LOW_LIMIT_1 0x0690
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__HIGH_LIMIT_1 0x0691
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__LOW_LIMIT_REF_1 0x0692
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__HIGH_LIMIT_REF_1 0x0693
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__QUANTIFIER_1_MSB 0x0694
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__QUANTIFIER_1_LSB 0x0695
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__QUANTIFIER_REF_1_MSB 0x0696
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__QUANTIFIER_REF_1_LSB 0x0697
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_OFFSET_1_MSB 0x0698
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_OFFSET_1_LSB 0x0699
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_OFFSET_REF_1_MSB 0x069A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_OFFSET_REF_1_LSB 0x069B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__FILTER_STRENGTH_1 0x069C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__FILTER_STRENGTH_REF_1 0x069D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SIGNAL_EVENT_LIMIT_1_MSB 0x069E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SIGNAL_EVENT_LIMIT_1_LSB 0x069F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SIGNAL_EVENT_LIMIT_REF_1_MSB 0x06A0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SIGNAL_EVENT_LIMIT_REF_1_LSB 0x06A1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__TIMEOUT_OVERALL_PERIODS_MSB 0x06A4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__TIMEOUT_OVERALL_PERIODS_LSB 0x06A5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__INVERT_HW 0x06A6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__FORCE_HW 0x06A7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__STATIC_HW_VALUE 0x06A8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__FORCE_CONTINUOUS_AMBIENT 0x06A9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__TEST_PHASE_SELECT_TO_FILTER 0x06AA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__TEST_PHASE_SELECT_TO_TIMING_GEN 0x06AB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__INITIAL_PHASE_VALUE_1 0x06AC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__INITIAL_PHASE_VALUE_REF_1 0x06AD
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__FORCE_UP_IN 0x06AE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__FORCE_DN_IN 0x06AF
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__STATIC_UP_VALUE_1 0x06B0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__STATIC_UP_VALUE_REF_1 0x06B1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__STATIC_DN_VALUE_1 0x06B2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__STATIC_DN_VALUE_REF_1 0x06B3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__MONITOR_UP_DN 0x06B4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__INVERT_UP_DN 0x06B5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__CPUMP_1 0x06B6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__CPUMP_2 0x06B7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__CPUMP_3 0x06B8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__OSC_1 0x06B9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__PLL_1 0x06BB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__PLL_2 0x06BC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__REFERENCE_1 0x06BD
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__REFERENCE_3 0x06BF
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__REFERENCE_4 0x06C0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__REFERENCE_5 0x06C1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__REGAVDD1V2 0x06C3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__CALIB_1 0x06C4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__CALIB_2 0x06C5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__CALIB_3 0x06C6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__TST_MUX_SEL1 0x06C9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__TST_MUX_SEL2 0x06CA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__TST_MUX 0x06CB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__GPIO_OUT_TESTMUX 0x06CC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__CUSTOM_FE 0x06CD
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__CUSTOM_FE_2 0x06CE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SPAD_READOUT 0x06CF
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SPAD_READOUT_1 0x06D0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SPAD_READOUT_2 0x06D1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SPAD_PS 0x06D2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__LASER_SAFETY_2 0x06D4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__MODE 0x0780
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__PDN 0x0781
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__PROGN 0x0782
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__READN 0x0783
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__PULSE_WIDTH_MSB 0x0784
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__PULSE_WIDTH_LSB 0x0785
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__HV_RISE_MSB 0x0786
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__HV_RISE_LSB 0x0787
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__HV_FALL_MSB 0x0788
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__HV_FALL_LSB 0x0789
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__TST 0x078A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__TESTREAD 0x078B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__DATAIN_MMM 0x078C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__DATAIN_LMM 0x078D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__DATAIN_LLM 0x078E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__DATAIN_LLL 0x078F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__DATAOUT_MMM 0x0790
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__DATAOUT_LMM 0x0791
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__DATAOUT_LLM 0x0792
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__DATAOUT_LLL 0x0793
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__ADDR 0x0794
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__NVM_CTRL__DATAOUT_ECC 0x0795
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_0 0x0796
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_1 0x0797
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_2 0x0798
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_3 0x0799
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_4 0x079A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_5 0x079B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_6 0x079C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_7 0x079D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_8 0x079E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_9 0x079F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_10 0x07A0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_11 0x07A1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_12 0x07A2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_13 0x07A3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_14 0x07A4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_15 0x07A5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_16 0x07A6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_17 0x07A7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SPAD_SHIFT_EN 0x07BA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SPAD_DISABLE_CTRL 0x07BB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SPAD_EN_SHIFT_OUT_DEBUG 0x07BC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SPI_MODE 0x07BD
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__GPIO_DIR 0x07BE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__VCSEL_PERIOD 0x0880
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__VCSEL_START 0x0881
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__VCSEL_STOP 0x0882
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__VCSEL_1 0x0885
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__VCSEL_STATUS 0x088D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__STATUS 0x0980
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__LASER_CONTINUITY_STATE 0x0981
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RANGE_1_MMM 0x0982
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RANGE_1_LMM 0x0983
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RANGE_1_LLM 0x0984
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RANGE_1_LLL 0x0985
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RANGE_REF_1_MMM 0x0986
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RANGE_REF_1_LMM 0x0987
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RANGE_REF_1_LLM 0x0988
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RANGE_REF_1_LLL 0x0989
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_WINDOW_EVENTS_1_MMM 0x098A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_WINDOW_EVENTS_1_LMM 0x098B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_WINDOW_EVENTS_1_LLM 0x098C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_WINDOW_EVENTS_1_LLL 0x098D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RANGING_TOTAL_EVENTS_1_MMM 0x098E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RANGING_TOTAL_EVENTS_1_LMM 0x098F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RANGING_TOTAL_EVENTS_1_LLM 0x0990
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RANGING_TOTAL_EVENTS_1_LLL 0x0991
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SIGNAL_TOTAL_EVENTS_1_MMM 0x0992
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SIGNAL_TOTAL_EVENTS_1_LMM 0x0993
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SIGNAL_TOTAL_EVENTS_1_LLM 0x0994
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SIGNAL_TOTAL_EVENTS_1_LLL 0x0995
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__TOTAL_PERIODS_ELAPSED_1_MM 0x0996
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__TOTAL_PERIODS_ELAPSED_1_LM 0x0997
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__TOTAL_PERIODS_ELAPSED_1_LL 0x0998
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_MISMATCH_MM 0x0999
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_MISMATCH_LM 0x099A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_MISMATCH_LL 0x099B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_WINDOW_EVENTS_REF_1_MMM 0x099C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_WINDOW_EVENTS_REF_1_LMM 0x099D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_WINDOW_EVENTS_REF_1_LLM 0x099E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_WINDOW_EVENTS_REF_1_LLL 0x099F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RANGING_TOTAL_EVENTS_REF_1_MMM 0x09A0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RANGING_TOTAL_EVENTS_REF_1_LMM 0x09A1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RANGING_TOTAL_EVENTS_REF_1_LLM 0x09A2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RANGING_TOTAL_EVENTS_REF_1_LLL 0x09A3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SIGNAL_TOTAL_EVENTS_REF_1_MMM 0x09A4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SIGNAL_TOTAL_EVENTS_REF_1_LMM 0x09A5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SIGNAL_TOTAL_EVENTS_REF_1_LLM 0x09A6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SIGNAL_TOTAL_EVENTS_REF_1_LLL 0x09A7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__TOTAL_PERIODS_ELAPSED_REF_1_MM 0x09A8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__TOTAL_PERIODS_ELAPSED_REF_1_LM 0x09A9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__TOTAL_PERIODS_ELAPSED_REF_1_LL 0x09AA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_MISMATCH_REF_MM 0x09AB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_MISMATCH_REF_LM 0x09AC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__AMBIENT_MISMATCH_REF_LL 0x09AD
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__GPIO_CONFIG__A0 0x0A00
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RESET_CONTROL__A0 0x0A01
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__INTR_MANAGER__A0 0x0A02
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__POWER_FSM_TIME_OSC__A0 0x0A06
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__VCSEL_ATEST__A0 0x0A07
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__VCSEL_PERIOD_CLIPPED__A0 0x0A08
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__VCSEL_STOP_CLIPPED__A0 0x0A09
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__CALIB_2__A0 0x0A0A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__STOP_CONDITION__A0 0x0A0B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__STATUS_RESET__A0 0x0A0C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__READOUT_CFG__A0 0x0A0D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__WINDOW_SETTING__A0 0x0A0E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__VCSEL_DELAY__A0 0x0A1A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__REFERENCE_2__A0 0x0A1B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__REGAVDD1V2__A0 0x0A1D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__TST_MUX__A0 0x0A1F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__CUSTOM_FE_2__A0 0x0A20
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SPAD_READOUT__A0 0x0A21
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__CPUMP_1__A0 0x0A22
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__SPARE_REGISTER__A0 0x0A23
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__VCSEL_CONT_STAGE5_BYPASS__A0 0x0A24
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_18 0x0A25
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_19 0x0A26
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_20 0x0A27
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_21 0x0A28
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_22 0x0A29
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_23 0x0A2A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_24 0x0A2B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_25 0x0A2C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_26 0x0A2D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_27 0x0A2E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_28 0x0A2F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_29 0x0A30
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_30 0x0A31
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__RET_SPAD_EN_31 0x0A32
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__REF_SPAD_EN_0__EWOK 0x0A33
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__REF_SPAD_EN_1__EWOK 0x0A34
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__REF_SPAD_EN_2__EWOK 0x0A35
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__REF_SPAD_EN_3__EWOK 0x0A36
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__REF_SPAD_EN_4__EWOK 0x0A37
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__REF_SPAD_EN_5__EWOK 0x0A38
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__REF_EN_START_SELECT 0x0A39
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGING_CORE__REGDVDD1V2_ATEST__EWOK 0x0A41
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SOFT_RESET_GO1 0x0B00
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PRIVATE__PATCH_BASE_ADDR_RSLV 0x0E00
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__INTERRUPT_STATUS 0x0ED0
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [2:0] = prev_shadow_int_status
+ - [4:3] = prev_shadow_int_error_status
+ - [5] = prev_shadow_gph_id_gpio_status
+*/
+#define VL53L1_PREV_SHADOW_RESULT__RANGE_STATUS 0x0ED1
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [4:0] = prev_shadow_range_status
+ - [5] = prev_shadow_max_threshold_hit
+ - [6] = prev_shadow_min_threshold_hit
+ - [7] = prev_shadow_gph_id_range_status
+*/
+#define VL53L1_PREV_SHADOW_RESULT__REPORT_STATUS 0x0ED2
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [3:0] = prev_shadow_report_status
+*/
+#define VL53L1_PREV_SHADOW_RESULT__STREAM_COUNT 0x0ED3
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [7:0] = prev_shadow_result__stream_count
+*/
+#define VL53L1_PREV_SHADOW_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0 0x0ED4
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__dss_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+#define VL53L1_PREV_SHADOW_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0_HI 0x0ED4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0_LO 0x0ED5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD0 0x0ED6
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__peak_signal_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+#define VL53L1_PREV_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD0_HI 0x0ED6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD0_LO 0x0ED7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__AMBIENT_COUNT_RATE_MCPS_SD0 0x0ED8
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__ambient_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+#define VL53L1_PREV_SHADOW_RESULT__AMBIENT_COUNT_RATE_MCPS_SD0_HI 0x0ED8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__AMBIENT_COUNT_RATE_MCPS_SD0_LO 0x0ED9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SIGMA_SD0 0x0EDA
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__sigma_sd0 (fixed point 14.2)
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SIGMA_SD0_HI 0x0EDA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SIGMA_SD0_LO 0x0EDB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__PHASE_SD0 0x0EDC
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__phase_sd0 (fixed point 5.11)
+*/
+#define VL53L1_PREV_SHADOW_RESULT__PHASE_SD0_HI 0x0EDC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__PHASE_SD0_LO 0x0EDD
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0 0x0EDE
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__final_crosstalk_corrected_range_mm_sd0
+*/
+#define VL53L1_PREV_SHADOW_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0_HI 0x0EDE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0_LO 0x0EDF
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_CROSSTALK_CORRECTED_MCPS_SD0 0x0EE0
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0 (fixed point 9.7)
+*/
+#define VL53L1_PREV_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_CROSSTALK_CORRECTED_MCPS_SD0_HI 0x0EE0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_CROSSTALK_CORRECTED_MCPS_SD0_LO 0x0EE1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__MM_INNER_ACTUAL_EFFECTIVE_SPADS_SD0 0x0EE2
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__mm_inner_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+#define VL53L1_PREV_SHADOW_RESULT__MM_INNER_ACTUAL_EFFECTIVE_SPADS_SD0_HI 0x0EE2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__MM_INNER_ACTUAL_EFFECTIVE_SPADS_SD0_LO 0x0EE3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__MM_OUTER_ACTUAL_EFFECTIVE_SPADS_SD0 0x0EE4
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__mm_outer_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+#define VL53L1_PREV_SHADOW_RESULT__MM_OUTER_ACTUAL_EFFECTIVE_SPADS_SD0_HI 0x0EE4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__MM_OUTER_ACTUAL_EFFECTIVE_SPADS_SD0_LO 0x0EE5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__AVG_SIGNAL_COUNT_RATE_MCPS_SD0 0x0EE6
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__avg_signal_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+#define VL53L1_PREV_SHADOW_RESULT__AVG_SIGNAL_COUNT_RATE_MCPS_SD0_HI 0x0EE6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__AVG_SIGNAL_COUNT_RATE_MCPS_SD0_LO 0x0EE7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD1 0x0EE8
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__dss_actual_effective_spads_sd1 (fixed point 8.8)
+*/
+#define VL53L1_PREV_SHADOW_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD1_HI 0x0EE8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD1_LO 0x0EE9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD1 0x0EEA
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__peak_signal_count_rate_mcps_sd1 (fixed point 9.7)
+*/
+#define VL53L1_PREV_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD1_HI 0x0EEA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD1_LO 0x0EEB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__AMBIENT_COUNT_RATE_MCPS_SD1 0x0EEC
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__ambient_count_rate_mcps_sd1 (fixed point 9.7)
+*/
+#define VL53L1_PREV_SHADOW_RESULT__AMBIENT_COUNT_RATE_MCPS_SD1_HI 0x0EEC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__AMBIENT_COUNT_RATE_MCPS_SD1_LO 0x0EED
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SIGMA_SD1 0x0EEE
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__sigma_sd1 (fixed point 14.2)
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SIGMA_SD1_HI 0x0EEE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SIGMA_SD1_LO 0x0EEF
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__PHASE_SD1 0x0EF0
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__phase_sd1 (fixed point 5.11)
+*/
+#define VL53L1_PREV_SHADOW_RESULT__PHASE_SD1_HI 0x0EF0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__PHASE_SD1_LO 0x0EF1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD1 0x0EF2
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__final_crosstalk_corrected_range_mm_sd1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD1_HI 0x0EF2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD1_LO 0x0EF3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SPARE_0_SD1 0x0EF4
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__spare_0_sd1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SPARE_0_SD1_HI 0x0EF4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SPARE_0_SD1_LO 0x0EF5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SPARE_1_SD1 0x0EF6
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__spare_1_sd1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SPARE_1_SD1_HI 0x0EF6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SPARE_1_SD1_LO 0x0EF7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SPARE_2_SD1 0x0EF8
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__spare_2_sd1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SPARE_2_SD1_HI 0x0EF8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SPARE_2_SD1_LO 0x0EF9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SPARE_3_SD1 0x0EFA
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['prev_shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = prev_shadow_result__spare_3_sd1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SPARE_3_SD1_HI 0x0EFA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT__SPARE_3_SD1_LO 0x0EFB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0 0x0EFC
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['prev_shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = prev_shadow_result_core__ambient_window_events_sd0
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0_3 0x0EFC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0_2 0x0EFD
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0_1 0x0EFE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0_0 0x0EFF
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD0 0x0F00
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['prev_shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = prev_shadow_result_core__ranging_total_events_sd0
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD0_3 0x0F00
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD0_2 0x0F01
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD0_1 0x0F02
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD0_0 0x0F03
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD0 0x0F04
+/*!<
+ type: int32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['prev_shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = prev_shadow_result_core__signal_total_events_sd0
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD0_3 0x0F04
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD0_2 0x0F05
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD0_1 0x0F06
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD0_0 0x0F07
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD0 0x0F08
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['prev_shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = prev_shadow_result_core__total_periods_elapsed_sd0
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD0_3 0x0F08
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD0_2 0x0F09
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD0_1 0x0F0A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD0_0 0x0F0B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD1 0x0F0C
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['prev_shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = prev_shadow_result_core__ambient_window_events_sd1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD1_3 0x0F0C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD1_2 0x0F0D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD1_1 0x0F0E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD1_0 0x0F0F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD1 0x0F10
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['prev_shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = prev_shadow_result_core__ranging_total_events_sd1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD1_3 0x0F10
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD1_2 0x0F11
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD1_1 0x0F12
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD1_0 0x0F13
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD1 0x0F14
+/*!<
+ type: int32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['prev_shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = prev_shadow_result_core__signal_total_events_sd1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD1_3 0x0F14
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD1_2 0x0F15
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD1_1 0x0F16
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD1_0 0x0F17
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD1 0x0F18
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['prev_shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = prev_shadow_result_core__total_periods_elapsed_sd1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD1_3 0x0F18
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD1_2 0x0F19
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD1_1 0x0F1A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD1_0 0x0F1B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PREV_SHADOW_RESULT_CORE__SPARE_0 0x0F1C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['prev_shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [7:0] = prev_shadow_result_core__spare_0
+*/
+#define VL53L1_RESULT__DEBUG_STATUS 0x0F20
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_debug', 'misc_results']
+
+ fields: \n
+ - [7:0] = result_debug_status
+*/
+#define VL53L1_RESULT__DEBUG_STAGE 0x0F21
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_debug', 'misc_results']
+
+ fields: \n
+ - [7:0] = result_debug_stage
+*/
+#define VL53L1_GPH__SYSTEM__THRESH_RATE_HIGH 0x0F24
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['gph_general_config', 'dss_config']
+
+ fields: \n
+ - [15:0] = gph__system_thresh_rate_high (fixed point 9.7)
+*/
+#define VL53L1_GPH__SYSTEM__THRESH_RATE_HIGH_HI 0x0F24
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_GPH__SYSTEM__THRESH_RATE_HIGH_LO 0x0F25
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_GPH__SYSTEM__THRESH_RATE_LOW 0x0F26
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['gph_general_config', 'dss_config']
+
+ fields: \n
+ - [15:0] = gph__system_thresh_rate_low (fixed point 9.7)
+*/
+#define VL53L1_GPH__SYSTEM__THRESH_RATE_LOW_HI 0x0F26
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_GPH__SYSTEM__THRESH_RATE_LOW_LO 0x0F27
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_GPH__SYSTEM__INTERRUPT_CONFIG_GPIO 0x0F28
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_general_config', 'gph_config']
+
+ fields: \n
+ - [1:0] = gph__int_mode_distance
+ - [3:2] = gph__int_mode_rate
+ - [4] = gph__int_spare
+ - [5] = gph__int_new_measure_ready
+ - [6] = gph__int_no_target_en
+ - [7] = gph__int_combined_mode
+*/
+#define VL53L1_GPH__DSS_CONFIG__ROI_MODE_CONTROL 0x0F2F
+/*!<
+ type: uint8_t \n
+ default: 0x01 \n
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_static_config', 'dss_config']
+
+ fields: \n
+ - [1:0] = gph__dss_config__input_mode
+ - [2] = gph__calculate_roi_enable
+*/
+#define VL53L1_GPH__DSS_CONFIG__MANUAL_EFFECTIVE_SPADS_SELECT 0x0F30
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['gph_static_config', 'dss_config']
+
+ fields: \n
+ - [15:0] = gph__dss_config__manual_effective_spads_select
+*/
+#define VL53L1_GPH__DSS_CONFIG__MANUAL_EFFECTIVE_SPADS_SELECT_HI 0x0F30
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_GPH__DSS_CONFIG__MANUAL_EFFECTIVE_SPADS_SELECT_LO 0x0F31
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_GPH__DSS_CONFIG__MANUAL_BLOCK_SELECT 0x0F32
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_static_config', 'dss_config']
+
+ fields: \n
+ - [7:0] = gph__dss_config__manual_block_select
+*/
+#define VL53L1_GPH__DSS_CONFIG__MAX_SPADS_LIMIT 0x0F33
+/*!<
+ type: uint8_t \n
+ default: 0xFF \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_static_config', 'dss_config']
+
+ fields: \n
+ - [7:0] = gph__dss_config__max_spads_limit
+*/
+#define VL53L1_GPH__DSS_CONFIG__MIN_SPADS_LIMIT 0x0F34
+/*!<
+ type: uint8_t \n
+ default: 0x01 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_static_config', 'dss_config']
+
+ fields: \n
+ - [7:0] = gph__dss_config__min_spads_limit
+*/
+#define VL53L1_GPH__MM_CONFIG__TIMEOUT_MACROP_A_HI 0x0F36
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_timing_config', 'mm_config']
+
+ fields: \n
+ - [3:0] = gph_mm_config__config_timeout_macrop_a_hi
+*/
+#define VL53L1_GPH__MM_CONFIG__TIMEOUT_MACROP_A_LO 0x0F37
+/*!<
+ type: uint8_t \n
+ default: 0x06 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_timing_config', 'mm_config']
+
+ fields: \n
+ - [7:0] = gph_mm_config__config_timeout_macrop_a_lo
+*/
+#define VL53L1_GPH__MM_CONFIG__TIMEOUT_MACROP_B_HI 0x0F38
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_timing_config', 'mm_config']
+
+ fields: \n
+ - [3:0] = gph_mm_config__config_timeout_macrop_b_hi
+*/
+#define VL53L1_GPH__MM_CONFIG__TIMEOUT_MACROP_B_LO 0x0F39
+/*!<
+ type: uint8_t \n
+ default: 0x06 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_timing_config', 'mm_config']
+
+ fields: \n
+ - [7:0] = gph_mm_config__config_timeout_macrop_b_lo
+*/
+#define VL53L1_GPH__RANGE_CONFIG__TIMEOUT_MACROP_A_HI 0x0F3A
+/*!<
+ type: uint8_t \n
+ default: 0x01 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_timing_config', 'range_config']
+
+ fields: \n
+ - [3:0] = gph_range_timeout_overall_periods_macrop_a_hi
+*/
+#define VL53L1_GPH__RANGE_CONFIG__TIMEOUT_MACROP_A_LO 0x0F3B
+/*!<
+ type: uint8_t \n
+ default: 0x92 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_timing_config', 'range_config']
+
+ fields: \n
+ - [7:0] = gph_range_timeout_overall_periods_macrop_a_lo
+*/
+#define VL53L1_GPH__RANGE_CONFIG__VCSEL_PERIOD_A 0x0F3C
+/*!<
+ type: uint8_t \n
+ default: 0x0B \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_timing_config', 'range_config']
+
+ fields: \n
+ - [5:0] = gph_range_config__vcsel_period_a
+*/
+#define VL53L1_GPH__RANGE_CONFIG__VCSEL_PERIOD_B 0x0F3D
+/*!<
+ type: uint8_t \n
+ default: 0x09 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_timing_config', 'range_config']
+
+ fields: \n
+ - [5:0] = gph_range_config__vcsel_period_b
+*/
+#define VL53L1_GPH__RANGE_CONFIG__TIMEOUT_MACROP_B_HI 0x0F3E
+/*!<
+ type: uint8_t \n
+ default: 0x01 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_timing_config', 'range_config']
+
+ fields: \n
+ - [3:0] = gph_range_timeout_overall_periods_macrop_b_hi
+*/
+#define VL53L1_GPH__RANGE_CONFIG__TIMEOUT_MACROP_B_LO 0x0F3F
+/*!<
+ type: uint8_t \n
+ default: 0x92 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_timing_config', 'range_config']
+
+ fields: \n
+ - [7:0] = gph_range_timeout_overall_periods_macrop_b_lo
+*/
+#define VL53L1_GPH__RANGE_CONFIG__SIGMA_THRESH 0x0F40
+/*!<
+ type: uint16_t \n
+ default: 0x0080 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['gph_timing_config', 'range_config']
+
+ fields: \n
+ - [15:0] = gph_range_config__sigma_thresh (fixed point 14.2)
+*/
+#define VL53L1_GPH__RANGE_CONFIG__SIGMA_THRESH_HI 0x0F40
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_GPH__RANGE_CONFIG__SIGMA_THRESH_LO 0x0F41
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_GPH__RANGE_CONFIG__MIN_COUNT_RATE_RTN_LIMIT_MCPS 0x0F42
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['gph_timing_config', 'range_config']
+
+ fields: \n
+ - [15:0] = gph_range_config__min_count_rate_rtn_limit_mcps (fixed point 9.7)
+*/
+#define VL53L1_GPH__RANGE_CONFIG__MIN_COUNT_RATE_RTN_LIMIT_MCPS_HI 0x0F42
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_GPH__RANGE_CONFIG__MIN_COUNT_RATE_RTN_LIMIT_MCPS_LO 0x0F43
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_GPH__RANGE_CONFIG__VALID_PHASE_LOW 0x0F44
+/*!<
+ type: uint8_t \n
+ default: 0x08 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_timing_config', 'range_config']
+
+ fields: \n
+ - [7:0] = gph_range_config__valid_phase_low (fixed point 5.3)
+*/
+#define VL53L1_GPH__RANGE_CONFIG__VALID_PHASE_HIGH 0x0F45
+/*!<
+ type: uint8_t \n
+ default: 0x80 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['gph_timing_config', 'range_config']
+
+ fields: \n
+ - [7:0] = gph_range_config__valid_phase_high (fixed point 5.3)
+*/
+#define VL53L1_FIRMWARE__INTERNAL_STREAM_COUNT_DIV 0x0F46
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['fw_internal']
+
+ fields: \n
+ - [7:0] = fw__internal_stream_count_div
+*/
+#define VL53L1_FIRMWARE__INTERNAL_STREAM_COUNTER_VAL 0x0F47
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['fw_internal']
+
+ fields: \n
+ - [7:0] = fw__internal_stream_counter_val
+*/
+#define VL53L1_DSS_CALC__ROI_CTRL 0x0F54
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [0] = dss_calc__roi_intersect_enable
+ - [1] = dss_calc__roi_subtract_enable
+*/
+#define VL53L1_DSS_CALC__SPARE_1 0x0F55
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__spare_1
+*/
+#define VL53L1_DSS_CALC__SPARE_2 0x0F56
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__spare_2
+*/
+#define VL53L1_DSS_CALC__SPARE_3 0x0F57
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__spare_3
+*/
+#define VL53L1_DSS_CALC__SPARE_4 0x0F58
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__spare_4
+*/
+#define VL53L1_DSS_CALC__SPARE_5 0x0F59
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__spare_5
+*/
+#define VL53L1_DSS_CALC__SPARE_6 0x0F5A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__spare_6
+*/
+#define VL53L1_DSS_CALC__SPARE_7 0x0F5B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__spare_7
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_0 0x0F5C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_0
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_1 0x0F5D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_1
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_2 0x0F5E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_2
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_3 0x0F5F
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_3
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_4 0x0F60
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_4
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_5 0x0F61
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_5
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_6 0x0F62
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_6
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_7 0x0F63
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_7
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_8 0x0F64
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_8
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_9 0x0F65
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_9
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_10 0x0F66
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_10
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_11 0x0F67
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_11
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_12 0x0F68
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_12
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_13 0x0F69
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_13
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_14 0x0F6A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_14
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_15 0x0F6B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_15
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_16 0x0F6C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_16
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_17 0x0F6D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_17
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_18 0x0F6E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_18
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_19 0x0F6F
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_19
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_20 0x0F70
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_20
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_21 0x0F71
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_21
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_22 0x0F72
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_22
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_23 0x0F73
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_23
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_24 0x0F74
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_24
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_25 0x0F75
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_25
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_26 0x0F76
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_26
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_27 0x0F77
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_27
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_28 0x0F78
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_28
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_29 0x0F79
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_29
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_30 0x0F7A
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_30
+*/
+#define VL53L1_DSS_CALC__USER_ROI_SPAD_EN_31 0x0F7B
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_31
+*/
+#define VL53L1_DSS_CALC__USER_ROI_0 0x0F7C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_0
+*/
+#define VL53L1_DSS_CALC__USER_ROI_1 0x0F7D
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_1
+*/
+#define VL53L1_DSS_CALC__MODE_ROI_0 0x0F7E
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__mode_roi_0
+*/
+#define VL53L1_DSS_CALC__MODE_ROI_1 0x0F7F
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_calc']
+
+ fields: \n
+ - [7:0] = dss_calc__mode_roi_1
+*/
+#define VL53L1_SIGMA_ESTIMATOR_CALC__SPARE_0 0x0F80
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'sigma_est_spare']
+
+ fields: \n
+ - [7:0] = sigma_estimator_calc__spare_0
+*/
+#define VL53L1_VHV_RESULT__PEAK_SIGNAL_RATE_MCPS 0x0F82
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['patch_results', 'vhv_results']
+
+ fields: \n
+ - [15:0] = vhv_result__peak_signal_rate_mcps
+*/
+#define VL53L1_VHV_RESULT__PEAK_SIGNAL_RATE_MCPS_HI 0x0F82
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_VHV_RESULT__PEAK_SIGNAL_RATE_MCPS_LO 0x0F83
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_VHV_RESULT__SIGNAL_TOTAL_EVENTS_REF 0x0F84
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['patch_results', 'vhv_results']
+
+ fields: \n
+ - [31:0] = vhv_result__signal_total_events_ref
+*/
+#define VL53L1_VHV_RESULT__SIGNAL_TOTAL_EVENTS_REF_3 0x0F84
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_VHV_RESULT__SIGNAL_TOTAL_EVENTS_REF_2 0x0F85
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_VHV_RESULT__SIGNAL_TOTAL_EVENTS_REF_1 0x0F86
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_VHV_RESULT__SIGNAL_TOTAL_EVENTS_REF_0 0x0F87
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PHASECAL_RESULT__PHASE_OUTPUT_REF 0x0F88
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['patch_results', 'phasecal_results']
+
+ fields: \n
+ - [15:0] = phasecal_result__normalised_phase_ref
+*/
+#define VL53L1_PHASECAL_RESULT__PHASE_OUTPUT_REF_HI 0x0F88
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_PHASECAL_RESULT__PHASE_OUTPUT_REF_LO 0x0F89
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_DSS_RESULT__TOTAL_RATE_PER_SPAD 0x0F8A
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['patch_results', 'dss_results']
+
+ fields: \n
+ - [15:0] = dss_result__total_rate_per_spad
+*/
+#define VL53L1_DSS_RESULT__TOTAL_RATE_PER_SPAD_HI 0x0F8A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_DSS_RESULT__TOTAL_RATE_PER_SPAD_LO 0x0F8B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_DSS_RESULT__ENABLED_BLOCKS 0x0F8C
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['patch_results', 'dss_results']
+
+ fields: \n
+ - [7:0] = dss_result__enabled_blocks
+*/
+#define VL53L1_DSS_RESULT__NUM_REQUESTED_SPADS 0x0F8E
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['patch_results', 'dss_results']
+
+ fields: \n
+ - [15:0] = dss_result__num_requested_spads (fixed point 8.8)
+*/
+#define VL53L1_DSS_RESULT__NUM_REQUESTED_SPADS_HI 0x0F8E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_DSS_RESULT__NUM_REQUESTED_SPADS_LO 0x0F8F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MM_RESULT__INNER_INTERSECTION_RATE 0x0F92
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['patch_results', 'mm_results']
+
+ fields: \n
+ - [15:0] = mm_result__inner_intersection_rate
+*/
+#define VL53L1_MM_RESULT__INNER_INTERSECTION_RATE_HI 0x0F92
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MM_RESULT__INNER_INTERSECTION_RATE_LO 0x0F93
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MM_RESULT__OUTER_COMPLEMENT_RATE 0x0F94
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['patch_results', 'mm_results']
+
+ fields: \n
+ - [15:0] = mm_result__outer_complement_rate
+*/
+#define VL53L1_MM_RESULT__OUTER_COMPLEMENT_RATE_HI 0x0F94
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MM_RESULT__OUTER_COMPLEMENT_RATE_LO 0x0F95
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MM_RESULT__TOTAL_OFFSET 0x0F96
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['patch_results', 'mm_results']
+
+ fields: \n
+ - [15:0] = mm_result__total_offset
+*/
+#define VL53L1_MM_RESULT__TOTAL_OFFSET_HI 0x0F96
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_MM_RESULT__TOTAL_OFFSET_LO 0x0F97
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_XTALK_CALC__XTALK_FOR_ENABLED_SPADS 0x0F98
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 23
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['patch_results', 'xtalk_calc']
+
+ fields: \n
+ - [23:0] = xtalk_calc__xtalk_for_enabled_spads (fixed point 11.13)
+*/
+#define VL53L1_XTALK_CALC__XTALK_FOR_ENABLED_SPADS_3 0x0F98
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_XTALK_CALC__XTALK_FOR_ENABLED_SPADS_2 0x0F99
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_XTALK_CALC__XTALK_FOR_ENABLED_SPADS_1 0x0F9A
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_XTALK_CALC__XTALK_FOR_ENABLED_SPADS_0 0x0F9B
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_XTALK_RESULT__AVG_XTALK_USER_ROI_KCPS 0x0F9C
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 23
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['patch_results', 'xtalk_results']
+
+ fields: \n
+ - [23:0] = xtalk_result__avg_xtalk_user_roi_kcps (fixed point 11.13)
+*/
+#define VL53L1_XTALK_RESULT__AVG_XTALK_USER_ROI_KCPS_3 0x0F9C
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_XTALK_RESULT__AVG_XTALK_USER_ROI_KCPS_2 0x0F9D
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_XTALK_RESULT__AVG_XTALK_USER_ROI_KCPS_1 0x0F9E
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_XTALK_RESULT__AVG_XTALK_USER_ROI_KCPS_0 0x0F9F
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_XTALK_RESULT__AVG_XTALK_MM_INNER_ROI_KCPS 0x0FA0
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 23
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['patch_results', 'xtalk_results']
+
+ fields: \n
+ - [23:0] = xtalk_result__avg_xtalk_mm_inner_roi_kcps (fixed point 11.13)
+*/
+#define VL53L1_XTALK_RESULT__AVG_XTALK_MM_INNER_ROI_KCPS_3 0x0FA0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_XTALK_RESULT__AVG_XTALK_MM_INNER_ROI_KCPS_2 0x0FA1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_XTALK_RESULT__AVG_XTALK_MM_INNER_ROI_KCPS_1 0x0FA2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_XTALK_RESULT__AVG_XTALK_MM_INNER_ROI_KCPS_0 0x0FA3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_XTALK_RESULT__AVG_XTALK_MM_OUTER_ROI_KCPS 0x0FA4
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 23
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['patch_results', 'xtalk_results']
+
+ fields: \n
+ - [23:0] = xtalk_result__avg_xtalk_mm_outer_roi_kcps (fixed point 11.13)
+*/
+#define VL53L1_XTALK_RESULT__AVG_XTALK_MM_OUTER_ROI_KCPS_3 0x0FA4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_XTALK_RESULT__AVG_XTALK_MM_OUTER_ROI_KCPS_2 0x0FA5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_XTALK_RESULT__AVG_XTALK_MM_OUTER_ROI_KCPS_1 0x0FA6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_XTALK_RESULT__AVG_XTALK_MM_OUTER_ROI_KCPS_0 0x0FA7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGE_RESULT__ACCUM_PHASE 0x0FA8
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['patch_results', 'range_results']
+
+ fields: \n
+ - [31:0] = range_result__accum_phase
+*/
+#define VL53L1_RANGE_RESULT__ACCUM_PHASE_3 0x0FA8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGE_RESULT__ACCUM_PHASE_2 0x0FA9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGE_RESULT__ACCUM_PHASE_1 0x0FAA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGE_RESULT__ACCUM_PHASE_0 0x0FAB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGE_RESULT__OFFSET_CORRECTED_RANGE 0x0FAC
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['patch_results', 'range_results']
+
+ fields: \n
+ - [15:0] = range_result__offset_corrected_range
+*/
+#define VL53L1_RANGE_RESULT__OFFSET_CORRECTED_RANGE_HI 0x0FAC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_RANGE_RESULT__OFFSET_CORRECTED_RANGE_LO 0x0FAD
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_PHASECAL_RESULT__VCSEL_START 0x0FAE
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['shadow_system_results', 'histogram_results']
+
+ fields: \n
+ - [7:0] = shadow_phasecal_result__vcsel_start
+*/
+#define VL53L1_SHADOW_RESULT__INTERRUPT_STATUS 0x0FB0
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [2:0] = shadow_int_status
+ - [4:3] = shadow_int_error_status
+ - [5] = shadow_gph_id_gpio_status
+*/
+#define VL53L1_SHADOW_RESULT__RANGE_STATUS 0x0FB1
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [4:0] = shadow_range_status
+ - [5] = shadow_max_threshold_hit
+ - [6] = shadow_min_threshold_hit
+ - [7] = shadow_gph_id_range_status
+*/
+#define VL53L1_SHADOW_RESULT__REPORT_STATUS 0x0FB2
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [3:0] = shadow_report_status
+*/
+#define VL53L1_SHADOW_RESULT__STREAM_COUNT 0x0FB3
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [7:0] = shadow_result__stream_count
+*/
+#define VL53L1_SHADOW_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0 0x0FB4
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__dss_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+#define VL53L1_SHADOW_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0_HI 0x0FB4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0_LO 0x0FB5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD0 0x0FB6
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__peak_signal_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+#define VL53L1_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD0_HI 0x0FB6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD0_LO 0x0FB7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__AMBIENT_COUNT_RATE_MCPS_SD0 0x0FB8
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__ambient_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+#define VL53L1_SHADOW_RESULT__AMBIENT_COUNT_RATE_MCPS_SD0_HI 0x0FB8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__AMBIENT_COUNT_RATE_MCPS_SD0_LO 0x0FB9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__SIGMA_SD0 0x0FBA
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__sigma_sd0 (fixed point 14.2)
+*/
+#define VL53L1_SHADOW_RESULT__SIGMA_SD0_HI 0x0FBA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__SIGMA_SD0_LO 0x0FBB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__PHASE_SD0 0x0FBC
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__phase_sd0 (fixed point 5.11)
+*/
+#define VL53L1_SHADOW_RESULT__PHASE_SD0_HI 0x0FBC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__PHASE_SD0_LO 0x0FBD
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0 0x0FBE
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__final_crosstalk_corrected_range_mm_sd0
+*/
+#define VL53L1_SHADOW_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0_HI 0x0FBE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0_LO 0x0FBF
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_CROSSTALK_CORRECTED_MCPS_SD0 0x0FC0
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0 (fixed point 9.7)
+*/
+#define VL53L1_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_CROSSTALK_CORRECTED_MCPS_SD0_HI 0x0FC0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_CROSSTALK_CORRECTED_MCPS_SD0_LO 0x0FC1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__MM_INNER_ACTUAL_EFFECTIVE_SPADS_SD0 0x0FC2
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__mm_inner_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+#define VL53L1_SHADOW_RESULT__MM_INNER_ACTUAL_EFFECTIVE_SPADS_SD0_HI 0x0FC2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__MM_INNER_ACTUAL_EFFECTIVE_SPADS_SD0_LO 0x0FC3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__MM_OUTER_ACTUAL_EFFECTIVE_SPADS_SD0 0x0FC4
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__mm_outer_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+#define VL53L1_SHADOW_RESULT__MM_OUTER_ACTUAL_EFFECTIVE_SPADS_SD0_HI 0x0FC4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__MM_OUTER_ACTUAL_EFFECTIVE_SPADS_SD0_LO 0x0FC5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__AVG_SIGNAL_COUNT_RATE_MCPS_SD0 0x0FC6
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__avg_signal_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+#define VL53L1_SHADOW_RESULT__AVG_SIGNAL_COUNT_RATE_MCPS_SD0_HI 0x0FC6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__AVG_SIGNAL_COUNT_RATE_MCPS_SD0_LO 0x0FC7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD1 0x0FC8
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__dss_actual_effective_spads_sd1 (fixed point 8.8)
+*/
+#define VL53L1_SHADOW_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD1_HI 0x0FC8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD1_LO 0x0FC9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD1 0x0FCA
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__peak_signal_count_rate_mcps_sd1 (fixed point 9.7)
+*/
+#define VL53L1_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD1_HI 0x0FCA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__PEAK_SIGNAL_COUNT_RATE_MCPS_SD1_LO 0x0FCB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__AMBIENT_COUNT_RATE_MCPS_SD1 0x0FCC
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__ambient_count_rate_mcps_sd1 (fixed point 9.7)
+*/
+#define VL53L1_SHADOW_RESULT__AMBIENT_COUNT_RATE_MCPS_SD1_HI 0x0FCC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__AMBIENT_COUNT_RATE_MCPS_SD1_LO 0x0FCD
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__SIGMA_SD1 0x0FCE
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__sigma_sd1 (fixed point 14.2)
+*/
+#define VL53L1_SHADOW_RESULT__SIGMA_SD1_HI 0x0FCE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__SIGMA_SD1_LO 0x0FCF
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__PHASE_SD1 0x0FD0
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__phase_sd1 (fixed point 5.11)
+*/
+#define VL53L1_SHADOW_RESULT__PHASE_SD1_HI 0x0FD0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__PHASE_SD1_LO 0x0FD1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD1 0x0FD2
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__final_crosstalk_corrected_range_mm_sd1
+*/
+#define VL53L1_SHADOW_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD1_HI 0x0FD2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD1_LO 0x0FD3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__SPARE_0_SD1 0x0FD4
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__spare_0_sd1
+*/
+#define VL53L1_SHADOW_RESULT__SPARE_0_SD1_HI 0x0FD4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__SPARE_0_SD1_LO 0x0FD5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__SPARE_1_SD1 0x0FD6
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__spare_1_sd1
+*/
+#define VL53L1_SHADOW_RESULT__SPARE_1_SD1_HI 0x0FD6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__SPARE_1_SD1_LO 0x0FD7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__SPARE_2_SD1 0x0FD8
+/*!<
+ type: uint16_t \n
+ default: 0x0000 \n
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [15:0] = shadow_result__spare_2_sd1
+*/
+#define VL53L1_SHADOW_RESULT__SPARE_2_SD1_HI 0x0FD8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__SPARE_2_SD1_LO 0x0FD9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT__SPARE_3_SD1 0x0FDA
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [7:0] = shadow_result__spare_3_sd1
+*/
+#define VL53L1_SHADOW_RESULT__THRESH_INFO 0x0FDB
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['shadow_system_results', 'results']
+
+ fields: \n
+ - [3:0] = shadow_result__distance_int_info
+ - [7:4] = shadow_result__rate_int_info
+*/
+#define VL53L1_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0 0x0FDC
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = shadow_result_core__ambient_window_events_sd0
+*/
+#define VL53L1_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0_3 0x0FDC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0_2 0x0FDD
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0_1 0x0FDE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0_0 0x0FDF
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD0 0x0FE0
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = shadow_result_core__ranging_total_events_sd0
+*/
+#define VL53L1_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD0_3 0x0FE0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD0_2 0x0FE1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD0_1 0x0FE2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD0_0 0x0FE3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD0 0x0FE4
+/*!<
+ type: int32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = shadow_result_core__signal_total_events_sd0
+*/
+#define VL53L1_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD0_3 0x0FE4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD0_2 0x0FE5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD0_1 0x0FE6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD0_0 0x0FE7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD0 0x0FE8
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = shadow_result_core__total_periods_elapsed_sd0
+*/
+#define VL53L1_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD0_3 0x0FE8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD0_2 0x0FE9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD0_1 0x0FEA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD0_0 0x0FEB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD1 0x0FEC
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = shadow_result_core__ambient_window_events_sd1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD1_3 0x0FEC
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD1_2 0x0FED
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD1_1 0x0FEE
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD1_0 0x0FEF
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD1 0x0FF0
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = shadow_result_core__ranging_total_events_sd1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD1_3 0x0FF0
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD1_2 0x0FF1
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD1_1 0x0FF2
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__RANGING_TOTAL_EVENTS_SD1_0 0x0FF3
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD1 0x0FF4
+/*!<
+ type: int32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = shadow_result_core__signal_total_events_sd1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD1_3 0x0FF4
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD1_2 0x0FF5
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD1_1 0x0FF6
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__SIGNAL_TOTAL_EVENTS_SD1_0 0x0FF7
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD1 0x0FF8
+/*!<
+ type: uint32_t \n
+ default: 0x00000000 \n
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ groups: \n
+ ['shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [31:0] = shadow_result_core__total_periods_elapsed_sd1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD1_3 0x0FF8
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD1_2 0x0FF9
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD1_1 0x0FFA
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__TOTAL_PERIODS_ELAPSED_SD1_0 0x0FFB
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+*/
+#define VL53L1_SHADOW_RESULT_CORE__SPARE_0 0x0FFC
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['shadow_core_results', 'ranging_core_results']
+
+ fields: \n
+ - [7:0] = shadow_result_core__spare_0
+*/
+#define VL53L1_SHADOW_PHASECAL_RESULT__REFERENCE_PHASE_HI 0x0FFE
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['shadow_system_results', 'histogram_results']
+
+ fields: \n
+ - [7:0] = shadow_phasecal_result__reference_phase_hi
+*/
+#define VL53L1_SHADOW_PHASECAL_RESULT__REFERENCE_PHASE_LO 0x0FFF
+/*!<
+ type: uint8_t \n
+ default: 0x00 \n
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ groups: \n
+ ['shadow_system_results', 'histogram_results']
+
+ fields: \n
+ - [7:0] = shadow_phasecal_result__reference_phase_lo
+*/
+
+/** @} VL53L1_register_DefineRegisters_group */
+
+
+#endif
+
diff --git a/src/lib/vl53l1/core/inc/vl53l1_register_settings.h b/src/lib/vl53l1/core/inc/vl53l1_register_settings.h
new file mode 100644
index 0000000000..7f2032bb96
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_register_settings.h
@@ -0,0 +1,188 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*******************************************************************************/
+
+/**
+ * @file vl53l1_register_settings.h
+ *
+ * @brief Device register setting defines.
+ */
+
+#ifndef _VL53L1_REGISTER_SETTINGS_H_
+#define _VL53L1_REGISTER_SETTINGS_H_
+
+
+/** @defgroup VL53L1_RegisterSettings_group Functionality
+ * @brief Defines the register settings for key device
+ * configuration registers
+ * @{
+ */
+
+/** @defgroup VL53L1_DeviceSchedulerMode_group - Pseudo, Streaming & Hist
+ * @brief Values below match the bit positions in the SYSTEM__MODE_START
+ * register do not change
+ * @{
+ */
+
+#define VL53L1_DEVICESCHEDULERMODE_PSEUDO_SOLO 0x00
+#define VL53L1_DEVICESCHEDULERMODE_STREAMING 0x01
+#define VL53L1_DEVICESCHEDULERMODE_HISTOGRAM 0x02
+
+/** @} end of VL53L1_DeviceReadoutMode_group */
+
+/** @defgroup VL53L1_DeviceReadoutMode_group - Single, Dual, Split & Manual
+ * @brief Values below match the bit positions in the SYSTEM__MODE_START
+ * register do not change
+ * @{
+ */
+
+#define VL53L1_DEVICEREADOUTMODE_SINGLE_SD (0x00 << 2)
+#define VL53L1_DEVICEREADOUTMODE_DUAL_SD (0x01 << 2)
+#define VL53L1_DEVICEREADOUTMODE_SPLIT_READOUT (0x02 << 2)
+#define VL53L1_DEVICEREADOUTMODE_SPLIT_MANUAL (0x03 << 2)
+
+/** @} end of VL53L1_DeviceReadoutMode_group */
+
+/** @defgroup VL53L1_DeviceMeasurementMode_group - SingleShot, BackToBack & timed
+ * @brief Values below match the bit positions in the SYSTEM__MODE_START
+ * register do not change
+ * @{
+ */
+
+/*
+#define VL53L1_DEVICEMEASUREMENTMODE_STOP 0x00
+#define VL53L1_DEVICEMEASUREMENTMODE_SINGLESHOT 0x10
+#define VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK 0x20
+#define VL53L1_DEVICEMEASUREMENTMODE_TIMED 0x40
+#define VL53L1_DEVICEMEASUREMENTMODE_ABORT 0x80
+*/
+#define VL53L1_DEVICEMEASUREMENTMODE_MODE_MASK 0xF0
+#define VL53L1_DEVICEMEASUREMENTMODE_STOP_MASK 0x0F
+
+#define VL53L1_GROUPEDPARAMETERHOLD_ID_MASK 0x02
+
+/** @} end of VL53L1_DeviceMeasurementMode_group */
+
+#define VL53L1_EWOK_I2C_DEV_ADDR_DEFAULT 0x29
+ /*!< Device default 7-bit I2C address */
+#define VL53L1_OSC_FREQUENCY 0x00
+#define VL53L1_OSC_TRIM_DEFAULT 0x00
+#define VL53L1_OSC_FREQ_SET_DEFAULT 0x00
+
+#define VL53L1_RANGE_HISTOGRAM_REF 0x08
+#define VL53L1_RANGE_HISTOGRAM_RET 0x10
+#define VL53L1_RANGE_HISTOGRAM_BOTH 0x18
+#define VL53L1_RANGE_HISTOGRAM_INIT 0x20
+#define VL53L1_RANGE_VHV_INIT 0x40
+
+/* Result Status */
+#define VL53L1_RESULT_RANGE_STATUS 0x1F
+
+/* */
+#define VL53L1_SYSTEM__SEED_CONFIG__MANUAL 0x00
+#define VL53L1_SYSTEM__SEED_CONFIG__STANDARD 0x01
+#define VL53L1_SYSTEM__SEED_CONFIG__EVEN_UPDATE_ONLY 0x02
+
+/* Interrupt Config */
+#define VL53L1_INTERRUPT_CONFIG_LEVEL_LOW 0x00
+#define VL53L1_INTERRUPT_CONFIG_LEVEL_HIGH 0x01
+#define VL53L1_INTERRUPT_CONFIG_OUT_OF_WINDOW 0x02
+#define VL53L1_INTERRUPT_CONFIG_IN_WINDOW 0x03
+#define VL53L1_INTERRUPT_CONFIG_NEW_SAMPLE_READY 0x20
+
+/* Interrupt Clear */
+#define VL53L1_CLEAR_RANGE_INT 0x01
+#define VL53L1_CLEAR_ERROR_INT 0x02
+
+/* Sequence Config */
+#define VL53L1_SEQUENCE_VHV_EN 0x01
+#define VL53L1_SEQUENCE_PHASECAL_EN 0x02
+#define VL53L1_SEQUENCE_REFERENCE_PHASE_EN 0x04
+#define VL53L1_SEQUENCE_DSS1_EN 0x08
+#define VL53L1_SEQUENCE_DSS2_EN 0x10
+#define VL53L1_SEQUENCE_MM1_EN 0x20
+#define VL53L1_SEQUENCE_MM2_EN 0x40
+#define VL53L1_SEQUENCE_RANGE_EN 0x80
+
+/* defines for DSS__ROI_CONTROL */
+#define VL53L1_DSS_CONTROL__ROI_SUBTRACT 0x20
+#define VL53L1_DSS_CONTROL__ROI_INTERSECT 0x10
+
+#define VL53L1_DSS_CONTROL__MODE_DISABLED 0x00
+#define VL53L1_DSS_CONTROL__MODE_TARGET_RATE 0x01
+#define VL53L1_DSS_CONTROL__MODE_EFFSPADS 0x02
+#define VL53L1_DSS_CONTROL__MODE_BLOCKSELECT 0x03
+
+/* SPAD Readout defines
+ *
+ * 7:6 - SPAD_IN_SEL_REF
+ * 5:4 - SPAD_IN_SEL_RTN
+ * 2 - SPAD_PS_BYPASS
+ * 0 - SPAD_EN_PULSE_EXTENDER
+ */
+
+#define VL53L1_RANGING_CORE__SPAD_READOUT__STANDARD 0x45
+#define VL53L1_RANGING_CORE__SPAD_READOUT__RETURN_ARRAY_ONLY 0x05
+#define VL53L1_RANGING_CORE__SPAD_READOUT__REFERENCE_ARRAY_ONLY 0x55
+#define VL53L1_RANGING_CORE__SPAD_READOUT__RETURN_SPLIT_ARRAY 0x25
+#define VL53L1_RANGING_CORE__SPAD_READOUT__CALIB_PULSES 0xF5
+
+
+#define VL53L1_LASER_SAFETY__KEY_VALUE 0x6C
+
+/* Range Status defines
+ *
+ * 7 - GPH ID
+ * 6 - Min threshold hit
+ * 5 - Max threshold hit
+ * 4:0 - Range Status
+ */
+
+#define VL53L1_RANGE_STATUS__RANGE_STATUS_MASK 0x1F
+#define VL53L1_RANGE_STATUS__MAX_THRESHOLD_HIT_MASK 0x20
+#define VL53L1_RANGE_STATUS__MIN_THRESHOLD_HIT_MASK 0x40
+#define VL53L1_RANGE_STATUS__GPH_ID_RANGE_STATUS_MASK 0x80
+
+/* Interrupt Status defines
+ *
+ * 5 - GPH ID
+ * 4:3 - Interrupt Error Status
+ * 2:0 - Interrupt Status
+ */
+
+#define VL53L1_INTERRUPT_STATUS__INT_STATUS_MASK 0x07
+#define VL53L1_INTERRUPT_STATUS__INT_ERROR_STATUS_MASK 0x18
+#define VL53L1_INTERRUPT_STATUS__GPH_ID_INT_STATUS_MASK 0x20
+
+/** @} end of VL53L1_RegisterSettings_group */
+
+
+#endif
+
+/* _VL53L1_REGISTER_SETTINGS_H_ */
+
+
diff --git a/src/lib/vl53l1/core/inc/vl53l1_register_structs.h b/src/lib/vl53l1/core/inc/vl53l1_register_structs.h
new file mode 100644
index 0000000000..80a49b7c25
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_register_structs.h
@@ -0,0 +1,4371 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+******************************************************************************/
+
+/**
+ * @file vl53l1_register_structs.h
+ * @brief VL53L1 Register Structure definitions
+ */
+
+#ifndef _VL53L1_REGISTER_STRUCTS_H_
+#define _VL53L1_REGISTER_STRUCTS_H_
+
+#include "vl53l1_types.h"
+#include "vl53l1_register_map.h"
+
+#define VL53L1_STATIC_NVM_MANAGED_I2C_INDEX VL53L1_I2C_SLAVE__DEVICE_ADDRESS
+#define VL53L1_CUSTOMER_NVM_MANAGED_I2C_INDEX VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_REF_0
+#define VL53L1_STATIC_CONFIG_I2C_INDEX VL53L1_DSS_CONFIG__TARGET_TOTAL_RATE_MCPS
+#define VL53L1_GENERAL_CONFIG_I2C_INDEX VL53L1_GPH_CONFIG__STREAM_COUNT_UPDATE_VALUE
+#define VL53L1_TIMING_CONFIG_I2C_INDEX VL53L1_MM_CONFIG__TIMEOUT_MACROP_A_HI
+#define VL53L1_DYNAMIC_CONFIG_I2C_INDEX VL53L1_SYSTEM__GROUPED_PARAMETER_HOLD_0
+#define VL53L1_SYSTEM_CONTROL_I2C_INDEX VL53L1_POWER_MANAGEMENT__GO1_POWER_FORCE
+#define VL53L1_SYSTEM_RESULTS_I2C_INDEX VL53L1_RESULT__INTERRUPT_STATUS
+#define VL53L1_CORE_RESULTS_I2C_INDEX VL53L1_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0
+#define VL53L1_DEBUG_RESULTS_I2C_INDEX VL53L1_PHASECAL_RESULT__REFERENCE_PHASE
+#define VL53L1_NVM_COPY_DATA_I2C_INDEX VL53L1_IDENTIFICATION__MODEL_ID
+#define VL53L1_PREV_SHADOW_SYSTEM_RESULTS_I2C_INDEX VL53L1_PREV_SHADOW_RESULT__INTERRUPT_STATUS
+#define VL53L1_PREV_SHADOW_CORE_RESULTS_I2C_INDEX VL53L1_PREV_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0
+#define VL53L1_PATCH_DEBUG_I2C_INDEX VL53L1_RESULT__DEBUG_STATUS
+#define VL53L1_GPH_GENERAL_CONFIG_I2C_INDEX VL53L1_GPH__SYSTEM__THRESH_RATE_HIGH
+#define VL53L1_GPH_STATIC_CONFIG_I2C_INDEX VL53L1_GPH__DSS_CONFIG__ROI_MODE_CONTROL
+#define VL53L1_GPH_TIMING_CONFIG_I2C_INDEX VL53L1_GPH__MM_CONFIG__TIMEOUT_MACROP_A_HI
+#define VL53L1_FW_INTERNAL_I2C_INDEX VL53L1_FIRMWARE__INTERNAL_STREAM_COUNT_DIV
+#define VL53L1_PATCH_RESULTS_I2C_INDEX VL53L1_DSS_CALC__ROI_CTRL
+#define VL53L1_SHADOW_SYSTEM_RESULTS_I2C_INDEX VL53L1_SHADOW_PHASECAL_RESULT__VCSEL_START
+#define VL53L1_SHADOW_CORE_RESULTS_I2C_INDEX VL53L1_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0
+
+#define VL53L1_STATIC_NVM_MANAGED_I2C_SIZE_BYTES 11
+#define VL53L1_CUSTOMER_NVM_MANAGED_I2C_SIZE_BYTES 23
+#define VL53L1_STATIC_CONFIG_I2C_SIZE_BYTES 32
+#define VL53L1_GENERAL_CONFIG_I2C_SIZE_BYTES 22
+#define VL53L1_TIMING_CONFIG_I2C_SIZE_BYTES 23
+#define VL53L1_DYNAMIC_CONFIG_I2C_SIZE_BYTES 18
+#define VL53L1_SYSTEM_CONTROL_I2C_SIZE_BYTES 5
+#define VL53L1_SYSTEM_RESULTS_I2C_SIZE_BYTES 44
+#define VL53L1_CORE_RESULTS_I2C_SIZE_BYTES 33
+#define VL53L1_DEBUG_RESULTS_I2C_SIZE_BYTES 56
+#define VL53L1_NVM_COPY_DATA_I2C_SIZE_BYTES 49
+#define VL53L1_PREV_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES 44
+#define VL53L1_PREV_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES 33
+#define VL53L1_PATCH_DEBUG_I2C_SIZE_BYTES 2
+#define VL53L1_GPH_GENERAL_CONFIG_I2C_SIZE_BYTES 5
+#define VL53L1_GPH_STATIC_CONFIG_I2C_SIZE_BYTES 6
+#define VL53L1_GPH_TIMING_CONFIG_I2C_SIZE_BYTES 16
+#define VL53L1_FW_INTERNAL_I2C_SIZE_BYTES 2
+#define VL53L1_PATCH_RESULTS_I2C_SIZE_BYTES 90
+#define VL53L1_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES 82
+#define VL53L1_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES 33
+
+
+/**
+ * @struct VL53L1_static_nvm_managed_t
+ *
+ * - registers = 10
+ * - first_index = 1 (0x0001)
+ * - last _index = 11 (0x000B)
+ * - i2c_size = 11
+ */
+
+typedef struct {
+ uint8_t i2c_slave__device_address;
+/*!<
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [6:0] = i2c_slave_device_address
+*/
+ uint8_t ana_config__vhv_ref_sel_vddpix;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = ref_sel_vddpix
+*/
+ uint8_t ana_config__vhv_ref_sel_vquench;
+/*!<
+ info: \n
+ - msb = 6
+ - lsb = 3
+ - i2c_size = 1
+
+ fields: \n
+ - [6:3] = ref_sel_vquench
+*/
+ uint8_t ana_config__reg_avdd1v2_sel;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [1:0] = reg_avdd1v2_sel
+*/
+ uint8_t ana_config__fast_osc__trim;
+/*!<
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [6:0] = fast_osc_trim
+*/
+ uint16_t osc_measured__fast_osc__frequency;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = osc_frequency (fixed point 4.12)
+*/
+ uint8_t vhv_config__timeout_macrop_loop_bound;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [1:0] = vhv_timeout__macrop
+ - [7:2] = vhv_loop_bound
+*/
+ uint8_t vhv_config__count_thresh;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = vhv_count_thresh
+*/
+ uint8_t vhv_config__offset;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [5:0] = vhv_step_val
+*/
+ uint8_t vhv_config__init;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7] = vhv0_init_enable
+ - [5:0] = vhv0_init_value
+*/
+} VL53L1_static_nvm_managed_t;
+
+
+/**
+ * @struct VL53L1_customer_nvm_managed_t
+ *
+ * - registers = 16
+ * - first_index = 13 (0x000D)
+ * - last _index = 34 (0x0022)
+ * - i2c_size = 23
+ */
+
+typedef struct {
+ uint8_t global_config__spad_enables_ref_0;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_ref_0
+*/
+ uint8_t global_config__spad_enables_ref_1;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_ref_1
+*/
+ uint8_t global_config__spad_enables_ref_2;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_ref_2
+*/
+ uint8_t global_config__spad_enables_ref_3;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_ref_3
+*/
+ uint8_t global_config__spad_enables_ref_4;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_ref_4
+*/
+ uint8_t global_config__spad_enables_ref_5;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = spad_enables_ref_5
+*/
+ uint8_t global_config__ref_en_start_select;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = ref_en_start_select
+*/
+ uint8_t ref_spad_man__num_requested_ref_spads;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [5:0] = ref_spad_man__num_requested_ref_spad
+*/
+ uint8_t ref_spad_man__ref_location;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [1:0] = ref_spad_man__ref_location
+*/
+ uint16_t algo__crosstalk_compensation_plane_offset_kcps;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = crosstalk_compensation_plane_offset_kcps (fixed point 7.9)
+*/
+ int16_t algo__crosstalk_compensation_x_plane_gradient_kcps;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = crosstalk_compensation_x_plane_gradient_kcps (fixed point 5.11)
+*/
+ int16_t algo__crosstalk_compensation_y_plane_gradient_kcps;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = crosstalk_compensation_y_plane_gradient_kcps (fixed point 5.11)
+*/
+ uint16_t ref_spad_char__total_rate_target_mcps;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = ref_spad_char__total_rate_target_mcps (fixed point 9.7)
+*/
+ int16_t algo__part_to_part_range_offset_mm;
+/*!<
+ info: \n
+ - msb = 12
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [12:0] = part_to_part_offset_mm (fixed point 11.2)
+*/
+ int16_t mm_config__inner_offset_mm;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = mm_config__inner_offset_mm
+*/
+ int16_t mm_config__outer_offset_mm;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = mm_config__outer_offset_mm
+*/
+} VL53L1_customer_nvm_managed_t;
+
+
+/**
+ * @struct VL53L1_static_config_t
+ *
+ * - registers = 30
+ * - first_index = 36 (0x0024)
+ * - last _index = 67 (0x0043)
+ * - i2c_size = 32
+ */
+
+typedef struct {
+ uint16_t dss_config__target_total_rate_mcps;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = dss_config__target_total_rate_mcps (fixed point 9.7)
+*/
+ uint8_t debug__ctrl;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = enable_result_logging
+*/
+ uint8_t test_mode__ctrl;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = test_mode__cmd
+*/
+ uint8_t clk_gating__ctrl;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = clk_gate_en__mcu_bank
+ - [1] = clk_gate_en__mcu_patch_ctrl
+ - [2] = clk_gate_en__mcu_timers
+ - [3] = clk_gate_en__mcu_mult_div
+*/
+ uint8_t nvm_bist__ctrl;
+/*!<
+ info: \n
+ - msb = 4
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [2:0] = nvm_bist__cmd
+ - [4] = nvm_bist__ctrl
+*/
+ uint8_t nvm_bist__num_nvm_words;
+/*!<
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [6:0] = nvm_bist__num_nvm_words
+*/
+ uint8_t nvm_bist__start_address;
+/*!<
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [6:0] = nvm_bist__start_address
+*/
+ uint8_t host_if__status;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = host_interface
+*/
+ uint8_t pad_i2c_hv__config;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = pad_scl_sda__vmodeint_hv
+ - [1] = i2c_pad__test_hv
+ - [2] = pad_scl__fpen_hv
+ - [4:3] = pad_scl__progdel_hv
+ - [5] = pad_sda__fpen_hv
+ - [7:6] = pad_sda__progdel_hv
+*/
+ uint8_t pad_i2c_hv__extsup_config;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = pad_scl_sda__extsup_hv
+*/
+ uint8_t gpio_hv_pad__ctrl;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = gpio__extsup_hv
+ - [1] = gpio__vmodeint_hv
+*/
+ uint8_t gpio_hv_mux__ctrl;
+/*!<
+ info: \n
+ - msb = 4
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = gpio__mux_select_hv
+ - [4] = gpio__mux_active_high_hv
+*/
+ uint8_t gpio__tio_hv_status;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = gpio__tio_hv
+ - [1] = fresh_out_of_reset
+*/
+ uint8_t gpio__fio_hv_status;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 1
+ - i2c_size = 1
+
+ fields: \n
+ - [1] = gpio__fio_hv
+*/
+ uint8_t ana_config__spad_sel_pswidth;
+/*!<
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [2:0] = spad_sel_pswidth
+*/
+ uint8_t ana_config__vcsel_pulse_width_offset;
+/*!<
+ info: \n
+ - msb = 4
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [4:0] = vcsel_pulse_width_offset (fixed point 1.4)
+*/
+ uint8_t ana_config__fast_osc__config_ctrl;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = osc_config__latch_bypass
+*/
+ uint8_t sigma_estimator__effective_pulse_width_ns;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = sigma_estimator__eff_pulse_width
+*/
+ uint8_t sigma_estimator__effective_ambient_width_ns;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = sigma_estimator__eff_ambient_width
+*/
+ uint8_t sigma_estimator__sigma_ref_mm;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = sigma_estimator__sigma_ref
+*/
+ uint8_t algo__crosstalk_compensation_valid_height_mm;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = crosstalk_compensation_valid_height_mm
+*/
+ uint8_t spare_host_config__static_config_spare_0;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = static_config_spare_0
+*/
+ uint8_t spare_host_config__static_config_spare_1;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = static_config_spare_1
+*/
+ uint16_t algo__range_ignore_threshold_mcps;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = range_ignore_thresh_mcps (fixed point 3.13)
+*/
+ uint8_t algo__range_ignore_valid_height_mm;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = range_ignore_height_mm
+*/
+ uint8_t algo__range_min_clip;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = algo__range_min_clip_enable
+ - [7:1] = algo__range_min_clip_value_mm
+*/
+ uint8_t algo__consistency_check__tolerance;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = consistency_check_tolerance (fixed point 1.3)
+*/
+ uint8_t spare_host_config__static_config_spare_2;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = static_config_spare_2
+*/
+ uint8_t sd_config__reset_stages_msb;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = loop_init__clear_stage
+*/
+ uint8_t sd_config__reset_stages_lsb;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:4] = accum_reset__clear_stage
+ - [3:0] = count_reset__clear_stage
+*/
+} VL53L1_static_config_t;
+
+
+/**
+ * @struct VL53L1_general_config_t
+ *
+ * - registers = 17
+ * - first_index = 68 (0x0044)
+ * - last _index = 89 (0x0059)
+ * - i2c_size = 22
+ */
+
+typedef struct {
+ uint8_t gph_config__stream_count_update_value;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = stream_count_update_value
+*/
+ uint8_t global_config__stream_divider;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = stream_count_internal_div
+*/
+ uint8_t system__interrupt_config_gpio;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [1:0] = int_mode_distance
+ - [3:2] = int_mode_rate
+ - [4] = int_spare
+ - [5] = int_new_measure_ready
+ - [6] = int_no_target_en
+ - [7] = int_combined_mode
+*/
+ uint8_t cal_config__vcsel_start;
+/*!<
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [6:0] = cal_config__vcsel_start
+*/
+ uint16_t cal_config__repeat_rate;
+/*!<
+ info: \n
+ - msb = 11
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [11:0] = cal_config__repeat_rate
+*/
+ uint8_t global_config__vcsel_width;
+/*!<
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [6:0] = global_config__vcsel_width
+*/
+ uint8_t phasecal_config__timeout_macrop;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = phasecal_config__timeout_macrop
+*/
+ uint8_t phasecal_config__target;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = algo_phasecal_lim
+*/
+ uint8_t phasecal_config__override;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = phasecal_config__override
+*/
+ uint8_t dss_config__roi_mode_control;
+/*!<
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [1:0] = dss_config__input_mode
+ - [2] = calculate_roi_enable
+*/
+ uint16_t system__thresh_rate_high;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = thresh_rate_high (fixed point 9.7)
+*/
+ uint16_t system__thresh_rate_low;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = thresh_rate_low (fixed point 9.7)
+*/
+ uint16_t dss_config__manual_effective_spads_select;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = dss_config__manual_effective_spads_select
+*/
+ uint8_t dss_config__manual_block_select;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_config__manual_block_select
+*/
+ uint8_t dss_config__aperture_attenuation;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_config__aperture_attenuation
+*/
+ uint8_t dss_config__max_spads_limit;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_config__max_spads_limit
+*/
+ uint8_t dss_config__min_spads_limit;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_config__min_spads_limit
+*/
+} VL53L1_general_config_t;
+
+
+/**
+ * @struct VL53L1_timing_config_t
+ *
+ * - registers = 16
+ * - first_index = 90 (0x005A)
+ * - last _index = 112 (0x0070)
+ * - i2c_size = 23
+ */
+
+typedef struct {
+ uint8_t mm_config__timeout_macrop_a_hi;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = mm_config__config_timeout_macrop_a_hi
+*/
+ uint8_t mm_config__timeout_macrop_a_lo;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = mm_config__config_timeout_macrop_a_lo
+*/
+ uint8_t mm_config__timeout_macrop_b_hi;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = mm_config__config_timeout_macrop_b_hi
+*/
+ uint8_t mm_config__timeout_macrop_b_lo;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = mm_config__config_timeout_macrop_b_lo
+*/
+ uint8_t range_config__timeout_macrop_a_hi;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = range_timeout_overall_periods_macrop_a_hi
+*/
+ uint8_t range_config__timeout_macrop_a_lo;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = range_timeout_overall_periods_macrop_a_lo
+*/
+ uint8_t range_config__vcsel_period_a;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [5:0] = range_config__vcsel_period_a
+*/
+ uint8_t range_config__timeout_macrop_b_hi;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = range_timeout_overall_periods_macrop_b_hi
+*/
+ uint8_t range_config__timeout_macrop_b_lo;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = range_timeout_overall_periods_macrop_b_lo
+*/
+ uint8_t range_config__vcsel_period_b;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [5:0] = range_config__vcsel_period_b
+*/
+ uint16_t range_config__sigma_thresh;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = range_config__sigma_thresh (fixed point 14.2)
+*/
+ uint16_t range_config__min_count_rate_rtn_limit_mcps;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = range_config__min_count_rate_rtn_limit_mcps (fixed point 9.7)
+*/
+ uint8_t range_config__valid_phase_low;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = range_config__valid_phase_low (fixed point 5.3)
+*/
+ uint8_t range_config__valid_phase_high;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = range_config__valid_phase_high (fixed point 5.3)
+*/
+ uint32_t system__intermeasurement_period;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = intermeasurement_period
+*/
+ uint8_t system__fractional_enable;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = range_fractional_enable
+*/
+} VL53L1_timing_config_t;
+
+
+/**
+ * @struct VL53L1_dynamic_config_t
+ *
+ * - registers = 16
+ * - first_index = 113 (0x0071)
+ * - last _index = 130 (0x0082)
+ * - i2c_size = 18
+ */
+
+typedef struct {
+ uint8_t system__grouped_parameter_hold_0;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = grouped_parameter_hold
+ - [1] = grouped_parameter_hold_id
+*/
+ uint16_t system__thresh_high;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = thresh_high
+*/
+ uint16_t system__thresh_low;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = thresh_low
+*/
+ uint8_t system__enable_xtalk_per_quadrant;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = system__enable_xtalk_per_quadrant
+*/
+ uint8_t system__seed_config;
+/*!<
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [1:0] = system__seed_config
+ - [2] = system__fw_pause_ctrl
+*/
+ uint8_t sd_config__woi_sd0;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = sd_config__woi_sd0
+*/
+ uint8_t sd_config__woi_sd1;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = sd_config__woi_sd1
+*/
+ uint8_t sd_config__initial_phase_sd0;
+/*!<
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [6:0] = sd_config__initial_phase_sd0
+*/
+ uint8_t sd_config__initial_phase_sd1;
+/*!<
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [6:0] = sd_config__initial_phase_sd1
+*/
+ uint8_t system__grouped_parameter_hold_1;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = grouped_parameter_hold
+ - [1] = grouped_parameter_hold_id
+*/
+ uint8_t sd_config__first_order_select;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = sd_config__first_order_select_rtn
+ - [1] = sd_config__first_order_select_ref
+*/
+ uint8_t sd_config__quantifier;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = sd_config__quantifier
+*/
+ uint8_t roi_config__user_roi_centre_spad;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = user_roi_center_spad
+*/
+ uint8_t roi_config__user_roi_requested_global_xy_size;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = roi_config__user_roi_requested_global_xy_size
+*/
+ uint8_t system__sequence_config;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = sequence_vhv_en
+ - [1] = sequence_phasecal_en
+ - [2] = sequence_reference_phase_en
+ - [3] = sequence_dss1_en
+ - [4] = sequence_dss2_en
+ - [5] = sequence_mm1_en
+ - [6] = sequence_mm2_en
+ - [7] = sequence_range_en
+*/
+ uint8_t system__grouped_parameter_hold;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = grouped_parameter_hold
+ - [1] = grouped_parameter_hold_id
+*/
+} VL53L1_dynamic_config_t;
+
+
+/**
+ * @struct VL53L1_system_control_t
+ *
+ * - registers = 5
+ * - first_index = 131 (0x0083)
+ * - last _index = 135 (0x0087)
+ * - i2c_size = 5
+ */
+
+typedef struct {
+ uint8_t power_management__go1_power_force;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = go1_dig_powerforce
+*/
+ uint8_t system__stream_count_ctrl;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = retain_stream_count
+*/
+ uint8_t firmware__enable;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = firmware_enable
+*/
+ uint8_t system__interrupt_clear;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = sys_interrupt_clear_range
+ - [1] = sys_interrupt_clear_error
+*/
+ uint8_t system__mode_start;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [1:0] = scheduler_mode
+ - [3:2] = readout_mode
+ - [4] = mode_range__single_shot
+ - [5] = mode_range__back_to_back
+ - [6] = mode_range__timed
+ - [7] = mode_range__abort
+*/
+} VL53L1_system_control_t;
+
+
+/**
+ * @struct VL53L1_system_results_t
+ *
+ * - registers = 25
+ * - first_index = 136 (0x0088)
+ * - last _index = 179 (0x00B3)
+ * - i2c_size = 44
+ */
+
+typedef struct {
+ uint8_t result__interrupt_status;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [2:0] = int_status
+ - [4:3] = int_error_status
+ - [5] = gph_id_gpio_status
+*/
+ uint8_t result__range_status;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [4:0] = range_status
+ - [5] = max_threshold_hit
+ - [6] = min_threshold_hit
+ - [7] = gph_id_range_status
+*/
+ uint8_t result__report_status;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = report_status
+*/
+ uint8_t result__stream_count;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = result__stream_count
+*/
+ uint16_t result__dss_actual_effective_spads_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__dss_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+ uint16_t result__peak_signal_count_rate_mcps_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__peak_signal_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+ uint16_t result__ambient_count_rate_mcps_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__ambient_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+ uint16_t result__sigma_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__sigma_sd0 (fixed point 14.2)
+*/
+ uint16_t result__phase_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__phase_sd0 (fixed point 5.11)
+*/
+ uint16_t result__final_crosstalk_corrected_range_mm_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__final_crosstalk_corrected_range_mm_sd0
+*/
+ uint16_t result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0 (fixed point 9.7)
+*/
+ uint16_t result__mm_inner_actual_effective_spads_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__mm_inner_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+ uint16_t result__mm_outer_actual_effective_spads_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__mm_outer_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+ uint16_t result__avg_signal_count_rate_mcps_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__avg_signal_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+ uint16_t result__dss_actual_effective_spads_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__dss_actual_effective_spads_sd1 (fixed point 8.8)
+*/
+ uint16_t result__peak_signal_count_rate_mcps_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__peak_signal_count_rate_mcps_sd1 (fixed point 9.7)
+*/
+ uint16_t result__ambient_count_rate_mcps_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__ambient_count_rate_mcps_sd1 (fixed point 9.7)
+*/
+ uint16_t result__sigma_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__sigma_sd1 (fixed point 14.2)
+*/
+ uint16_t result__phase_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__phase_sd1 (fixed point 5.11)
+*/
+ uint16_t result__final_crosstalk_corrected_range_mm_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__final_crosstalk_corrected_range_mm_sd1
+*/
+ uint16_t result__spare_0_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__spare_0_sd1
+*/
+ uint16_t result__spare_1_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__spare_1_sd1
+*/
+ uint16_t result__spare_2_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result__spare_2_sd1
+*/
+ uint8_t result__spare_3_sd1;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = result__spare_3_sd1
+*/
+ uint8_t result__thresh_info;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = result__distance_int_info
+ - [7:4] = result__rate_int_info
+*/
+} VL53L1_system_results_t;
+
+
+/**
+ * @struct VL53L1_core_results_t
+ *
+ * - registers = 9
+ * - first_index = 180 (0x00B4)
+ * - last _index = 212 (0x00D4)
+ * - i2c_size = 33
+ */
+
+typedef struct {
+ uint32_t result_core__ambient_window_events_sd0;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = result_core__ambient_window_events_sd0
+*/
+ uint32_t result_core__ranging_total_events_sd0;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = result_core__ranging_total_events_sd0
+*/
+ int32_t result_core__signal_total_events_sd0;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = result_core__signal_total_events_sd0
+*/
+ uint32_t result_core__total_periods_elapsed_sd0;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = result_core__total_periods_elapsed_sd0
+*/
+ uint32_t result_core__ambient_window_events_sd1;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = result_core__ambient_window_events_sd1
+*/
+ uint32_t result_core__ranging_total_events_sd1;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = result_core__ranging_total_events_sd1
+*/
+ int32_t result_core__signal_total_events_sd1;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = result_core__signal_total_events_sd1
+*/
+ uint32_t result_core__total_periods_elapsed_sd1;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = result_core__total_periods_elapsed_sd1
+*/
+ uint8_t result_core__spare_0;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = result_core__spare_0
+*/
+} VL53L1_core_results_t;
+
+
+/**
+ * @struct VL53L1_debug_results_t
+ *
+ * - registers = 43
+ * - first_index = 214 (0x00D6)
+ * - last _index = 269 (0x010D)
+ * - i2c_size = 56
+ */
+
+typedef struct {
+ uint16_t phasecal_result__reference_phase;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = result_phasecal__reference_phase (fixed point 5.11)
+*/
+ uint8_t phasecal_result__vcsel_start;
+/*!<
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [6:0] = result_phasecal__vcsel_start
+*/
+ uint8_t ref_spad_char_result__num_actual_ref_spads;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [5:0] = ref_spad_char_result__num_actual_ref_spads
+*/
+ uint8_t ref_spad_char_result__ref_location;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [1:0] = ref_spad_char_result__ref_location
+*/
+ uint8_t vhv_result__coldboot_status;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = vhv_result__coldboot_status
+*/
+ uint8_t vhv_result__search_result;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [5:0] = cp_sel_result
+*/
+ uint8_t vhv_result__latest_setting;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [5:0] = cp_sel_latest_setting
+*/
+ uint16_t result__osc_calibrate_val;
+/*!<
+ info: \n
+ - msb = 9
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [9:0] = osc_calibrate_val
+*/
+ uint8_t ana_config__powerdown_go1;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = go2_ref_bg_disable_avdd
+ - [1] = go2_regdvdd1v2_enable_avdd
+*/
+ uint8_t ana_config__ref_bg_ctrl;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = go2_ref_overdrvbg_avdd
+ - [1] = go2_ref_forcebgison_avdd
+*/
+ uint8_t ana_config__regdvdd1v2_ctrl;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = go2_regdvdd1v2_sel_pulldown_avdd
+ - [1] = go2_regdvdd1v2_sel_boost_avdd
+ - [3:2] = go2_regdvdd1v2_selv_avdd
+*/
+ uint8_t ana_config__osc_slow_ctrl;
+/*!<
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = osc_slow_en
+ - [1] = osc_slow_op_en
+ - [2] = osc_slow_freq_sel
+*/
+ uint8_t test_mode__status;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = test_mode_status
+*/
+ uint8_t firmware__system_status;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = firmware_bootup
+ - [1] = firmware_first_range
+*/
+ uint8_t firmware__mode_status;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = firmware_mode_status
+*/
+ uint8_t firmware__secondary_mode_status;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = fw_secondary_mode_status
+*/
+ uint16_t firmware__cal_repeat_rate_counter;
+/*!<
+ info: \n
+ - msb = 11
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [11:0] = firmware_cal_repeat_rate
+*/
+ uint16_t gph__system__thresh_high;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_thresh_high
+*/
+ uint16_t gph__system__thresh_low;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_thresh_low
+*/
+ uint8_t gph__system__enable_xtalk_per_quadrant;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = shadow__enable_xtalk_per_quadrant
+*/
+ uint8_t gph__spare_0;
+/*!<
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = fw_safe_to_disable
+ - [1] = shadow__spare_0
+ - [2] = shadow__spare_1
+*/
+ uint8_t gph__sd_config__woi_sd0;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = shadow_sd_config__woi_sd0
+*/
+ uint8_t gph__sd_config__woi_sd1;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = shadow_sd_config__woi_sd1
+*/
+ uint8_t gph__sd_config__initial_phase_sd0;
+/*!<
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [6:0] = shadow_sd_config__initial_phase_sd0
+*/
+ uint8_t gph__sd_config__initial_phase_sd1;
+/*!<
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [6:0] = shadow_sd_config__initial_phase_sd1
+*/
+ uint8_t gph__sd_config__first_order_select;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = shadow_sd_config__first_order_select_rtn
+ - [1] = shadow_sd_config__first_order_select_ref
+*/
+ uint8_t gph__sd_config__quantifier;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = shadow_sd_config__quantifier
+*/
+ uint8_t gph__roi_config__user_roi_centre_spad;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = shadow_user_roi_center_spad_q0
+*/
+ uint8_t gph__roi_config__user_roi_requested_global_xy_size;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = shadow_user_roi_requested_global_xy_size
+*/
+ uint8_t gph__system__sequence_config;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = shadow_sequence_vhv_en
+ - [1] = shadow_sequence_phasecal_en
+ - [2] = shadow_sequence_reference_phase_en
+ - [3] = shadow_sequence_dss1_en
+ - [4] = shadow_sequence_dss2_en
+ - [5] = shadow_sequence_mm1_en
+ - [6] = shadow_sequence_mm2_en
+ - [7] = shadow_sequence_range_en
+*/
+ uint8_t gph__gph_id;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = shadow_gph_id
+*/
+ uint8_t system__interrupt_set;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = sys_interrupt_set_range
+ - [1] = sys_interrupt_set_error
+*/
+ uint8_t interrupt_manager__enables;
+/*!<
+ info: \n
+ - msb = 4
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = interrupt_enable__single_shot
+ - [1] = interrupt_enable__back_to_back
+ - [2] = interrupt_enable__timed
+ - [3] = interrupt_enable__abort
+ - [4] = interrupt_enable__test
+*/
+ uint8_t interrupt_manager__clear;
+/*!<
+ info: \n
+ - msb = 4
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = interrupt_clear__single_shot
+ - [1] = interrupt_clear__back_to_back
+ - [2] = interrupt_clear__timed
+ - [3] = interrupt_clear__abort
+ - [4] = interrupt_clear__test
+*/
+ uint8_t interrupt_manager__status;
+/*!<
+ info: \n
+ - msb = 4
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = interrupt_status__single_shot
+ - [1] = interrupt_status__back_to_back
+ - [2] = interrupt_status__timed
+ - [3] = interrupt_status__abort
+ - [4] = interrupt_status__test
+*/
+ uint8_t mcu_to_host_bank__wr_access_en;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = mcu_to_host_bank_wr_en
+*/
+ uint8_t power_management__go1_reset_status;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = go1_status
+*/
+ uint8_t pad_startup_mode__value_ro;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = pad_atest1_val_ro
+ - [1] = pad_atest2_val_ro
+*/
+ uint8_t pad_startup_mode__value_ctrl;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = pad_atest1_val
+ - [1] = pad_atest2_val
+ - [4] = pad_atest1_dig_enable
+ - [5] = pad_atest2_dig_enable
+*/
+ uint32_t pll_period_us;
+/*!<
+ info: \n
+ - msb = 17
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [17:0] = pll_period_us (fixed point 0.24)
+*/
+ uint32_t interrupt_scheduler__data_out;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = interrupt_scheduler_data_out
+*/
+ uint8_t nvm_bist__complete;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = nvm_bist__complete
+*/
+ uint8_t nvm_bist__status;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = nvm_bist__status
+*/
+} VL53L1_debug_results_t;
+
+
+/**
+ * @struct VL53L1_nvm_copy_data_t
+ *
+ * - registers = 48
+ * - first_index = 271 (0x010F)
+ * - last _index = 319 (0x013F)
+ * - i2c_size = 49
+ */
+
+typedef struct {
+ uint8_t identification__model_id;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = model_id
+*/
+ uint8_t identification__module_type;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = module_type
+*/
+ uint8_t identification__revision_id;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = nvm_revision_id
+ - [7:4] = mask_revision_id
+*/
+ uint16_t identification__module_id;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = module_id
+*/
+ uint8_t ana_config__fast_osc__trim_max;
+/*!<
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [6:0] = osc_trim_max
+*/
+ uint8_t ana_config__fast_osc__freq_set;
+/*!<
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [2:0] = osc_freq_set
+*/
+ uint8_t ana_config__vcsel_trim;
+/*!<
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [2:0] = vcsel_trim
+*/
+ uint8_t ana_config__vcsel_selion;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [5:0] = vcsel_selion
+*/
+ uint8_t ana_config__vcsel_selion_max;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [5:0] = vcsel_selion_max
+*/
+ uint8_t protected_laser_safety__lock_bit;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = laser_safety__lock_bit
+*/
+ uint8_t laser_safety__key;
+/*!<
+ info: \n
+ - msb = 6
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [6:0] = laser_safety__key
+*/
+ uint8_t laser_safety__key_ro;
+/*!<
+ info: \n
+ - msb = 0
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = laser_safety__key_ro
+*/
+ uint8_t laser_safety__clip;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [5:0] = vcsel_pulse_width_clip
+*/
+ uint8_t laser_safety__mult;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [5:0] = vcsel_pulse_width_mult
+*/
+ uint8_t global_config__spad_enables_rtn_0;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_0
+*/
+ uint8_t global_config__spad_enables_rtn_1;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_1
+*/
+ uint8_t global_config__spad_enables_rtn_2;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_2
+*/
+ uint8_t global_config__spad_enables_rtn_3;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_3
+*/
+ uint8_t global_config__spad_enables_rtn_4;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_4
+*/
+ uint8_t global_config__spad_enables_rtn_5;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_5
+*/
+ uint8_t global_config__spad_enables_rtn_6;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_6
+*/
+ uint8_t global_config__spad_enables_rtn_7;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_7
+*/
+ uint8_t global_config__spad_enables_rtn_8;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_8
+*/
+ uint8_t global_config__spad_enables_rtn_9;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_9
+*/
+ uint8_t global_config__spad_enables_rtn_10;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_10
+*/
+ uint8_t global_config__spad_enables_rtn_11;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_11
+*/
+ uint8_t global_config__spad_enables_rtn_12;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_12
+*/
+ uint8_t global_config__spad_enables_rtn_13;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_13
+*/
+ uint8_t global_config__spad_enables_rtn_14;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_14
+*/
+ uint8_t global_config__spad_enables_rtn_15;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_15
+*/
+ uint8_t global_config__spad_enables_rtn_16;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_16
+*/
+ uint8_t global_config__spad_enables_rtn_17;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_17
+*/
+ uint8_t global_config__spad_enables_rtn_18;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_18
+*/
+ uint8_t global_config__spad_enables_rtn_19;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_19
+*/
+ uint8_t global_config__spad_enables_rtn_20;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_20
+*/
+ uint8_t global_config__spad_enables_rtn_21;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_21
+*/
+ uint8_t global_config__spad_enables_rtn_22;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_22
+*/
+ uint8_t global_config__spad_enables_rtn_23;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_23
+*/
+ uint8_t global_config__spad_enables_rtn_24;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_24
+*/
+ uint8_t global_config__spad_enables_rtn_25;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_25
+*/
+ uint8_t global_config__spad_enables_rtn_26;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_26
+*/
+ uint8_t global_config__spad_enables_rtn_27;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_27
+*/
+ uint8_t global_config__spad_enables_rtn_28;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_28
+*/
+ uint8_t global_config__spad_enables_rtn_29;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_29
+*/
+ uint8_t global_config__spad_enables_rtn_30;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_30
+*/
+ uint8_t global_config__spad_enables_rtn_31;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = spad_enables_rtn_31
+*/
+ uint8_t roi_config__mode_roi_centre_spad;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = mode_roi_center_spad
+*/
+ uint8_t roi_config__mode_roi_xy_size;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = mode_roi_xy_size
+*/
+} VL53L1_nvm_copy_data_t;
+
+
+/**
+ * @struct VL53L1_prev_shadow_system_results_t
+ *
+ * - registers = 24
+ * - first_index = 3792 (0x0ED0)
+ * - last _index = 3834 (0x0EFA)
+ * - i2c_size = 44
+ */
+
+typedef struct {
+ uint8_t prev_shadow_result__interrupt_status;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [2:0] = prev_shadow_int_status
+ - [4:3] = prev_shadow_int_error_status
+ - [5] = prev_shadow_gph_id_gpio_status
+*/
+ uint8_t prev_shadow_result__range_status;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [4:0] = prev_shadow_range_status
+ - [5] = prev_shadow_max_threshold_hit
+ - [6] = prev_shadow_min_threshold_hit
+ - [7] = prev_shadow_gph_id_range_status
+*/
+ uint8_t prev_shadow_result__report_status;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = prev_shadow_report_status
+*/
+ uint8_t prev_shadow_result__stream_count;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = prev_shadow_result__stream_count
+*/
+ uint16_t prev_shadow_result__dss_actual_effective_spads_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__dss_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+ uint16_t prev_shadow_result__peak_signal_count_rate_mcps_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__peak_signal_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+ uint16_t prev_shadow_result__ambient_count_rate_mcps_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__ambient_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+ uint16_t prev_shadow_result__sigma_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__sigma_sd0 (fixed point 14.2)
+*/
+ uint16_t prev_shadow_result__phase_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__phase_sd0 (fixed point 5.11)
+*/
+ uint16_t prev_shadow_result__final_crosstalk_corrected_range_mm_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__final_crosstalk_corrected_range_mm_sd0
+*/
+ uint16_t prev_shadow_result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0 (fixed point 9.7)
+*/
+ uint16_t prev_shadow_result__mm_inner_actual_effective_spads_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__mm_inner_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+ uint16_t prev_shadow_result__mm_outer_actual_effective_spads_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__mm_outer_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+ uint16_t prev_shadow_result__avg_signal_count_rate_mcps_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__avg_signal_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+ uint16_t prev_shadow_result__dss_actual_effective_spads_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__dss_actual_effective_spads_sd1 (fixed point 8.8)
+*/
+ uint16_t prev_shadow_result__peak_signal_count_rate_mcps_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__peak_signal_count_rate_mcps_sd1 (fixed point 9.7)
+*/
+ uint16_t prev_shadow_result__ambient_count_rate_mcps_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__ambient_count_rate_mcps_sd1 (fixed point 9.7)
+*/
+ uint16_t prev_shadow_result__sigma_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__sigma_sd1 (fixed point 14.2)
+*/
+ uint16_t prev_shadow_result__phase_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__phase_sd1 (fixed point 5.11)
+*/
+ uint16_t prev_shadow_result__final_crosstalk_corrected_range_mm_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__final_crosstalk_corrected_range_mm_sd1
+*/
+ uint16_t prev_shadow_result__spare_0_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__spare_0_sd1
+*/
+ uint16_t prev_shadow_result__spare_1_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__spare_1_sd1
+*/
+ uint16_t prev_shadow_result__spare_2_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__spare_2_sd1
+*/
+ uint16_t prev_shadow_result__spare_3_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = prev_shadow_result__spare_3_sd1
+*/
+} VL53L1_prev_shadow_system_results_t;
+
+
+/**
+ * @struct VL53L1_prev_shadow_core_results_t
+ *
+ * - registers = 9
+ * - first_index = 3836 (0x0EFC)
+ * - last _index = 3868 (0x0F1C)
+ * - i2c_size = 33
+ */
+
+typedef struct {
+ uint32_t prev_shadow_result_core__ambient_window_events_sd0;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = prev_shadow_result_core__ambient_window_events_sd0
+*/
+ uint32_t prev_shadow_result_core__ranging_total_events_sd0;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = prev_shadow_result_core__ranging_total_events_sd0
+*/
+ int32_t prev_shadow_result_core__signal_total_events_sd0;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = prev_shadow_result_core__signal_total_events_sd0
+*/
+ uint32_t prev_shadow_result_core__total_periods_elapsed_sd0;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = prev_shadow_result_core__total_periods_elapsed_sd0
+*/
+ uint32_t prev_shadow_result_core__ambient_window_events_sd1;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = prev_shadow_result_core__ambient_window_events_sd1
+*/
+ uint32_t prev_shadow_result_core__ranging_total_events_sd1;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = prev_shadow_result_core__ranging_total_events_sd1
+*/
+ int32_t prev_shadow_result_core__signal_total_events_sd1;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = prev_shadow_result_core__signal_total_events_sd1
+*/
+ uint32_t prev_shadow_result_core__total_periods_elapsed_sd1;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = prev_shadow_result_core__total_periods_elapsed_sd1
+*/
+ uint8_t prev_shadow_result_core__spare_0;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = prev_shadow_result_core__spare_0
+*/
+} VL53L1_prev_shadow_core_results_t;
+
+
+/**
+ * @struct VL53L1_patch_debug_t
+ *
+ * - registers = 2
+ * - first_index = 3872 (0x0F20)
+ * - last _index = 3873 (0x0F21)
+ * - i2c_size = 2
+ */
+
+typedef struct {
+ uint8_t result__debug_status;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = result_debug_status
+*/
+ uint8_t result__debug_stage;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = result_debug_stage
+*/
+} VL53L1_patch_debug_t;
+
+
+/**
+ * @struct VL53L1_gph_general_config_t
+ *
+ * - registers = 3
+ * - first_index = 3876 (0x0F24)
+ * - last _index = 3880 (0x0F28)
+ * - i2c_size = 5
+ */
+
+typedef struct {
+ uint16_t gph__system__thresh_rate_high;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = gph__system_thresh_rate_high (fixed point 9.7)
+*/
+ uint16_t gph__system__thresh_rate_low;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = gph__system_thresh_rate_low (fixed point 9.7)
+*/
+ uint8_t gph__system__interrupt_config_gpio;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [1:0] = gph__int_mode_distance
+ - [3:2] = gph__int_mode_rate
+ - [4] = gph__int_spare
+ - [5] = gph__int_new_measure_ready
+ - [6] = gph__int_no_target_en
+ - [7] = gph__int_combined_mode
+*/
+} VL53L1_gph_general_config_t;
+
+
+/**
+ * @struct VL53L1_gph_static_config_t
+ *
+ * - registers = 5
+ * - first_index = 3887 (0x0F2F)
+ * - last _index = 3892 (0x0F34)
+ * - i2c_size = 6
+ */
+
+typedef struct {
+ uint8_t gph__dss_config__roi_mode_control;
+/*!<
+ info: \n
+ - msb = 2
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [1:0] = gph__dss_config__input_mode
+ - [2] = gph__calculate_roi_enable
+*/
+ uint16_t gph__dss_config__manual_effective_spads_select;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = gph__dss_config__manual_effective_spads_select
+*/
+ uint8_t gph__dss_config__manual_block_select;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = gph__dss_config__manual_block_select
+*/
+ uint8_t gph__dss_config__max_spads_limit;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = gph__dss_config__max_spads_limit
+*/
+ uint8_t gph__dss_config__min_spads_limit;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = gph__dss_config__min_spads_limit
+*/
+} VL53L1_gph_static_config_t;
+
+
+/**
+ * @struct VL53L1_gph_timing_config_t
+ *
+ * - registers = 14
+ * - first_index = 3894 (0x0F36)
+ * - last _index = 3909 (0x0F45)
+ * - i2c_size = 16
+ */
+
+typedef struct {
+ uint8_t gph__mm_config__timeout_macrop_a_hi;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = gph_mm_config__config_timeout_macrop_a_hi
+*/
+ uint8_t gph__mm_config__timeout_macrop_a_lo;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = gph_mm_config__config_timeout_macrop_a_lo
+*/
+ uint8_t gph__mm_config__timeout_macrop_b_hi;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = gph_mm_config__config_timeout_macrop_b_hi
+*/
+ uint8_t gph__mm_config__timeout_macrop_b_lo;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = gph_mm_config__config_timeout_macrop_b_lo
+*/
+ uint8_t gph__range_config__timeout_macrop_a_hi;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = gph_range_timeout_overall_periods_macrop_a_hi
+*/
+ uint8_t gph__range_config__timeout_macrop_a_lo;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = gph_range_timeout_overall_periods_macrop_a_lo
+*/
+ uint8_t gph__range_config__vcsel_period_a;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [5:0] = gph_range_config__vcsel_period_a
+*/
+ uint8_t gph__range_config__vcsel_period_b;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [5:0] = gph_range_config__vcsel_period_b
+*/
+ uint8_t gph__range_config__timeout_macrop_b_hi;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = gph_range_timeout_overall_periods_macrop_b_hi
+*/
+ uint8_t gph__range_config__timeout_macrop_b_lo;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = gph_range_timeout_overall_periods_macrop_b_lo
+*/
+ uint16_t gph__range_config__sigma_thresh;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = gph_range_config__sigma_thresh (fixed point 14.2)
+*/
+ uint16_t gph__range_config__min_count_rate_rtn_limit_mcps;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = gph_range_config__min_count_rate_rtn_limit_mcps (fixed point 9.7)
+*/
+ uint8_t gph__range_config__valid_phase_low;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = gph_range_config__valid_phase_low (fixed point 5.3)
+*/
+ uint8_t gph__range_config__valid_phase_high;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = gph_range_config__valid_phase_high (fixed point 5.3)
+*/
+} VL53L1_gph_timing_config_t;
+
+
+/**
+ * @struct VL53L1_fw_internal_t
+ *
+ * - registers = 2
+ * - first_index = 3910 (0x0F46)
+ * - last _index = 3911 (0x0F47)
+ * - i2c_size = 2
+ */
+
+typedef struct {
+ uint8_t firmware__internal_stream_count_div;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = fw__internal_stream_count_div
+*/
+ uint8_t firmware__internal_stream_counter_val;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = fw__internal_stream_counter_val
+*/
+} VL53L1_fw_internal_t;
+
+
+/**
+ * @struct VL53L1_patch_results_t
+ *
+ * - registers = 60
+ * - first_index = 3924 (0x0F54)
+ * - last _index = 4012 (0x0FAC)
+ * - i2c_size = 90
+ */
+
+typedef struct {
+ uint8_t dss_calc__roi_ctrl;
+/*!<
+ info: \n
+ - msb = 1
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [0] = dss_calc__roi_intersect_enable
+ - [1] = dss_calc__roi_subtract_enable
+*/
+ uint8_t dss_calc__spare_1;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__spare_1
+*/
+ uint8_t dss_calc__spare_2;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__spare_2
+*/
+ uint8_t dss_calc__spare_3;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__spare_3
+*/
+ uint8_t dss_calc__spare_4;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__spare_4
+*/
+ uint8_t dss_calc__spare_5;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__spare_5
+*/
+ uint8_t dss_calc__spare_6;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__spare_6
+*/
+ uint8_t dss_calc__spare_7;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__spare_7
+*/
+ uint8_t dss_calc__user_roi_spad_en_0;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_0
+*/
+ uint8_t dss_calc__user_roi_spad_en_1;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_1
+*/
+ uint8_t dss_calc__user_roi_spad_en_2;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_2
+*/
+ uint8_t dss_calc__user_roi_spad_en_3;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_3
+*/
+ uint8_t dss_calc__user_roi_spad_en_4;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_4
+*/
+ uint8_t dss_calc__user_roi_spad_en_5;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_5
+*/
+ uint8_t dss_calc__user_roi_spad_en_6;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_6
+*/
+ uint8_t dss_calc__user_roi_spad_en_7;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_7
+*/
+ uint8_t dss_calc__user_roi_spad_en_8;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_8
+*/
+ uint8_t dss_calc__user_roi_spad_en_9;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_9
+*/
+ uint8_t dss_calc__user_roi_spad_en_10;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_10
+*/
+ uint8_t dss_calc__user_roi_spad_en_11;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_11
+*/
+ uint8_t dss_calc__user_roi_spad_en_12;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_12
+*/
+ uint8_t dss_calc__user_roi_spad_en_13;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_13
+*/
+ uint8_t dss_calc__user_roi_spad_en_14;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_14
+*/
+ uint8_t dss_calc__user_roi_spad_en_15;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_15
+*/
+ uint8_t dss_calc__user_roi_spad_en_16;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_16
+*/
+ uint8_t dss_calc__user_roi_spad_en_17;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_17
+*/
+ uint8_t dss_calc__user_roi_spad_en_18;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_18
+*/
+ uint8_t dss_calc__user_roi_spad_en_19;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_19
+*/
+ uint8_t dss_calc__user_roi_spad_en_20;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_20
+*/
+ uint8_t dss_calc__user_roi_spad_en_21;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_21
+*/
+ uint8_t dss_calc__user_roi_spad_en_22;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_22
+*/
+ uint8_t dss_calc__user_roi_spad_en_23;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_23
+*/
+ uint8_t dss_calc__user_roi_spad_en_24;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_24
+*/
+ uint8_t dss_calc__user_roi_spad_en_25;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_25
+*/
+ uint8_t dss_calc__user_roi_spad_en_26;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_26
+*/
+ uint8_t dss_calc__user_roi_spad_en_27;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_27
+*/
+ uint8_t dss_calc__user_roi_spad_en_28;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_28
+*/
+ uint8_t dss_calc__user_roi_spad_en_29;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_29
+*/
+ uint8_t dss_calc__user_roi_spad_en_30;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_30
+*/
+ uint8_t dss_calc__user_roi_spad_en_31;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_spad_en_31
+*/
+ uint8_t dss_calc__user_roi_0;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_0
+*/
+ uint8_t dss_calc__user_roi_1;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__user_roi_1
+*/
+ uint8_t dss_calc__mode_roi_0;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__mode_roi_0
+*/
+ uint8_t dss_calc__mode_roi_1;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_calc__mode_roi_1
+*/
+ uint8_t sigma_estimator_calc__spare_0;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = sigma_estimator_calc__spare_0
+*/
+ uint16_t vhv_result__peak_signal_rate_mcps;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = vhv_result__peak_signal_rate_mcps
+*/
+ uint32_t vhv_result__signal_total_events_ref;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = vhv_result__signal_total_events_ref
+*/
+ uint16_t phasecal_result__phase_output_ref;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = phasecal_result__normalised_phase_ref
+*/
+ uint16_t dss_result__total_rate_per_spad;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = dss_result__total_rate_per_spad
+*/
+ uint8_t dss_result__enabled_blocks;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = dss_result__enabled_blocks
+*/
+ uint16_t dss_result__num_requested_spads;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = dss_result__num_requested_spads (fixed point 8.8)
+*/
+ uint16_t mm_result__inner_intersection_rate;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = mm_result__inner_intersection_rate
+*/
+ uint16_t mm_result__outer_complement_rate;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = mm_result__outer_complement_rate
+*/
+ uint16_t mm_result__total_offset;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = mm_result__total_offset
+*/
+ uint32_t xtalk_calc__xtalk_for_enabled_spads;
+/*!<
+ info: \n
+ - msb = 23
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [23:0] = xtalk_calc__xtalk_for_enabled_spads (fixed point 11.13)
+*/
+ uint32_t xtalk_result__avg_xtalk_user_roi_kcps;
+/*!<
+ info: \n
+ - msb = 23
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [23:0] = xtalk_result__avg_xtalk_user_roi_kcps (fixed point 11.13)
+*/
+ uint32_t xtalk_result__avg_xtalk_mm_inner_roi_kcps;
+/*!<
+ info: \n
+ - msb = 23
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [23:0] = xtalk_result__avg_xtalk_mm_inner_roi_kcps (fixed point 11.13)
+*/
+ uint32_t xtalk_result__avg_xtalk_mm_outer_roi_kcps;
+/*!<
+ info: \n
+ - msb = 23
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [23:0] = xtalk_result__avg_xtalk_mm_outer_roi_kcps (fixed point 11.13)
+*/
+ uint32_t range_result__accum_phase;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = range_result__accum_phase
+*/
+ uint16_t range_result__offset_corrected_range;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = range_result__offset_corrected_range
+*/
+} VL53L1_patch_results_t;
+
+
+/**
+ * @struct VL53L1_shadow_system_results_t
+ *
+ * - registers = 28
+ * - first_index = 4014 (0x0FAE)
+ * - last _index = 4095 (0x0FFF)
+ * - i2c_size = 82
+ */
+
+typedef struct {
+ uint8_t shadow_phasecal_result__vcsel_start;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = shadow_phasecal_result__vcsel_start
+*/
+ uint8_t shadow_result__interrupt_status;
+/*!<
+ info: \n
+ - msb = 5
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [2:0] = shadow_int_status
+ - [4:3] = shadow_int_error_status
+ - [5] = shadow_gph_id_gpio_status
+*/
+ uint8_t shadow_result__range_status;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [4:0] = shadow_range_status
+ - [5] = shadow_max_threshold_hit
+ - [6] = shadow_min_threshold_hit
+ - [7] = shadow_gph_id_range_status
+*/
+ uint8_t shadow_result__report_status;
+/*!<
+ info: \n
+ - msb = 3
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = shadow_report_status
+*/
+ uint8_t shadow_result__stream_count;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = shadow_result__stream_count
+*/
+ uint16_t shadow_result__dss_actual_effective_spads_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__dss_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+ uint16_t shadow_result__peak_signal_count_rate_mcps_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__peak_signal_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+ uint16_t shadow_result__ambient_count_rate_mcps_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__ambient_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+ uint16_t shadow_result__sigma_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__sigma_sd0 (fixed point 14.2)
+*/
+ uint16_t shadow_result__phase_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__phase_sd0 (fixed point 5.11)
+*/
+ uint16_t shadow_result__final_crosstalk_corrected_range_mm_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__final_crosstalk_corrected_range_mm_sd0
+*/
+ uint16_t shadow_result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0 (fixed point 9.7)
+*/
+ uint16_t shadow_result__mm_inner_actual_effective_spads_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__mm_inner_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+ uint16_t shadow_result__mm_outer_actual_effective_spads_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__mm_outer_actual_effective_spads_sd0 (fixed point 8.8)
+*/
+ uint16_t shadow_result__avg_signal_count_rate_mcps_sd0;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__avg_signal_count_rate_mcps_sd0 (fixed point 9.7)
+*/
+ uint16_t shadow_result__dss_actual_effective_spads_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__dss_actual_effective_spads_sd1 (fixed point 8.8)
+*/
+ uint16_t shadow_result__peak_signal_count_rate_mcps_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__peak_signal_count_rate_mcps_sd1 (fixed point 9.7)
+*/
+ uint16_t shadow_result__ambient_count_rate_mcps_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__ambient_count_rate_mcps_sd1 (fixed point 9.7)
+*/
+ uint16_t shadow_result__sigma_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__sigma_sd1 (fixed point 14.2)
+*/
+ uint16_t shadow_result__phase_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__phase_sd1 (fixed point 5.11)
+*/
+ uint16_t shadow_result__final_crosstalk_corrected_range_mm_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__final_crosstalk_corrected_range_mm_sd1
+*/
+ uint16_t shadow_result__spare_0_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__spare_0_sd1
+*/
+ uint16_t shadow_result__spare_1_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__spare_1_sd1
+*/
+ uint16_t shadow_result__spare_2_sd1;
+/*!<
+ info: \n
+ - msb = 15
+ - lsb = 0
+ - i2c_size = 2
+
+ fields: \n
+ - [15:0] = shadow_result__spare_2_sd1
+*/
+ uint8_t shadow_result__spare_3_sd1;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = shadow_result__spare_3_sd1
+*/
+ uint8_t shadow_result__thresh_info;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [3:0] = shadow_result__distance_int_info
+ - [7:4] = shadow_result__rate_int_info
+*/
+ uint8_t shadow_phasecal_result__reference_phase_hi;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = shadow_phasecal_result__reference_phase_hi
+*/
+ uint8_t shadow_phasecal_result__reference_phase_lo;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = shadow_phasecal_result__reference_phase_lo
+*/
+} VL53L1_shadow_system_results_t;
+
+
+/**
+ * @struct VL53L1_shadow_core_results_t
+ *
+ * - registers = 9
+ * - first_index = 4060 (0x0FDC)
+ * - last _index = 4092 (0x0FFC)
+ * - i2c_size = 33
+ */
+
+typedef struct {
+ uint32_t shadow_result_core__ambient_window_events_sd0;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = shadow_result_core__ambient_window_events_sd0
+*/
+ uint32_t shadow_result_core__ranging_total_events_sd0;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = shadow_result_core__ranging_total_events_sd0
+*/
+ int32_t shadow_result_core__signal_total_events_sd0;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = shadow_result_core__signal_total_events_sd0
+*/
+ uint32_t shadow_result_core__total_periods_elapsed_sd0;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = shadow_result_core__total_periods_elapsed_sd0
+*/
+ uint32_t shadow_result_core__ambient_window_events_sd1;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = shadow_result_core__ambient_window_events_sd1
+*/
+ uint32_t shadow_result_core__ranging_total_events_sd1;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = shadow_result_core__ranging_total_events_sd1
+*/
+ int32_t shadow_result_core__signal_total_events_sd1;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = shadow_result_core__signal_total_events_sd1
+*/
+ uint32_t shadow_result_core__total_periods_elapsed_sd1;
+/*!<
+ info: \n
+ - msb = 31
+ - lsb = 0
+ - i2c_size = 4
+
+ fields: \n
+ - [31:0] = shadow_result_core__total_periods_elapsed_sd1
+*/
+ uint8_t shadow_result_core__spare_0;
+/*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7:0] = shadow_result_core__spare_0
+*/
+} VL53L1_shadow_core_results_t;
+
+
+#endif
+
diff --git a/src/lib/vl53l1/core/inc/vl53l1_silicon_core.h b/src/lib/vl53l1/core/inc/vl53l1_silicon_core.h
new file mode 100644
index 0000000000..5ae8c5a78c
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_silicon_core.h
@@ -0,0 +1,66 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*******************************************************************************/
+
+/**
+ * @file vl53l1_silicon_core.h
+ *
+ * @brief EwokPlus25 low level silicon specific API function definitions
+ */
+
+#ifndef _VL53L1_SILICON_CORE_H_
+#define _VL53L1_SILICON_CORE_H_
+
+#include "vl53l1_platform.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+/**
+ * @brief Checks if the firmware is ready for ranging (Silicon variant)
+ *
+ * @param[in] Dev : Device Handle
+ * @param[out] pready : pointer to data ready flag \n
+ * 0 = firmware not ready \n
+ * 1 = firmware ready
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_is_firmware_ready_silicon(
+ VL53L1_DEV Dev,
+ uint8_t *pready);
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _VL53L1_SILICON_CORE_H_ */
diff --git a/src/lib/vl53l1/core/inc/vl53l1_tuning_parm_defaults.h b/src/lib/vl53l1/core/inc/vl53l1_tuning_parm_defaults.h
new file mode 100644
index 0000000000..39b4c02e52
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_tuning_parm_defaults.h
@@ -0,0 +1,176 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*******************************************************************************/
+
+/**
+ * @file vl53l1_tuning_parm_defaults.h
+ *
+ * @brief Define defaults for tuning parm list
+ *
+ * - Ensures coherence of internal defaults to tuning table
+ * - Allows reduction of tuning parm list to only changes from the
+ * standard settings defined below
+ *
+ */
+
+
+#ifndef _VL53L1_TUNING_PARM_DEFAULTS_H_
+#define _VL53L1_TUNING_PARM_DEFAULTS_H_
+
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/** @defgroup VL53L1_tuningparmdefault_group VL53L1 Defines
+ * @brief VL53L1 Tuning Parm Default Values
+ * @{
+ */
+
+#define VL53L1_TUNINGPARM_VERSION_DEFAULT \
+((uint16_t) 32771)
+#define VL53L1_TUNINGPARM_KEY_TABLE_VERSION_DEFAULT \
+((uint16_t) 32769)
+#define VL53L1_TUNINGPARM_LLD_VERSION_DEFAULT \
+((uint16_t) 32833)
+#define VL53L1_TUNINGPARM_CONSISTENCY_LITE_PHASE_TOLERANCE_DEFAULT \
+((uint8_t) 2)
+#define VL53L1_TUNINGPARM_PHASECAL_TARGET_DEFAULT \
+((uint8_t) 33)
+#define VL53L1_TUNINGPARM_LITE_CAL_REPEAT_RATE_DEFAULT \
+((uint16_t) 0)
+#define VL53L1_TUNINGPARM_LITE_RANGING_GAIN_FACTOR_DEFAULT \
+((uint16_t) 2011)
+#define VL53L1_TUNINGPARM_LITE_MIN_CLIP_MM_DEFAULT \
+((uint8_t) 0)
+#define VL53L1_TUNINGPARM_LITE_LONG_SIGMA_THRESH_MM_DEFAULT \
+((uint16_t) 60)
+#define VL53L1_TUNINGPARM_LITE_MED_SIGMA_THRESH_MM_DEFAULT \
+((uint16_t) 60)
+#define VL53L1_TUNINGPARM_LITE_SHORT_SIGMA_THRESH_MM_DEFAULT \
+((uint16_t) 360)
+#define VL53L1_TUNINGPARM_LITE_LONG_MIN_COUNT_RATE_RTN_MCPS_DEFAULT \
+((uint16_t) 128)
+#define VL53L1_TUNINGPARM_LITE_MED_MIN_COUNT_RATE_RTN_MCPS_DEFAULT \
+((uint16_t) 128)
+#define VL53L1_TUNINGPARM_LITE_SHORT_MIN_COUNT_RATE_RTN_MCPS_DEFAULT \
+((uint16_t) 192)
+#define VL53L1_TUNINGPARM_LITE_SIGMA_EST_PULSE_WIDTH_DEFAULT \
+((uint8_t) 8)
+#define VL53L1_TUNINGPARM_LITE_SIGMA_EST_AMB_WIDTH_NS_DEFAULT \
+((uint8_t) 16)
+#define VL53L1_TUNINGPARM_LITE_SIGMA_REF_MM_DEFAULT \
+((uint8_t) 1)
+#define VL53L1_TUNINGPARM_LITE_RIT_MULT_DEFAULT \
+((uint8_t) 64)
+#define VL53L1_TUNINGPARM_LITE_SEED_CONFIG_DEFAULT \
+((uint8_t) 2)
+#define VL53L1_TUNINGPARM_LITE_QUANTIFIER_DEFAULT \
+((uint8_t) 2)
+#define VL53L1_TUNINGPARM_LITE_FIRST_ORDER_SELECT_DEFAULT \
+((uint8_t) 0)
+#define VL53L1_TUNINGPARM_LITE_XTALK_MARGIN_KCPS_DEFAULT \
+((int16_t) 0)
+#define VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_LONG_RANGE_DEFAULT \
+((uint8_t) 14)
+#define VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_MED_RANGE_DEFAULT \
+((uint8_t) 10)
+#define VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_SHORT_RANGE_DEFAULT \
+((uint8_t) 6)
+#define VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_LONG_RANGE_DEFAULT \
+((uint8_t) 14)
+#define VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_MED_RANGE_DEFAULT \
+((uint8_t) 10)
+#define VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_SHORT_RANGE_DEFAULT \
+((uint8_t) 6)
+#define VL53L1_TUNINGPARM_TIMED_SEED_CONFIG_DEFAULT \
+((uint8_t) 1)
+#define VL53L1_TUNINGPARM_VHV_LOOPBOUND_DEFAULT \
+((uint8_t) 32)
+#define VL53L1_TUNINGPARM_REFSPADCHAR_DEVICE_TEST_MODE_DEFAULT \
+((uint8_t) 8)
+#define VL53L1_TUNINGPARM_REFSPADCHAR_VCSEL_PERIOD_DEFAULT \
+((uint8_t) 11)
+#define VL53L1_TUNINGPARM_REFSPADCHAR_PHASECAL_TIMEOUT_US_DEFAULT \
+((uint32_t) 1000)
+#define VL53L1_TUNINGPARM_REFSPADCHAR_TARGET_COUNT_RATE_MCPS_DEFAULT \
+((uint16_t) 2560)
+#define VL53L1_TUNINGPARM_REFSPADCHAR_MIN_COUNTRATE_LIMIT_MCPS_DEFAULT \
+((uint16_t) 1280)
+#define VL53L1_TUNINGPARM_REFSPADCHAR_MAX_COUNTRATE_LIMIT_MCPS_DEFAULT \
+((uint16_t) 5120)
+#define VL53L1_TUNINGPARM_OFFSET_CAL_DSS_RATE_MCPS_DEFAULT \
+((uint16_t) 2560)
+#define VL53L1_TUNINGPARM_OFFSET_CAL_PHASECAL_TIMEOUT_US_DEFAULT \
+((uint32_t) 1000)
+#define VL53L1_TUNINGPARM_OFFSET_CAL_MM_TIMEOUT_US_DEFAULT \
+((uint32_t) 13000)
+#define VL53L1_TUNINGPARM_OFFSET_CAL_RANGE_TIMEOUT_US_DEFAULT \
+((uint32_t) 13000)
+#define VL53L1_TUNINGPARM_OFFSET_CAL_PRE_SAMPLES_DEFAULT \
+((uint8_t) 8)
+#define VL53L1_TUNINGPARM_OFFSET_CAL_MM1_SAMPLES_DEFAULT \
+((uint8_t) 40)
+#define VL53L1_TUNINGPARM_OFFSET_CAL_MM2_SAMPLES_DEFAULT \
+((uint8_t) 9)
+#define VL53L1_TUNINGPARM_SPADMAP_VCSEL_PERIOD_DEFAULT \
+((uint8_t) 18)
+#define VL53L1_TUNINGPARM_SPADMAP_VCSEL_START_DEFAULT \
+((uint8_t) 15)
+#define VL53L1_TUNINGPARM_SPADMAP_RATE_LIMIT_MCPS_DEFAULT \
+((uint16_t) 12)
+#define VL53L1_TUNINGPARM_LITE_DSS_CONFIG_TARGET_TOTAL_RATE_MCPS_DEFAULT \
+((uint16_t) 2560)
+#define VL53L1_TUNINGPARM_TIMED_DSS_CONFIG_TARGET_TOTAL_RATE_MCPS_DEFAULT \
+((uint16_t) 2560)
+#define VL53L1_TUNINGPARM_LITE_PHASECAL_CONFIG_TIMEOUT_US_DEFAULT \
+((uint32_t) 1000)
+#define VL53L1_TUNINGPARM_TIMED_PHASECAL_CONFIG_TIMEOUT_US_DEFAULT \
+((uint32_t) 1000)
+#define VL53L1_TUNINGPARM_LITE_MM_CONFIG_TIMEOUT_US_DEFAULT \
+((uint32_t) 2000)
+#define VL53L1_TUNINGPARM_TIMED_MM_CONFIG_TIMEOUT_US_DEFAULT \
+((uint32_t) 2000)
+#define VL53L1_TUNINGPARM_LITE_RANGE_CONFIG_TIMEOUT_US_DEFAULT \
+((uint32_t) 63000)
+#define VL53L1_TUNINGPARM_TIMED_RANGE_CONFIG_TIMEOUT_US_DEFAULT \
+((uint32_t) 13000)
+#define VL53L1_TUNINGPARM_LOWPOWERAUTO_VHV_LOOP_BOUND_DEFAULT \
+((uint8_t) 3)
+#define VL53L1_TUNINGPARM_LOWPOWERAUTO_MM_CONFIG_TIMEOUT_US_DEFAULT \
+((uint32_t) 1)
+#define VL53L1_TUNINGPARM_LOWPOWERAUTO_RANGE_CONFIG_TIMEOUT_US_DEFAULT \
+((uint32_t) 8000)
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _VL53L1_LL_DEF_H_ */
+
+
diff --git a/src/lib/vl53l1/core/inc/vl53l1_wait.h b/src/lib/vl53l1/core/inc/vl53l1_wait.h
new file mode 100644
index 0000000000..f85505bb0e
--- /dev/null
+++ b/src/lib/vl53l1/core/inc/vl53l1_wait.h
@@ -0,0 +1,242 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*******************************************************************************/
+
+/**
+ * @file vl53l1_wait.h
+ *
+ * @brief EwokPlus25 low level Driver wait function definitions
+ */
+
+#ifndef _VL53L1_WAIT_H_
+#define _VL53L1_WAIT_H_
+
+#include "../../../../drivers/interface/vl53l1x.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+/**
+ * @brief Wait for initial firmware boot to finish
+ *
+ * Calls VL53L1_poll_for_boot_completion()
+ *
+ * @param[in] Dev : Device handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_wait_for_boot_completion(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Waits for initial firmware ready
+ *
+ * Only waits to see if the firmware is ready in timed and
+ * single shot modes.
+ *
+ * Calls VL53L1_poll_for_firmware_ready()
+ *
+ * @param[in] Dev : Device handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_wait_for_firmware_ready(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Waits for the next ranging interrupt
+ *
+ * Calls VL53L1_poll_for_range_completion()
+ *
+ * @param[in] Dev : Device handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_wait_for_range_completion(
+ VL53L1_DEV Dev);
+
+
+/**
+ * @brief Waits for a device test mode to complete.
+
+ * Calls VL53L1_poll_for_test_completion()
+ *
+ * @param[in] Dev : Device Handle
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_wait_for_test_completion(
+ VL53L1_DEV Dev);
+
+
+
+
+/**
+ * @brief Reads FIRMWARE__SYSTEM_STATUS register to detect if the
+ * firmware was finished booting
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] pready : pointer to data ready flag \n
+ * 0 = boot not complete \n
+ * 1 = boot complete
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_is_boot_complete(
+ VL53L1_DEV Dev,
+ uint8_t *pready);
+
+/**
+ * @brief Reads FIRMWARE__SYSTEM_STATUS register to detect if the
+ * firmware is ready for ranging.
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] pready : pointer to data ready flag \n
+ * 0 = firmware not ready \n
+ * 1 = firmware ready
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_is_firmware_ready(
+ VL53L1_DEV Dev,
+ uint8_t *pready);
+
+
+/**
+ * @brief Reads bit 0 of VL53L1_GPIO__TIO_HV_STATUS register to determine
+ * if new range data is ready (available).
+ *
+ * Interrupt may be either active high or active low. The behaviour of bit 0
+ * of the VL53L1_GPIO__TIO_HV_STATUS register is the same as the interrupt
+ * signal generated on the GPIO pin.
+ *
+ * pdev->stat_cfg.gpio_hv_mux_ctrl bit 4 is used to select required check level
+ *
+ *
+ * @param[in] Dev : Device handle
+ * @param[out] pready : pointer to data ready flag \n
+ * 0 = data not ready \n
+ * 1 = new range data available
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_is_new_data_ready(
+ VL53L1_DEV Dev,
+ uint8_t *pready);
+
+
+
+
+/**
+ * @brief Waits (polls) for initial firmware boot to finish
+ *
+ * After power on or a device reset via XSHUTDOWN EwokPlus25 firmware takes
+ * about 2ms to boot. During this boot sequence elected NVM data is copied
+ * to the device's Host & MCU G02 registers
+ *
+ * This function polls the FIRMWARE__SYSTEM_STATUS register to detect when
+ * firmware is ready.
+ *
+ * Polling is implemented using VL53L1_WaitValueMaskEx()
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] timeout_ms : Wait timeout in [ms]
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_poll_for_boot_completion(
+ VL53L1_DEV Dev,
+ uint32_t timeout_ms);
+
+
+/**
+ * @brief Waits (polls) for initial firmware ready
+ *
+ * Polling is implemented using VL53L1_WaitValueMaskEx()
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] timeout_ms : Wait timeout in [ms]
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_poll_for_firmware_ready(
+ VL53L1_DEV Dev,
+ uint32_t timeout_ms);
+
+
+/**
+ * @brief Polls bit 0 of VL53L1_GPIO__TIO_HV_STATUS register to determine
+ * the state of the GPIO (Interrupt) pin.
+ *
+ * Interrupt may be either active high or active low. The behaviour of bit 0
+ * of the VL53L1_GPIO__TIO_HV_STATUS register is the same as the interrupt
+ * signal generated on the GPIO pin.
+ *
+ * pdev->stat_cfg.gpio_hv_mux_ctrl bit 4 is used to select required check level
+ *
+ * Polling is implemented using VL53L1_WaitValueMaskEx()
+ *
+ * @param[in] Dev : Device handle
+ * @param[in] timeout_ms : Wait timeout in [ms]
+ *
+ * @return VL53L1_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L1_Error
+ */
+
+VL53L1_Error VL53L1_poll_for_range_completion(
+ VL53L1_DEV Dev,
+ uint32_t timeout_ms);
+
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _VL53L1_WAIT_H_ */
diff --git a/src/lib/vl53l1/core/src/vl53l1_api.c b/src/lib/vl53l1/core/src/vl53l1_api.c
new file mode 100644
index 0000000000..2ccbe6e83b
--- /dev/null
+++ b/src/lib/vl53l1/core/src/vl53l1_api.c
@@ -0,0 +1,2988 @@
+/*
+* Copyright (c) 2017, STMicroelectronics - All Rights Reserved
+*
+* This file is part of VL53L1 Core and is dual licensed, either
+* 'STMicroelectronics Proprietary license'
+* or 'BSD 3-clause "New" or "Revised" License' , at your option.
+*
+********************************************************************************
+*
+* 'STMicroelectronics Proprietary license'
+*
+********************************************************************************
+*
+* License terms: STMicroelectronics Proprietary in accordance with licensing
+* terms at www.st.com/sla0044
+*
+* STMicroelectronics confidential
+* Reproduction and Communication of this document is strictly prohibited unless
+* specifically authorized in writing by STMicroelectronics.
+*
+*
+********************************************************************************
+*
+* Alternatively, VL53L1 Core may be distributed under the terms of
+* 'BSD 3-clause "New" or "Revised" License', in which case the following
+* provisions apply instead of the ones
+* mentioned above :
+*
+********************************************************************************
+*
+* License terms: BSD 3-clause "New" or "Revised" License.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions are met:
+*
+* 1. Redistributions of source code must retain the above copyright notice, this
+* list of conditions and the following disclaimer.
+*
+* 2. Redistributions in binary form must reproduce the above copyright notice,
+* this list of conditions and the following disclaimer in the documentation
+* and/or other materials provided with the distribution.
+*
+* 3. Neither the name of the copyright holder nor the names of its contributors
+* may be used to endorse or promote products derived from this software
+* without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*
+********************************************************************************
+*
+*/
+
+#include "vl53l1_api.h"
+#include "vl53l1_api_strings.h"
+#include "vl53l1_register_settings.h"
+#include "vl53l1_register_funcs.h"
+#include "vl53l1_core.h"
+#include "vl53l1_api_calibration.h"
+#include "vl53l1_wait.h"
+#include "vl53l1_preset_setup.h"
+#include "vl53l1_api_debug.h"
+#include "vl53l1_api_core.h"
+
+/* Check for minimum user zone requested by Xtalk calibration */
+/* no need for VL53L1_MAX_USER_ZONES check, set 5 to pass the test */
+#define ZONE_CHECK 5
+
+#if ZONE_CHECK < 5
+#error Must define at least 5 zones in MAX_USER_ZONES constant
+#endif
+
+
+#ifdef VL53L1_NOCALIB
+#define OFFSET_CALIB_EMPTY
+#endif
+
+#ifndef VL53L1_NOCALIB
+#define OFFSET_CALIB
+#endif
+
+#define LOG_FUNCTION_START(fmt, ...) \
+ _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_API, fmt, ##__VA_ARGS__)
+#define LOG_FUNCTION_END(status, ...) \
+ _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_API, status, ##__VA_ARGS__)
+#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
+ _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_API, status, \
+ fmt, ##__VA_ARGS__)
+
+#ifdef VL53L1_LOG_ENABLE
+#define trace_print(level, ...) trace_print_module_function(\
+ VL53L1_TRACE_MODULE_API, level, VL53L1_TRACE_FUNCTION_NONE, \
+ ##__VA_ARGS__)
+#endif
+
+#ifndef MIN
+#define MIN(v1, v2) ((v1) < (v2) ? (v1) : (v2))
+#endif
+#ifndef MAX
+#define MAX(v1, v2) ((v1) < (v2) ? (v2) : (v1))
+#endif
+
+#define DMAX_REFLECTANCE_IDX 2
+/* Use Dmax index 2 because it's the 50% reflectance case by default */
+
+/* Following LOWPOWER_AUTO figures have been measured observing vcsel
+ * emissions on an actual device
+ */
+#define LOWPOWER_AUTO_VHV_LOOP_DURATION_US 245
+#define LOWPOWER_AUTO_OVERHEAD_BEFORE_A_RANGING 1448
+#define LOWPOWER_AUTO_OVERHEAD_BETWEEN_A_B_RANGING 2100
+
+#define TUNING_PROXY_MIN -30 /* min distance in mm */
+#define TUNING_SINGLE_TARGET_XTALK_TARGET_DISTANCE_MM 600
+/* Target distance in mm for single target Xtalk */
+#define TUNING_SINGLE_TARGET_XTALK_SAMPLE_NUMBER 50
+/* Number of sample used for single target Xtalk */
+#define TUNING_MIN_AMBIENT_DMAX_VALID 8
+/* Minimum ambient level to state the Dmax returned by the device is valid */
+#define TUNING_MAX_SIMPLE_OFFSET_CALIBRATION_SAMPLE_NUMBER 50
+/* Maximum loops to perform simple offset calibration */
+
+#define FDA_MAX_TIMING_BUDGET_US 550000
+/* Maximum timing budget allowed codex #456189*/
+
+
+/* local static utilities functions */
+static VL53L1_Error set_tuning_parm(
+ VL53L1_DEV Dev,
+ VL53L1_TuningParms tuning_parm_key,
+ int32_t tuning_parm_value);
+static VL53L1_Error get_tuning_parm(
+ VL53L1_DEV Dev,
+ VL53L1_TuningParms tuning_parm_key,
+ int32_t *ptuning_parm_value);
+
+/* Bare Driver Tuning parameter table indexed with VL53L1_Tuning_t */
+static int32_t BDTable[VL53L1_TUNING_MAX_TUNABLE_KEY] = {
+ TUNING_VERSION,
+ TUNING_PROXY_MIN,
+ TUNING_SINGLE_TARGET_XTALK_TARGET_DISTANCE_MM,
+ TUNING_SINGLE_TARGET_XTALK_SAMPLE_NUMBER,
+ TUNING_MIN_AMBIENT_DMAX_VALID,
+ TUNING_MAX_SIMPLE_OFFSET_CALIBRATION_SAMPLE_NUMBER
+};
+
+#define VL53L1_NVM_POWER_UP_DELAY_US 50
+#define VL53L1_NVM_READ_TRIGGER_DELAY_US 5
+
+static VL53L1_Error VL53L1_nvm_enable(
+ VL53L1_DEV Dev,
+ uint16_t nvm_ctrl_pulse_width,
+ int32_t nvm_power_up_delay_us)
+{
+ /*
+ * Sequence below enables NVM for reading
+ *
+ * - Enable power force
+ * - Disable firmware
+ * - Power up NVM
+ * - Wait for 50us while the NVM powers up
+ * - Configure for reading and set the pulse width (16-bit)
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+
+ /* Disable Firmware */
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_disable_firmware(Dev);
+
+
+ /* Enable Power Force */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_powerforce(Dev);
+
+ /* Wait the required time for the regulators, bandgap,
+ * oscillator to wake up and settle
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WaitUs(
+ Dev,
+ VL53L1_ENABLE_POWERFORCE_SETTLING_TIME_US);
+
+ /* Power up NVM */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WrByte(
+ Dev,
+ VL53L1_RANGING_CORE__NVM_CTRL__PDN,
+ 0x01);
+
+ /* Enable NVM Clock */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WrByte(
+ Dev,
+ VL53L1_RANGING_CORE__CLK_CTRL1,
+ 0x05);
+
+ /* Wait the required time for NVM to power up*/
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WaitUs(
+ Dev,
+ nvm_power_up_delay_us);
+
+ /* Select read mode and set control pulse width */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WrByte(
+ Dev,
+ VL53L1_RANGING_CORE__NVM_CTRL__MODE,
+ 0x01);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WrWord(
+ Dev,
+ VL53L1_RANGING_CORE__NVM_CTRL__PULSE_WIDTH_MSB,
+ nvm_ctrl_pulse_width);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+
+}
+
+
+static VL53L1_Error VL53L1_nvm_read(
+ VL53L1_DEV Dev,
+ uint8_t start_address,
+ uint8_t count,
+ uint8_t *pdata)
+{
+ /*
+ * Sequence per 32-bit NVM read access:
+ *
+ * - Set up the 5-bit (0-127) NVM Address
+ * - Trigger the read of the NVM data by toggling NVM_CTRL__READN
+ * - Read the NVM data - 4 bytes wide read/write interface
+ * - Increment data byte pointer by 4 ready for the next loop
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t nvm_addr = 0;
+
+ LOG_FUNCTION_START("");
+
+ for (nvm_addr = start_address; nvm_addr < (start_address+count) ; nvm_addr++) {
+
+ /* Step 1 : set address */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WrByte(
+ Dev,
+ VL53L1_RANGING_CORE__NVM_CTRL__ADDR,
+ nvm_addr);
+
+ /* Step 2 : trigger reading of data */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WrByte(
+ Dev,
+ VL53L1_RANGING_CORE__NVM_CTRL__READN,
+ 0x00);
+
+ /* Step 3 : wait the required time */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WaitUs(
+ Dev,
+ VL53L1_NVM_READ_TRIGGER_DELAY_US);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WrByte(
+ Dev,
+ VL53L1_RANGING_CORE__NVM_CTRL__READN,
+ 0x01);
+
+ /* Step 3 : read 4-byte wide data register */
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_RANGING_CORE__NVM_CTRL__DATAOUT_MMM,
+ pdata,
+ 4);
+
+ /* Step 4 : increment byte buffer pointer */
+
+ pdata = pdata + 4;
+
+
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+static VL53L1_Error VL53L1_nvm_disable(
+ VL53L1_DEV Dev)
+{
+ /*
+ * Power down NVM (OTP) to extend lifetime
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_WrByte(
+ Dev,
+ VL53L1_RANGING_CORE__NVM_CTRL__READN,
+ 0x01);
+
+ /* Power down NVM */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WrByte(
+ Dev,
+ VL53L1_RANGING_CORE__NVM_CTRL__PDN,
+ 0x00);
+
+ /* Keep power force enabled */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_disable_powerforce(Dev);
+
+ /* (Re)Enable Firmware */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+
+}
+
+static VL53L1_Error VL53L1_read_nvm_raw_data(
+ VL53L1_DEV Dev,
+ uint8_t start_address,
+ uint8_t count,
+ uint8_t *pnvm_raw_data)
+{
+
+ /*
+ * Reads ALL 512 bytes of NVM data
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /*
+ * Enable NVM and set control pulse width
+ */
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_nvm_enable(
+ Dev,
+ 0x0004,
+ VL53L1_NVM_POWER_UP_DELAY_US);
+
+ /*
+ * Read the raw NVM data
+ * - currently all of 128 * 4 bytes = 512 bytes are read
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_nvm_read(
+ Dev,
+ start_address,
+ count,
+ pnvm_raw_data);
+
+ /*
+ * Disable NVM
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_nvm_disable(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+
+}
+
+static VL53L1_Error SingleTargetXTalkCalibration(VL53L1_DEV Dev)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ uint16_t sum_ranging = 0;
+ uint16_t sum_spads = 0;
+ FixPoint1616_t sum_signalRate = 0;
+ FixPoint1616_t total_count = 0;
+ uint8_t xtalk_meas = 0;
+ uint8_t xtalk_measmax =
+ BDTable[VL53L1_TUNING_SINGLE_TARGET_XTALK_SAMPLE_NUMBER];
+ VL53L1_RangingMeasurementData_t RMData;
+ FixPoint1616_t xTalkStoredMeanSignalRate;
+ FixPoint1616_t xTalkStoredMeanRange;
+ FixPoint1616_t xTalkStoredMeanRtnSpads;
+ uint32_t xTalkStoredMeanRtnSpadsAsInt;
+ uint32_t xTalkCalDistanceAsInt;
+ FixPoint1616_t XTalkCompensationRateMegaCps;
+ uint32_t signalXTalkTotalPerSpad;
+ VL53L1_PresetModes PresetMode;
+ VL53L1_CalibrationData_t CalibrationData;
+ VL53L1_CustomerNvmManaged_t *pC;
+
+
+ LOG_FUNCTION_START("");
+
+ /* check if the following are selected
+ * VL53L1_PRESETMODE_AUTONOMOUS,
+ * VL53L1_PRESETMODE_LOWPOWER_AUTONOMOUS
+ * VL53L1_PRESETMODE_LITE_RANGING
+ */
+ PresetMode = PALDevDataGet(Dev, CurrentParameters.PresetMode);
+
+ if ((PresetMode != VL53L1_PRESETMODE_AUTONOMOUS) &&
+ (PresetMode != VL53L1_PRESETMODE_LOWPOWER_AUTONOMOUS) &&
+ (PresetMode != VL53L1_PRESETMODE_LITE_RANGING)) {
+ Status = VL53L1_ERROR_MODE_NOT_SUPPORTED;
+ goto ENDFUNC;
+ }
+
+ /* disable crosstalk calibration */
+ Status = VL53L1_disable_xtalk_compensation(Dev);
+ CHECK_ERROR_GO_ENDFUNC;
+
+ Status = VL53L1_StartMeasurement(Dev);
+ CHECK_ERROR_GO_ENDFUNC;
+
+ sum_ranging = 0;
+ sum_spads = 0;
+ sum_signalRate = 0;
+ total_count = 0;
+ for (xtalk_meas = 0; xtalk_meas < xtalk_measmax; xtalk_meas++) {
+ VL53L1_WaitMeasurementDataReady(Dev);
+ VL53L1_GetRangingMeasurementData(Dev, &RMData);
+ VL53L1_ClearInterruptAndStartMeasurement(Dev);
+ if (RMData.RangeStatus == VL53L1_RANGESTATUS_RANGE_VALID) {
+ sum_ranging += RMData.RangeMilliMeter;
+ sum_signalRate += RMData.SignalRateRtnMegaCps;
+ sum_spads += RMData.EffectiveSpadRtnCount / 256;
+ total_count++;
+ }
+ }
+ Status = VL53L1_StopMeasurement(Dev);
+
+ if (total_count > 0) {
+ /* FixPoint1616_t / uint16_t = FixPoint1616_t */
+ xTalkStoredMeanSignalRate = sum_signalRate / total_count;
+ xTalkStoredMeanRange = (FixPoint1616_t)((uint32_t)(
+ sum_ranging << 16) / total_count);
+ xTalkStoredMeanRtnSpads = (FixPoint1616_t)((uint32_t)(
+ sum_spads << 16) / total_count);
+
+ /* Round Mean Spads to Whole Number.
+ * Typically the calculated mean SPAD count is a whole number
+ * or very close to a whole
+ * number, therefore any truncation will not result in a
+ * significant loss in accuracy.
+ * Also, for a grey target at a typical distance of around
+ * 400mm, around 220 SPADs will
+ * be enabled, therefore, any truncation will result in a loss
+ * of accuracy of less than
+ * 0.5%.
+ */
+ xTalkStoredMeanRtnSpadsAsInt = (xTalkStoredMeanRtnSpads +
+ 0x8000) >> 16;
+
+ /* Round Cal Distance to Whole Number.
+ * Note that the cal distance is in mm, therefore no resolution
+ * is lost.
+ */
+ xTalkCalDistanceAsInt = ((uint32_t)BDTable[
+ VL53L1_TUNING_SINGLE_TARGET_XTALK_TARGET_DISTANCE_MM]);
+ if (xTalkStoredMeanRtnSpadsAsInt == 0 ||
+ xTalkCalDistanceAsInt == 0 ||
+ xTalkStoredMeanRange >= (xTalkCalDistanceAsInt << 16)) {
+ XTalkCompensationRateMegaCps = 0;
+ } else {
+ /* Apply division by mean spad count early in the
+ * calculation to keep the numbers small.
+ * This ensures we can maintain a 32bit calculation.
+ * Fixed1616 / int := Fixed1616
+ */
+ signalXTalkTotalPerSpad = (xTalkStoredMeanSignalRate) /
+ xTalkStoredMeanRtnSpadsAsInt;
+
+ /* Complete the calculation for total Signal XTalk per
+ * SPAD
+ * Fixed1616 * (Fixed1616 - Fixed1616/int) :=
+ * (2^16 * Fixed1616)
+ */
+ signalXTalkTotalPerSpad *= ((1 << 16) -
+ (xTalkStoredMeanRange / xTalkCalDistanceAsInt));
+
+ /* Round from 2^16 * Fixed1616, to Fixed1616. */
+ XTalkCompensationRateMegaCps = (signalXTalkTotalPerSpad
+ + 0x8000) >> 16;
+ }
+
+
+ Status = VL53L1_GetCalibrationData(Dev, &CalibrationData);
+ CHECK_ERROR_GO_ENDFUNC;
+
+ pC = &CalibrationData.customer;
+
+ pC->algo__crosstalk_compensation_plane_offset_kcps =
+ (uint32_t)(1000 * ((XTalkCompensationRateMegaCps +
+ (1<<6)) >> (16-9)));
+
+ Status = VL53L1_SetCalibrationData(Dev, &CalibrationData);
+ CHECK_ERROR_GO_ENDFUNC;
+
+ Status = VL53L1_enable_xtalk_compensation(Dev);
+
+ } else
+ /* return error because no valid data found */
+ Status = VL53L1_ERROR_XTALK_EXTRACTION_NO_SAMPLE_FAIL;
+
+ENDFUNC:
+ LOG_FUNCTION_END(Status);
+ return Status;
+
+}
+
+/* Check Rectangle in user's coordinate system:
+ * 15 TL(x,y) o-----*
+ * ^ | |
+ * | *-----o BR(x,y)
+ * 0------------------------- >15
+ * check Rectangle definition conforms to the (0,15,15) coordinate system
+ * with a minimum of 4x4 size
+ */
+static VL53L1_Error CheckValidRectRoi(VL53L1_UserRoi_t ROI)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Negative check are not necessary because value is unsigned */
+ if ((ROI.TopLeftX > 15) || (ROI.TopLeftY > 15) ||
+ (ROI.BotRightX > 15) || (ROI.BotRightY > 15))
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+
+ if ((ROI.TopLeftX > ROI.BotRightX) || (ROI.TopLeftY < ROI.BotRightY))
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+static VL53L1_GPIO_Interrupt_Mode ConvertModeToLLD(VL53L1_Error *pStatus,
+ VL53L1_ThresholdMode CrossMode)
+{
+ VL53L1_GPIO_Interrupt_Mode Mode;
+
+ switch (CrossMode) {
+ case VL53L1_THRESHOLD_CROSSED_LOW:
+ Mode = VL53L1_GPIOINTMODE_LEVEL_LOW;
+ break;
+ case VL53L1_THRESHOLD_CROSSED_HIGH:
+ Mode = VL53L1_GPIOINTMODE_LEVEL_HIGH;
+ break;
+ case VL53L1_THRESHOLD_OUT_OF_WINDOW:
+ Mode = VL53L1_GPIOINTMODE_OUT_OF_WINDOW;
+ break;
+ case VL53L1_THRESHOLD_IN_WINDOW:
+ Mode = VL53L1_GPIOINTMODE_IN_WINDOW;
+ break;
+ default:
+ /* define Mode to avoid warning but actual value doesn't mind */
+ Mode = VL53L1_GPIOINTMODE_LEVEL_HIGH;
+ *pStatus = VL53L1_ERROR_INVALID_PARAMS;
+ }
+ return Mode;
+}
+
+static VL53L1_ThresholdMode ConvertModeFromLLD(VL53L1_Error *pStatus,
+ VL53L1_GPIO_Interrupt_Mode CrossMode)
+{
+ VL53L1_ThresholdMode Mode;
+
+ switch (CrossMode) {
+ case VL53L1_GPIOINTMODE_LEVEL_LOW:
+ Mode = VL53L1_THRESHOLD_CROSSED_LOW;
+ break;
+ case VL53L1_GPIOINTMODE_LEVEL_HIGH:
+ Mode = VL53L1_THRESHOLD_CROSSED_HIGH;
+ break;
+ case VL53L1_GPIOINTMODE_OUT_OF_WINDOW:
+ Mode = VL53L1_THRESHOLD_OUT_OF_WINDOW;
+ break;
+ case VL53L1_GPIOINTMODE_IN_WINDOW:
+ Mode = VL53L1_THRESHOLD_IN_WINDOW;
+ break;
+ default:
+ /* define Mode to avoid warning but actual value doesn't mind */
+ Mode = VL53L1_THRESHOLD_CROSSED_HIGH;
+ *pStatus = VL53L1_ERROR_UNDEFINED;
+ }
+ return Mode;
+}
+
+/* Group PAL General Functions */
+
+VL53L1_Error VL53L1_GetVersion(VL53L1_Version_t *pVersion)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ pVersion->major = VL53L1_IMPLEMENTATION_VER_MAJOR;
+ pVersion->minor = VL53L1_IMPLEMENTATION_VER_MINOR;
+ pVersion->build = VL53L1_IMPLEMENTATION_VER_SUB;
+
+ pVersion->revision = VL53L1_IMPLEMENTATION_VER_REVISION;
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_GetProductRevision(VL53L1_DEV Dev,
+ uint8_t *pProductRevisionMajor, uint8_t *pProductRevisionMinor)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ uint8_t revision_id;
+ VL53L1_LLDriverData_t *pLLData;
+
+ LOG_FUNCTION_START("");
+
+ pLLData = VL53L1DevStructGetLLDriverHandle(Dev);
+ revision_id = pLLData->nvm_copy_data.identification__revision_id;
+ *pProductRevisionMajor = 1;
+ *pProductRevisionMinor = (revision_id & 0xF0) >> 4;
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+
+}
+
+VL53L1_Error VL53L1_GetDeviceInfo(VL53L1_DEV Dev,
+ VL53L1_DeviceInfo_t *pVL53L1_DeviceInfo)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ uint8_t revision_id;
+ VL53L1_LLDriverData_t *pLLData;
+
+ LOG_FUNCTION_START("");
+
+ pLLData = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ strncpy(pVL53L1_DeviceInfo->ProductId, "",
+ VL53L1_DEVINFO_STRLEN-1);
+ pVL53L1_DeviceInfo->ProductType =
+ pLLData->nvm_copy_data.identification__module_type;
+
+ revision_id = pLLData->nvm_copy_data.identification__revision_id;
+ pVL53L1_DeviceInfo->ProductRevisionMajor = 1;
+ pVL53L1_DeviceInfo->ProductRevisionMinor = (revision_id & 0xF0) >> 4;
+
+#ifndef VL53L1_USE_EMPTY_STRING
+ if (pVL53L1_DeviceInfo->ProductRevisionMinor == 0)
+ strncpy(pVL53L1_DeviceInfo->Name,
+ VL53L1_STRING_DEVICE_INFO_NAME0,
+ VL53L1_DEVINFO_STRLEN-1);
+ else
+ strncpy(pVL53L1_DeviceInfo->Name,
+ VL53L1_STRING_DEVICE_INFO_NAME1,
+ VL53L1_DEVINFO_STRLEN-1);
+ strncpy(pVL53L1_DeviceInfo->Type,
+ VL53L1_STRING_DEVICE_INFO_TYPE,
+ VL53L1_DEVINFO_STRLEN-1);
+#else
+ pVL53L1_DeviceInfo->Name[0] = 0;
+ pVL53L1_DeviceInfo->Type[0] = 0;
+#endif
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+VL53L1_Error VL53L1_GetRangeStatusString(uint8_t RangeStatus,
+ char *pRangeStatusString)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ Status = VL53L1_get_range_status_string(RangeStatus,
+ pRangeStatusString);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_GetPalErrorString(VL53L1_Error PalErrorCode,
+ char *pPalErrorString)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ Status = VL53L1_get_pal_error_string(PalErrorCode, pPalErrorString);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_GetPalStateString(VL53L1_State PalStateCode,
+ char *pPalStateString)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ Status = VL53L1_get_pal_state_string(PalStateCode, pPalStateString);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_GetPalState(VL53L1_DEV Dev, VL53L1_State *pPalState)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ *pPalState = PALDevDataGet(Dev, PalState);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+/* End Group PAL General Functions */
+
+/* Group PAL Init Functions */
+VL53L1_Error VL53L1_SetDeviceAddress(VL53L1_DEV Dev, uint8_t DeviceAddress)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ Status = VL53L1_WrByte(Dev, VL53L1_I2C_SLAVE__DEVICE_ADDRESS,
+ DeviceAddress);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_DataInit(VL53L1_DEV Dev)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ uint8_t i;
+
+ LOG_FUNCTION_START("");
+
+ /* 2V8 power mode selection codex 447463 */
+#ifdef USE_I2C_2V8
+ Status = VL53L1_RdByte(Dev, VL53L1_PAD_I2C_HV__EXTSUP_CONFIG, &i);
+ if (Status == VL53L1_ERROR_NONE) {
+ i = (i & 0xfe) | 0x01;
+ Status = VL53L1_WrByte(Dev, VL53L1_PAD_I2C_HV__EXTSUP_CONFIG,
+ i);
+ }
+#endif
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_data_init(Dev, 1);
+
+ if (Status == VL53L1_ERROR_NONE) {
+ PALDevDataSet(Dev, PalState, VL53L1_STATE_WAIT_STATICINIT);
+ PALDevDataSet(Dev, CurrentParameters.PresetMode,
+ VL53L1_PRESETMODE_LOWPOWER_AUTONOMOUS);
+ }
+
+ /* Enable all check */
+ for (i = 0; i < VL53L1_CHECKENABLE_NUMBER_OF_CHECKS; i++) {
+ if (Status == VL53L1_ERROR_NONE)
+ Status |= VL53L1_SetLimitCheckEnable(Dev, i, 1);
+ else
+ break;
+
+ }
+
+ /* Limit default values */
+ if (Status == VL53L1_ERROR_NONE) {
+ Status = VL53L1_SetLimitCheckValue(Dev,
+ VL53L1_CHECKENABLE_SIGMA_FINAL_RANGE,
+ (FixPoint1616_t)(18 * 65536));
+ }
+ if (Status == VL53L1_ERROR_NONE) {
+ Status = VL53L1_SetLimitCheckValue(Dev,
+ VL53L1_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE,
+ (FixPoint1616_t)(25 * 65536 / 100));
+ /* 0.25 * 65536 */
+ }
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+VL53L1_Error VL53L1_StaticInit(VL53L1_DEV Dev)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ uint8_t measurement_mode;
+
+ LOG_FUNCTION_START("");
+
+ PALDevDataSet(Dev, PalState, VL53L1_STATE_IDLE);
+
+ measurement_mode = VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK;
+ PALDevDataSet(Dev, LLData.measurement_mode, measurement_mode);
+
+ PALDevDataSet(Dev, CurrentParameters.NewDistanceMode,
+ VL53L1_DISTANCEMODE_LONG);
+
+ PALDevDataSet(Dev, CurrentParameters.InternalDistanceMode,
+ VL53L1_DISTANCEMODE_LONG);
+
+ PALDevDataSet(Dev, CurrentParameters.DistanceMode,
+ VL53L1_DISTANCEMODE_LONG);
+
+ /* ticket 472728 fix */
+ Status = VL53L1_SetPresetMode(Dev,
+ VL53L1_PRESETMODE_LOWPOWER_AUTONOMOUS);
+ /* end of ticket 472728 fix */
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_WaitDeviceBooted(VL53L1_DEV Dev)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ Status = VL53L1_poll_for_boot_completion(Dev,
+ VL53L1_BOOT_COMPLETION_POLLING_TIMEOUT_MS);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+/* End Group PAL Init Functions */
+
+/* Group PAL Parameters Functions */
+static VL53L1_Error ComputeDevicePresetMode(
+ VL53L1_PresetModes PresetMode,
+ VL53L1_DistanceModes DistanceMode,
+ VL53L1_DevicePresetModes *pDevicePresetMode)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ uint8_t DistIdx;
+ VL53L1_DevicePresetModes LightModes[3] = {
+ VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_SHORT_RANGE,
+ VL53L1_DEVICEPRESETMODE_STANDARD_RANGING,
+ VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_LONG_RANGE};
+
+
+ VL53L1_DevicePresetModes TimedModes[3] = {
+ VL53L1_DEVICEPRESETMODE_TIMED_RANGING_SHORT_RANGE,
+ VL53L1_DEVICEPRESETMODE_TIMED_RANGING,
+ VL53L1_DEVICEPRESETMODE_TIMED_RANGING_LONG_RANGE};
+
+ VL53L1_DevicePresetModes LowPowerTimedModes[3] = {
+ VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_SHORT_RANGE,
+ VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_MEDIUM_RANGE,
+ VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_LONG_RANGE};
+
+ *pDevicePresetMode = VL53L1_DEVICEPRESETMODE_STANDARD_RANGING;
+
+ switch (DistanceMode) {
+ case VL53L1_DISTANCEMODE_SHORT:
+ DistIdx = 0;
+ break;
+ case VL53L1_DISTANCEMODE_MEDIUM:
+ DistIdx = 1;
+ break;
+ default:
+ DistIdx = 2;
+ }
+
+ switch (PresetMode) {
+ case VL53L1_PRESETMODE_LITE_RANGING:
+ *pDevicePresetMode = LightModes[DistIdx];
+ break;
+
+
+ case VL53L1_PRESETMODE_AUTONOMOUS:
+ *pDevicePresetMode = TimedModes[DistIdx];
+ break;
+
+ case VL53L1_PRESETMODE_LOWPOWER_AUTONOMOUS:
+ *pDevicePresetMode = LowPowerTimedModes[DistIdx];
+ break;
+
+ default:
+ /* Unsupported mode */
+ Status = VL53L1_ERROR_MODE_NOT_SUPPORTED;
+ }
+
+ return Status;
+}
+
+static VL53L1_Error SetPresetMode(VL53L1_DEV Dev,
+ VL53L1_PresetModes PresetMode,
+ VL53L1_DistanceModes DistanceMode,
+ uint32_t inter_measurement_period_ms)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ VL53L1_DevicePresetModes device_preset_mode;
+ uint8_t measurement_mode;
+ uint16_t dss_config__target_total_rate_mcps;
+ uint32_t phasecal_config_timeout_us;
+ uint32_t mm_config_timeout_us;
+ uint32_t lld_range_config_timeout_us;
+
+ LOG_FUNCTION_START("%d", (int)PresetMode);
+
+ if ((PresetMode == VL53L1_PRESETMODE_AUTONOMOUS) ||
+ (PresetMode == VL53L1_PRESETMODE_LOWPOWER_AUTONOMOUS))
+ measurement_mode = VL53L1_DEVICEMEASUREMENTMODE_TIMED;
+ else
+ measurement_mode = VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK;
+
+
+ Status = ComputeDevicePresetMode(PresetMode, DistanceMode,
+ &device_preset_mode);
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_get_preset_mode_timing_cfg(Dev,
+ device_preset_mode,
+ &dss_config__target_total_rate_mcps,
+ &phasecal_config_timeout_us,
+ &mm_config_timeout_us,
+ &lld_range_config_timeout_us);
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_set_preset_mode(
+ Dev,
+ device_preset_mode,
+ dss_config__target_total_rate_mcps,
+ phasecal_config_timeout_us,
+ mm_config_timeout_us,
+ lld_range_config_timeout_us,
+ inter_measurement_period_ms);
+
+ if (Status == VL53L1_ERROR_NONE)
+ PALDevDataSet(Dev, LLData.measurement_mode, measurement_mode);
+
+ if (Status == VL53L1_ERROR_NONE)
+ PALDevDataSet(Dev, CurrentParameters.PresetMode, PresetMode);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_SetPresetMode(VL53L1_DEV Dev, VL53L1_PresetModes PresetMode)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ VL53L1_DistanceModes DistanceMode = VL53L1_DISTANCEMODE_LONG;
+
+ LOG_FUNCTION_START("%d", (int)PresetMode);
+
+ Status = SetPresetMode(Dev,
+ PresetMode,
+ DistanceMode,
+ 1000);
+
+ if (Status == VL53L1_ERROR_NONE) {
+ PALDevDataSet(Dev, CurrentParameters.InternalDistanceMode,
+ DistanceMode);
+
+ PALDevDataSet(Dev, CurrentParameters.NewDistanceMode,
+ DistanceMode);
+
+ if ((PresetMode == VL53L1_PRESETMODE_LITE_RANGING) ||
+ (PresetMode == VL53L1_PRESETMODE_AUTONOMOUS) ||
+ (PresetMode == VL53L1_PRESETMODE_LOWPOWER_AUTONOMOUS))
+ Status = VL53L1_SetMeasurementTimingBudgetMicroSeconds(
+ Dev, 41000);
+ else
+ /* Set default timing budget to 30Hz (33.33 ms)*/
+ Status = VL53L1_SetMeasurementTimingBudgetMicroSeconds(
+ Dev, 33333);
+ }
+
+ if (Status == VL53L1_ERROR_NONE) {
+ /* Set default intermeasurement period to 1000 ms */
+ Status = VL53L1_SetInterMeasurementPeriodMilliSeconds(Dev,
+ 1000);
+ }
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+VL53L1_Error VL53L1_GetPresetMode(VL53L1_DEV Dev,
+ VL53L1_PresetModes *pPresetMode)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ *pPresetMode = PALDevDataGet(Dev, CurrentParameters.PresetMode);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_SetDistanceMode(VL53L1_DEV Dev,
+ VL53L1_DistanceModes DistanceMode)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ VL53L1_PresetModes PresetMode;
+ VL53L1_DistanceModes InternalDistanceMode;
+ uint32_t inter_measurement_period_ms;
+ uint32_t TimingBudget;
+ uint32_t MmTimeoutUs;
+ uint32_t PhaseCalTimeoutUs;
+ VL53L1_user_zone_t user_zone;
+
+ LOG_FUNCTION_START("%d", (int)DistanceMode);
+
+ PresetMode = PALDevDataGet(Dev, CurrentParameters.PresetMode);
+
+ /* when the distance mode is valid:
+ * Manual Mode: all modes
+ * AUTO AUTO_LITE : LITE_RANGING, RANGING
+ */
+
+ if ((DistanceMode != VL53L1_DISTANCEMODE_SHORT) &&
+ (DistanceMode != VL53L1_DISTANCEMODE_MEDIUM) &&
+ (DistanceMode != VL53L1_DISTANCEMODE_LONG))
+ return VL53L1_ERROR_INVALID_PARAMS;
+
+ /* The internal distance mode is limited to Short, Medium or
+ * long only
+ */
+ if (Status == VL53L1_ERROR_NONE) {
+ if ((DistanceMode == VL53L1_DISTANCEMODE_SHORT) ||
+ (DistanceMode == VL53L1_DISTANCEMODE_MEDIUM))
+ InternalDistanceMode = DistanceMode;
+ else /* (DistanceMode == VL53L1_DISTANCEMODE_LONG) */
+ InternalDistanceMode = VL53L1_DISTANCEMODE_LONG;
+ }
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_get_user_zone(Dev, &user_zone);
+
+ inter_measurement_period_ms = PALDevDataGet(Dev,
+ LLData.inter_measurement_period_ms);
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_get_timeouts_us(Dev, &PhaseCalTimeoutUs,
+ &MmTimeoutUs, &TimingBudget);
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = SetPresetMode(Dev,
+ PresetMode,
+ InternalDistanceMode,
+ inter_measurement_period_ms);
+
+ if (Status == VL53L1_ERROR_NONE) {
+ PALDevDataSet(Dev, CurrentParameters.InternalDistanceMode,
+ InternalDistanceMode);
+ PALDevDataSet(Dev, CurrentParameters.NewDistanceMode,
+ InternalDistanceMode);
+ PALDevDataSet(Dev, CurrentParameters.DistanceMode,
+ DistanceMode);
+ }
+
+ if (Status == VL53L1_ERROR_NONE) {
+ Status = VL53L1_set_timeouts_us(Dev, PhaseCalTimeoutUs,
+ MmTimeoutUs, TimingBudget);
+
+ if (Status == VL53L1_ERROR_NONE)
+ PALDevDataSet(Dev, LLData.range_config_timeout_us,
+ TimingBudget);
+ }
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_set_user_zone(Dev, &user_zone);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_GetDistanceMode(VL53L1_DEV Dev,
+ VL53L1_DistanceModes *pDistanceMode)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ *pDistanceMode = PALDevDataGet(Dev, CurrentParameters.DistanceMode);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+
+
+VL53L1_Error VL53L1_SetMeasurementTimingBudgetMicroSeconds(VL53L1_DEV Dev,
+ uint32_t MeasurementTimingBudgetMicroSeconds)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ uint8_t Mm1Enabled;
+ uint8_t Mm2Enabled;
+ uint32_t TimingGuard;
+ uint32_t divisor;
+ uint32_t TimingBudget;
+ uint32_t MmTimeoutUs;
+ VL53L1_PresetModes PresetMode;
+ uint32_t PhaseCalTimeoutUs;
+ uint32_t vhv;
+ int32_t vhv_loops;
+ uint32_t FDAMaxTimingBudgetUs = FDA_MAX_TIMING_BUDGET_US;
+
+ VL53L1_LLDriverData_t *pLLData;
+
+ LOG_FUNCTION_START("");
+
+ /* Timing budget is limited to 10 seconds */
+ if (MeasurementTimingBudgetMicroSeconds > 10000000)
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+
+ if (Status == VL53L1_ERROR_NONE) {
+ Status = VL53L1_GetSequenceStepEnable(Dev,
+ VL53L1_SEQUENCESTEP_MM1, &Mm1Enabled);
+ }
+
+ if (Status == VL53L1_ERROR_NONE) {
+ Status = VL53L1_GetSequenceStepEnable(Dev,
+ VL53L1_SEQUENCESTEP_MM2, &Mm2Enabled);
+ }
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_get_timeouts_us(Dev,
+ &PhaseCalTimeoutUs,
+ &MmTimeoutUs,
+ &TimingBudget);
+
+ if (Status == VL53L1_ERROR_NONE) {
+ PresetMode = PALDevDataGet(Dev, CurrentParameters.PresetMode);
+
+ TimingGuard = 0;
+ divisor = 1;
+ switch (PresetMode) {
+ case VL53L1_PRESETMODE_LITE_RANGING:
+ if ((Mm1Enabled == 1) || (Mm2Enabled == 1))
+ TimingGuard = 5000;
+ else
+ TimingGuard = 1000;
+ break;
+
+ case VL53L1_PRESETMODE_AUTONOMOUS:
+ FDAMaxTimingBudgetUs *= 2;
+ if ((Mm1Enabled == 1) || (Mm2Enabled == 1))
+ TimingGuard = 26600;
+ else
+ TimingGuard = 21600;
+ divisor = 2;
+ break;
+
+ case VL53L1_PRESETMODE_LOWPOWER_AUTONOMOUS:
+ FDAMaxTimingBudgetUs *= 2;
+ vhv = LOWPOWER_AUTO_VHV_LOOP_DURATION_US;
+ pLLData = VL53L1DevStructGetLLDriverHandle(Dev);
+ vhv_loops = pLLData->low_power_auto_data.vhv_loop_bound;
+ if (vhv_loops > 0) {
+ vhv += vhv_loops *
+ LOWPOWER_AUTO_VHV_LOOP_DURATION_US;
+ }
+ TimingGuard = LOWPOWER_AUTO_OVERHEAD_BEFORE_A_RANGING +
+ LOWPOWER_AUTO_OVERHEAD_BETWEEN_A_B_RANGING +
+ vhv;
+ divisor = 2;
+ break;
+
+ default:
+ /* Unsupported mode */
+ Status = VL53L1_ERROR_MODE_NOT_SUPPORTED;
+ }
+
+ if (MeasurementTimingBudgetMicroSeconds <= TimingGuard)
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ else {
+ TimingBudget = (MeasurementTimingBudgetMicroSeconds
+ - TimingGuard);
+ }
+
+ if (Status == VL53L1_ERROR_NONE) {
+ if (TimingBudget > FDAMaxTimingBudgetUs)
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ else {
+ TimingBudget /= divisor;
+ Status = VL53L1_set_timeouts_us(
+ Dev,
+ PhaseCalTimeoutUs,
+ MmTimeoutUs,
+ TimingBudget);
+ }
+
+ if (Status == VL53L1_ERROR_NONE)
+ PALDevDataSet(Dev,
+ LLData.range_config_timeout_us,
+ TimingBudget);
+ }
+ }
+ if (Status == VL53L1_ERROR_NONE) {
+ PALDevDataSet(Dev,
+ CurrentParameters.MeasurementTimingBudgetMicroSeconds,
+ MeasurementTimingBudgetMicroSeconds);
+ }
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+VL53L1_Error VL53L1_GetMeasurementTimingBudgetMicroSeconds(VL53L1_DEV Dev,
+ uint32_t *pMeasurementTimingBudgetMicroSeconds)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ uint8_t Mm1Enabled = 0;
+ uint8_t Mm2Enabled = 0;
+ uint32_t MmTimeoutUs = 0;
+ uint32_t RangeTimeoutUs = 0;
+ uint32_t MeasTimingBdg = 0;
+ uint32_t PhaseCalTimeoutUs = 0;
+ VL53L1_PresetModes PresetMode;
+ uint32_t TimingGuard;
+ uint32_t vhv;
+ int32_t vhv_loops;
+ VL53L1_LLDriverData_t *pLLData;
+
+ LOG_FUNCTION_START("");
+
+ *pMeasurementTimingBudgetMicroSeconds = 0;
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_GetSequenceStepEnable(Dev,
+ VL53L1_SEQUENCESTEP_MM1, &Mm1Enabled);
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_GetSequenceStepEnable(Dev,
+ VL53L1_SEQUENCESTEP_MM2, &Mm2Enabled);
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_get_timeouts_us(Dev,
+ &PhaseCalTimeoutUs,
+ &MmTimeoutUs,
+ &RangeTimeoutUs);
+
+ if (Status == VL53L1_ERROR_NONE) {
+ PresetMode = PALDevDataGet(Dev, CurrentParameters.PresetMode);
+
+ switch (PresetMode) {
+ case VL53L1_PRESETMODE_LITE_RANGING:
+ if ((Mm1Enabled == 1) || (Mm2Enabled == 1))
+ MeasTimingBdg = RangeTimeoutUs + 5000;
+ else
+ MeasTimingBdg = RangeTimeoutUs + 1000;
+
+ break;
+
+ case VL53L1_PRESETMODE_AUTONOMOUS:
+ if ((Mm1Enabled == 1) || (Mm2Enabled == 1))
+ MeasTimingBdg = 2 * RangeTimeoutUs + 26600;
+ else
+ MeasTimingBdg = 2 * RangeTimeoutUs + 21600;
+
+ break;
+
+ case VL53L1_PRESETMODE_LOWPOWER_AUTONOMOUS:
+ vhv = LOWPOWER_AUTO_VHV_LOOP_DURATION_US;
+ pLLData = VL53L1DevStructGetLLDriverHandle(Dev);
+ vhv_loops = pLLData->low_power_auto_data.vhv_loop_bound;
+ if (vhv_loops > 0) {
+ vhv += vhv_loops *
+ LOWPOWER_AUTO_VHV_LOOP_DURATION_US;
+ }
+ TimingGuard = LOWPOWER_AUTO_OVERHEAD_BEFORE_A_RANGING +
+ LOWPOWER_AUTO_OVERHEAD_BETWEEN_A_B_RANGING +
+ vhv;
+ MeasTimingBdg = 2 * RangeTimeoutUs + TimingGuard;
+ break;
+
+ default:
+ /* Unsupported mode */
+ Status = VL53L1_ERROR_MODE_NOT_SUPPORTED;
+ }
+ }
+ if (Status == VL53L1_ERROR_NONE)
+ *pMeasurementTimingBudgetMicroSeconds = MeasTimingBdg;
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+
+VL53L1_Error VL53L1_SetInterMeasurementPeriodMilliSeconds(VL53L1_DEV Dev,
+ uint32_t InterMeasurementPeriodMilliSeconds)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ Status = VL53L1_set_inter_measurement_period_ms(Dev,
+ InterMeasurementPeriodMilliSeconds);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_GetInterMeasurementPeriodMilliSeconds(VL53L1_DEV Dev,
+ uint32_t *pInterMeasurementPeriodMilliSeconds)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ Status = VL53L1_get_inter_measurement_period_ms(Dev,
+ pInterMeasurementPeriodMilliSeconds);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+/* End Group PAL Parameters Functions */
+
+
+/* Group Limit check Functions */
+
+VL53L1_Error VL53L1_GetNumberOfLimitCheck(uint16_t *pNumberOfLimitCheck)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ *pNumberOfLimitCheck = VL53L1_CHECKENABLE_NUMBER_OF_CHECKS;
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_GetLimitCheckInfo(uint16_t LimitCheckId,
+ char *pLimitCheckString)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ Status = VL53L1_get_limit_check_info(LimitCheckId,
+ pLimitCheckString);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_GetLimitCheckStatus(VL53L1_DEV Dev, uint16_t LimitCheckId,
+ uint8_t *pLimitCheckStatus)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ uint8_t Temp8;
+
+ LOG_FUNCTION_START("");
+
+ if (LimitCheckId >= VL53L1_CHECKENABLE_NUMBER_OF_CHECKS) {
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ } else {
+ VL53L1_GETARRAYPARAMETERFIELD(Dev, LimitChecksStatus,
+ LimitCheckId, Temp8);
+ *pLimitCheckStatus = Temp8;
+ }
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+static VL53L1_Error SetLimitValue(VL53L1_DEV Dev, uint16_t LimitCheckId,
+ FixPoint1616_t value)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ uint16_t tmpuint16; /* temporary variable */
+
+ LOG_FUNCTION_START("");
+
+ switch (LimitCheckId) {
+ case VL53L1_CHECKENABLE_SIGMA_FINAL_RANGE:
+ tmpuint16 = VL53L1_FIXPOINT1616TOFIXPOINT142(value);
+ VL53L1_set_lite_sigma_threshold(Dev, tmpuint16);
+ break;
+ case VL53L1_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE:
+ tmpuint16 = VL53L1_FIXPOINT1616TOFIXPOINT97(value);
+ VL53L1_set_lite_min_count_rate(Dev, tmpuint16);
+ break;
+ default:
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ }
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+VL53L1_Error VL53L1_SetLimitCheckEnable(VL53L1_DEV Dev, uint16_t LimitCheckId,
+ uint8_t LimitCheckEnable)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ FixPoint1616_t TempFix1616 = 0;
+
+ LOG_FUNCTION_START("");
+
+
+ if (LimitCheckId >= VL53L1_CHECKENABLE_NUMBER_OF_CHECKS) {
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ } else {
+ /* TempFix1616 contains either 0 or the limit value */
+ if (LimitCheckEnable == 0)
+ TempFix1616 = 0;
+ else
+ VL53L1_GETARRAYPARAMETERFIELD(Dev, LimitChecksValue,
+ LimitCheckId, TempFix1616);
+
+ Status = SetLimitValue(Dev, LimitCheckId, TempFix1616);
+ }
+
+ if (Status == VL53L1_ERROR_NONE)
+ VL53L1_SETARRAYPARAMETERFIELD(Dev,
+ LimitChecksEnable,
+ LimitCheckId,
+ ((LimitCheckEnable == 0) ? 0 : 1));
+
+
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_GetLimitCheckEnable(VL53L1_DEV Dev, uint16_t LimitCheckId,
+ uint8_t *pLimitCheckEnable)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ uint8_t Temp8;
+
+ LOG_FUNCTION_START("");
+
+ if (LimitCheckId >= VL53L1_CHECKENABLE_NUMBER_OF_CHECKS) {
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ *pLimitCheckEnable = 0;
+ } else {
+ VL53L1_GETARRAYPARAMETERFIELD(Dev, LimitChecksEnable,
+ LimitCheckId, Temp8);
+ *pLimitCheckEnable = Temp8;
+ }
+
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_SetLimitCheckValue(VL53L1_DEV Dev, uint16_t LimitCheckId,
+ FixPoint1616_t LimitCheckValue)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ uint8_t LimitChecksEnable;
+
+ LOG_FUNCTION_START("");
+
+ if (LimitCheckId >= VL53L1_CHECKENABLE_NUMBER_OF_CHECKS) {
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ } else {
+
+ VL53L1_GETARRAYPARAMETERFIELD(Dev, LimitChecksEnable,
+ LimitCheckId,
+ LimitChecksEnable);
+
+ if (LimitChecksEnable == 0) {
+ /* disabled write only internal value */
+ VL53L1_SETARRAYPARAMETERFIELD(Dev, LimitChecksValue,
+ LimitCheckId, LimitCheckValue);
+ } else {
+
+ Status = SetLimitValue(Dev, LimitCheckId,
+ LimitCheckValue);
+
+ if (Status == VL53L1_ERROR_NONE) {
+ VL53L1_SETARRAYPARAMETERFIELD(Dev,
+ LimitChecksValue,
+ LimitCheckId, LimitCheckValue);
+ }
+ }
+ }
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_GetLimitCheckValue(VL53L1_DEV Dev, uint16_t LimitCheckId,
+ FixPoint1616_t *pLimitCheckValue)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ uint16_t MinCountRate;
+ FixPoint1616_t TempFix1616;
+ uint16_t SigmaThresh;
+
+ LOG_FUNCTION_START("");
+
+ switch (LimitCheckId) {
+ case VL53L1_CHECKENABLE_SIGMA_FINAL_RANGE:
+ Status = VL53L1_get_lite_sigma_threshold(Dev, &SigmaThresh);
+ TempFix1616 = VL53L1_FIXPOINT142TOFIXPOINT1616(SigmaThresh);
+ break;
+ case VL53L1_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE:
+ Status = VL53L1_get_lite_min_count_rate(Dev, &MinCountRate);
+ TempFix1616 = VL53L1_FIXPOINT97TOFIXPOINT1616(MinCountRate);
+ break;
+ default:
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ }
+
+ if (Status == VL53L1_ERROR_NONE) {
+
+ if (TempFix1616 == 0) {
+ /* disabled: return value from memory */
+ VL53L1_GETARRAYPARAMETERFIELD(Dev,
+ LimitChecksValue, LimitCheckId,
+ TempFix1616);
+ *pLimitCheckValue = TempFix1616;
+ VL53L1_SETARRAYPARAMETERFIELD(Dev,
+ LimitChecksEnable, LimitCheckId, 0);
+ } else {
+ *pLimitCheckValue = TempFix1616;
+ VL53L1_SETARRAYPARAMETERFIELD(Dev,
+ LimitChecksValue, LimitCheckId,
+ TempFix1616);
+ VL53L1_SETARRAYPARAMETERFIELD(Dev,
+ LimitChecksEnable, LimitCheckId, 1);
+ }
+ }
+ LOG_FUNCTION_END(Status);
+ return Status;
+
+}
+
+VL53L1_Error VL53L1_GetLimitCheckCurrent(VL53L1_DEV Dev, uint16_t LimitCheckId,
+ FixPoint1616_t *pLimitCheckCurrent)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ FixPoint1616_t TempFix1616 = 0;
+
+ LOG_FUNCTION_START("");
+
+ if (LimitCheckId >= VL53L1_CHECKENABLE_NUMBER_OF_CHECKS) {
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ } else {
+ VL53L1_GETARRAYPARAMETERFIELD(Dev, LimitChecksCurrent,
+ LimitCheckId, TempFix1616);
+ *pLimitCheckCurrent = TempFix1616;
+ }
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+
+}
+
+/* End Group Limit check Functions */
+
+
+
+/* Group ROI Functions */
+
+VL53L1_Error VL53L1_SetUserROI(VL53L1_DEV Dev,
+ VL53L1_UserRoi_t *pRoi)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ VL53L1_user_zone_t user_zone;
+
+ Status = CheckValidRectRoi(*pRoi);
+ if (Status != VL53L1_ERROR_NONE)
+ return VL53L1_ERROR_INVALID_PARAMS;
+
+ user_zone.x_centre = (pRoi->BotRightX + pRoi->TopLeftX + 1) / 2;
+ user_zone.y_centre = (pRoi->TopLeftY + pRoi->BotRightY + 1) / 2;
+ user_zone.width = (pRoi->BotRightX - pRoi->TopLeftX);
+ user_zone.height = (pRoi->TopLeftY - pRoi->BotRightY);
+ if ((user_zone.width < 3) || (user_zone.height < 3))
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ else
+ Status = VL53L1_set_user_zone(Dev, &user_zone);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_GetUserROI(VL53L1_DEV Dev,
+ VL53L1_UserRoi_t *pRoi)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ VL53L1_user_zone_t user_zone;
+
+ Status = VL53L1_get_user_zone(Dev, &user_zone);
+
+ pRoi->TopLeftX = (2 * user_zone.x_centre - user_zone.width) >> 1;
+ pRoi->TopLeftY = (2 * user_zone.y_centre + user_zone.height) >> 1;
+ pRoi->BotRightX = (2 * user_zone.x_centre + user_zone.width) >> 1;
+ pRoi->BotRightY = (2 * user_zone.y_centre - user_zone.height) >> 1;
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+
+/* End Group ROI Functions */
+
+
+/* Group Sequence Step Functions */
+
+VL53L1_Error VL53L1_GetNumberOfSequenceSteps(VL53L1_DEV Dev,
+ uint8_t *pNumberOfSequenceSteps)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ SUPPRESS_UNUSED_WARNING(Dev);
+
+ LOG_FUNCTION_START("");
+
+ *pNumberOfSequenceSteps = VL53L1_SEQUENCESTEP_NUMBER_OF_ITEMS;
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_GetSequenceStepsInfo(VL53L1_SequenceStepId SequenceStepId,
+ char *pSequenceStepsString)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ Status = VL53L1_get_sequence_steps_info(
+ SequenceStepId,
+ pSequenceStepsString);
+
+ LOG_FUNCTION_END(Status);
+
+ return Status;
+}
+
+VL53L1_Error VL53L1_SetSequenceStepEnable(VL53L1_DEV Dev,
+ VL53L1_SequenceStepId SequenceStepId, uint8_t SequenceStepEnabled)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ uint32_t MeasurementTimingBudgetMicroSeconds;
+
+ LOG_FUNCTION_START("");
+
+ /* the VL53L1_SequenceStepId correspond to the LLD
+ * VL53L1_DeviceSequenceConfig
+ */
+
+ Status = VL53L1_set_sequence_config_bit(Dev,
+ (VL53L1_DeviceSequenceConfig)SequenceStepId,
+ SequenceStepEnabled);
+
+ /* Apply New Setting */
+ if (Status == VL53L1_ERROR_NONE) {
+
+ /* Recalculate timing budget */
+ MeasurementTimingBudgetMicroSeconds = PALDevDataGet(Dev,
+ CurrentParameters.MeasurementTimingBudgetMicroSeconds);
+
+ VL53L1_SetMeasurementTimingBudgetMicroSeconds(Dev,
+ MeasurementTimingBudgetMicroSeconds);
+ }
+
+ LOG_FUNCTION_END(Status);
+
+ return Status;
+}
+
+
+VL53L1_Error VL53L1_GetSequenceStepEnable(VL53L1_DEV Dev,
+ VL53L1_SequenceStepId SequenceStepId, uint8_t *pSequenceStepEnabled)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ Status = VL53L1_get_sequence_config_bit(Dev,
+ (VL53L1_DeviceSequenceConfig)SequenceStepId,
+ pSequenceStepEnabled);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+/* End Group Sequence Step Functions Functions */
+
+
+
+/* Group PAL Measurement Functions */
+
+
+
+VL53L1_Error VL53L1_StartMeasurement(VL53L1_DEV Dev)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ uint8_t DeviceMeasurementMode;
+ VL53L1_State CurrPalState;
+
+ LOG_FUNCTION_START("");
+
+ CurrPalState = PALDevDataGet(Dev, PalState);
+ switch (CurrPalState) {
+ case VL53L1_STATE_IDLE:
+ Status = VL53L1_ERROR_NONE;
+ break;
+ case VL53L1_STATE_POWERDOWN:
+ case VL53L1_STATE_WAIT_STATICINIT:
+ case VL53L1_STATE_STANDBY:
+ case VL53L1_STATE_RUNNING:
+ case VL53L1_STATE_RESET:
+ case VL53L1_STATE_UNKNOWN:
+ case VL53L1_STATE_ERROR:
+ Status = VL53L1_ERROR_INVALID_COMMAND;
+ break;
+ default:
+ Status = VL53L1_ERROR_UNDEFINED;
+ }
+
+ DeviceMeasurementMode = PALDevDataGet(Dev, LLData.measurement_mode);
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_init_and_start_range(
+ Dev,
+ DeviceMeasurementMode,
+ VL53L1_DEVICECONFIGLEVEL_FULL);
+
+ /* Set PAL State to Running */
+ if (Status == VL53L1_ERROR_NONE)
+ PALDevDataSet(Dev, PalState, VL53L1_STATE_RUNNING);
+
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_StopMeasurement(VL53L1_DEV Dev)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ Status = VL53L1_stop_range(Dev);
+
+ /* Set PAL State to Idle */
+ if (Status == VL53L1_ERROR_NONE)
+ PALDevDataSet(Dev, PalState, VL53L1_STATE_IDLE);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+static VL53L1_Error ChangePresetMode(VL53L1_DEV Dev)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ VL53L1_PresetModes PresetMode;
+ VL53L1_DistanceModes NewDistanceMode;
+ VL53L1_user_zone_t user_zone;
+ uint32_t TimingBudget;
+ uint32_t MmTimeoutUs;
+ uint32_t PhaseCalTimeoutUs;
+ uint8_t DeviceMeasurementMode;
+ uint32_t inter_measurement_period_ms;
+
+ LOG_FUNCTION_START("");
+
+ Status = VL53L1_get_user_zone(Dev, &user_zone);
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_get_timeouts_us(Dev, &PhaseCalTimeoutUs,
+ &MmTimeoutUs, &TimingBudget);
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_stop_range(Dev);
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_WaitUs(Dev, 500);
+
+ if (Status == VL53L1_ERROR_NONE) {
+ PresetMode = PALDevDataGet(Dev,
+ CurrentParameters.PresetMode);
+ NewDistanceMode = PALDevDataGet(Dev,
+ CurrentParameters.NewDistanceMode);
+ inter_measurement_period_ms = PALDevDataGet(Dev,
+ LLData.inter_measurement_period_ms);
+
+ Status = SetPresetMode(Dev,
+ PresetMode,
+ NewDistanceMode,
+ inter_measurement_period_ms);
+ }
+
+ if (Status == VL53L1_ERROR_NONE) {
+ Status = VL53L1_set_timeouts_us(Dev, PhaseCalTimeoutUs,
+ MmTimeoutUs, TimingBudget);
+
+ if (Status == VL53L1_ERROR_NONE)
+ PALDevDataSet(Dev, LLData.range_config_timeout_us,
+ TimingBudget);
+ }
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_set_user_zone(Dev, &user_zone);
+
+ if (Status == VL53L1_ERROR_NONE) {
+ DeviceMeasurementMode = PALDevDataGet(Dev,
+ LLData.measurement_mode);
+
+ Status = VL53L1_init_and_start_range(
+ Dev,
+ DeviceMeasurementMode,
+ VL53L1_DEVICECONFIGLEVEL_FULL);
+ }
+
+ if (Status == VL53L1_ERROR_NONE)
+ PALDevDataSet(Dev,
+ CurrentParameters.InternalDistanceMode,
+ NewDistanceMode);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+VL53L1_Error VL53L1_ClearInterruptAndStartMeasurement(VL53L1_DEV Dev)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ uint8_t DeviceMeasurementMode;
+ VL53L1_DistanceModes InternalDistanceMode;
+ VL53L1_DistanceModes NewDistanceMode;
+
+ LOG_FUNCTION_START("");
+
+ DeviceMeasurementMode = PALDevDataGet(Dev, LLData.measurement_mode);
+ InternalDistanceMode = PALDevDataGet(Dev,
+ CurrentParameters.InternalDistanceMode);
+ NewDistanceMode = PALDevDataGet(Dev,
+ CurrentParameters.NewDistanceMode);
+
+ if (NewDistanceMode != InternalDistanceMode)
+ Status = ChangePresetMode(Dev);
+ else
+ Status = VL53L1_clear_interrupt_and_enable_next_range(
+ Dev,
+ DeviceMeasurementMode);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+VL53L1_Error VL53L1_GetMeasurementDataReady(VL53L1_DEV Dev,
+ uint8_t *pMeasurementDataReady)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ Status = VL53L1_is_new_data_ready(Dev, pMeasurementDataReady);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_WaitMeasurementDataReady(VL53L1_DEV Dev)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Note that the timeout is given by:
+ * VL53L1_RANGE_COMPLETION_POLLING_TIMEOUT_MS defined in def.h
+ */
+
+ Status = VL53L1_poll_for_range_completion(Dev,
+ VL53L1_RANGE_COMPLETION_POLLING_TIMEOUT_MS);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+
+static uint8_t ComputeRQL(uint8_t active_results,
+ uint8_t FilteredRangeStatus,
+ VL53L1_range_data_t *presults_data)
+{
+ int16_t SRL = 300;
+ uint16_t SRAS = 30;
+ FixPoint1616_t RAS;
+ FixPoint1616_t SRQL;
+ FixPoint1616_t GI = 7713587; /* 117.7 * 65536 */
+ FixPoint1616_t GGm = 3198157; /* 48.8 * 65536 */
+ FixPoint1616_t LRAP = 6554; /* 0.1 * 65536 */
+ FixPoint1616_t partial;
+ uint8_t finalvalue;
+ uint8_t returnvalue;
+
+ if (active_results == 0)
+ returnvalue = 0;
+ else if (FilteredRangeStatus == VL53L1_DEVICEERROR_PHASECONSISTENCY)
+ returnvalue = 50;
+ else {
+ if (presults_data->median_range_mm < SRL)
+ RAS = SRAS * 65536;
+ else
+ RAS = LRAP * presults_data->median_range_mm;
+
+ /* Fix1616 + (fix1616 * uint16_t / fix1616) * 65536 = fix1616 */
+ if (RAS != 0) {
+ partial = (GGm * presults_data->sigma_mm);
+ partial = partial + (RAS >> 1);
+ partial = partial / RAS;
+ partial = partial * 65536;
+ if (partial <= GI)
+ SRQL = GI - partial;
+ else
+ SRQL = 50 * 65536;
+ } else
+ SRQL = 100 * 65536;
+
+ finalvalue = (uint8_t)(SRQL >> 16);
+ returnvalue = MAX(50, MIN(100, finalvalue));
+ }
+
+ return returnvalue;
+}
+
+
+static uint8_t ConvertStatusLite(uint8_t FilteredRangeStatus)
+{
+ uint8_t RangeStatus;
+
+ switch (FilteredRangeStatus) {
+ case VL53L1_DEVICEERROR_GPHSTREAMCOUNT0READY:
+ RangeStatus = VL53L1_RANGESTATUS_SYNCRONISATION_INT;
+ break;
+ case VL53L1_DEVICEERROR_RANGECOMPLETE_NO_WRAP_CHECK:
+ RangeStatus = VL53L1_RANGESTATUS_RANGE_VALID_NO_WRAP_CHECK_FAIL;
+ break;
+ case VL53L1_DEVICEERROR_RANGEPHASECHECK:
+ RangeStatus = VL53L1_RANGESTATUS_OUTOFBOUNDS_FAIL;
+ break;
+ case VL53L1_DEVICEERROR_MSRCNOTARGET:
+ RangeStatus = VL53L1_RANGESTATUS_SIGNAL_FAIL;
+ break;
+ case VL53L1_DEVICEERROR_SIGMATHRESHOLDCHECK:
+ RangeStatus = VL53L1_RANGESTATUS_SIGMA_FAIL;
+ break;
+ case VL53L1_DEVICEERROR_PHASECONSISTENCY:
+ RangeStatus = VL53L1_RANGESTATUS_WRAP_TARGET_FAIL;
+ break;
+ case VL53L1_DEVICEERROR_RANGEIGNORETHRESHOLD:
+ RangeStatus = VL53L1_RANGESTATUS_XTALK_SIGNAL_FAIL;
+ break;
+ case VL53L1_DEVICEERROR_MINCLIP:
+ RangeStatus = VL53L1_RANGESTATUS_RANGE_VALID_MIN_RANGE_CLIPPED;
+ break;
+ case VL53L1_DEVICEERROR_RANGECOMPLETE:
+ RangeStatus = VL53L1_RANGESTATUS_RANGE_VALID;
+ break;
+ default:
+ RangeStatus = VL53L1_RANGESTATUS_NONE;
+ }
+
+ return RangeStatus;
+}
+
+
+
+static VL53L1_Error SetSimpleData(VL53L1_DEV Dev,
+ uint8_t active_results, uint8_t device_status,
+ VL53L1_range_data_t *presults_data,
+ VL53L1_RangingMeasurementData_t *pRangeData)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ uint8_t FilteredRangeStatus;
+ uint8_t SigmaLimitflag;
+ uint8_t SignalLimitflag;
+ uint8_t Temp8Enable;
+ uint8_t Temp8;
+ FixPoint1616_t AmbientRate;
+ FixPoint1616_t SignalRate;
+ FixPoint1616_t TempFix1616;
+ FixPoint1616_t LimitCheckValue;
+ int16_t Range;
+
+ pRangeData->TimeStamp = presults_data->time_stamp;
+
+ FilteredRangeStatus = presults_data->range_status & 0x1F;
+
+ pRangeData->RangeQualityLevel = ComputeRQL(active_results,
+ FilteredRangeStatus,
+ presults_data);
+
+ SignalRate = VL53L1_FIXPOINT97TOFIXPOINT1616(
+ presults_data->peak_signal_count_rate_mcps);
+ pRangeData->SignalRateRtnMegaCps
+ = SignalRate;
+
+ AmbientRate = VL53L1_FIXPOINT97TOFIXPOINT1616(
+ presults_data->ambient_count_rate_mcps);
+ pRangeData->AmbientRateRtnMegaCps = AmbientRate;
+
+ pRangeData->EffectiveSpadRtnCount =
+ presults_data->actual_effective_spads;
+
+ TempFix1616 = VL53L1_FIXPOINT97TOFIXPOINT1616(
+ presults_data->sigma_mm);
+
+ pRangeData->SigmaMilliMeter = TempFix1616;
+
+ pRangeData->RangeMilliMeter = presults_data->median_range_mm;
+
+ pRangeData->RangeFractionalPart = 0;
+
+ /* Treat device error status first */
+ switch (device_status) {
+ case VL53L1_DEVICEERROR_MULTCLIPFAIL:
+ case VL53L1_DEVICEERROR_VCSELWATCHDOGTESTFAILURE:
+ case VL53L1_DEVICEERROR_VCSELCONTINUITYTESTFAILURE:
+ case VL53L1_DEVICEERROR_NOVHVVALUEFOUND:
+ pRangeData->RangeStatus = VL53L1_RANGESTATUS_HARDWARE_FAIL;
+ break;
+ case VL53L1_DEVICEERROR_USERROICLIP:
+ pRangeData->RangeStatus = VL53L1_RANGESTATUS_MIN_RANGE_FAIL;
+ break;
+ default:
+ pRangeData->RangeStatus = VL53L1_RANGESTATUS_RANGE_VALID;
+ }
+
+ /* Now deal with range status according to the ranging preset */
+ if (pRangeData->RangeStatus == VL53L1_RANGESTATUS_RANGE_VALID) {
+ pRangeData->RangeStatus =
+ ConvertStatusLite(FilteredRangeStatus);
+ }
+
+ /* Update current Limit Check */
+ TempFix1616 = VL53L1_FIXPOINT97TOFIXPOINT1616(
+ presults_data->sigma_mm);
+ VL53L1_SETARRAYPARAMETERFIELD(Dev,
+ LimitChecksCurrent, VL53L1_CHECKENABLE_SIGMA_FINAL_RANGE,
+ TempFix1616);
+
+ TempFix1616 = VL53L1_FIXPOINT97TOFIXPOINT1616(
+ presults_data->peak_signal_count_rate_mcps);
+ VL53L1_SETARRAYPARAMETERFIELD(Dev,
+ LimitChecksCurrent, VL53L1_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE,
+ TempFix1616);
+
+ /* Update Limit Check Status */
+ /* Sigma */
+ VL53L1_GetLimitCheckValue(Dev,
+ VL53L1_CHECKENABLE_SIGMA_FINAL_RANGE,
+ &LimitCheckValue);
+
+ SigmaLimitflag = (FilteredRangeStatus ==
+ VL53L1_DEVICEERROR_SIGMATHRESHOLDCHECK)
+ ? 1 : 0;
+
+ VL53L1_GetLimitCheckEnable(Dev,
+ VL53L1_CHECKENABLE_SIGMA_FINAL_RANGE,
+ &Temp8Enable);
+
+ Temp8 = ((Temp8Enable == 1) && (SigmaLimitflag == 1)) ? 1 : 0;
+ VL53L1_SETARRAYPARAMETERFIELD(Dev, LimitChecksStatus,
+ VL53L1_CHECKENABLE_SIGMA_FINAL_RANGE, Temp8);
+
+ /* Signal Rate */
+ VL53L1_GetLimitCheckValue(Dev,
+ VL53L1_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE,
+ &LimitCheckValue);
+
+ SignalLimitflag = (FilteredRangeStatus ==
+ VL53L1_DEVICEERROR_MSRCNOTARGET)
+ ? 1 : 0;
+
+ VL53L1_GetLimitCheckEnable(Dev,
+ VL53L1_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE,
+ &Temp8Enable);
+
+ Temp8 = ((Temp8Enable == 1) && (SignalLimitflag == 1)) ? 1 : 0;
+ VL53L1_SETARRAYPARAMETERFIELD(Dev, LimitChecksStatus,
+ VL53L1_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE, Temp8);
+
+ Range = pRangeData->RangeMilliMeter;
+ if ((pRangeData->RangeStatus == VL53L1_RANGESTATUS_RANGE_VALID) &&
+ (Range < 0)) {
+ if (Range < BDTable[VL53L1_TUNING_PROXY_MIN])
+ pRangeData->RangeStatus =
+ VL53L1_RANGESTATUS_RANGE_INVALID;
+ else
+ pRangeData->RangeMilliMeter = 0;
+ }
+
+ return Status;
+}
+
+
+
+VL53L1_Error VL53L1_GetRangingMeasurementData(VL53L1_DEV Dev,
+ VL53L1_RangingMeasurementData_t *pRangingMeasurementData)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ VL53L1_range_results_t results;
+ VL53L1_range_results_t *presults = &results;
+ VL53L1_range_data_t *presults_data;
+
+ LOG_FUNCTION_START("");
+
+
+ /* Clear Ranging Data */
+ memset(pRangingMeasurementData, 0xFF,
+ sizeof(VL53L1_RangingMeasurementData_t));
+
+ /* Get Ranging Data */
+ Status = VL53L1_get_device_results(
+ Dev,
+ VL53L1_DEVICERESULTSLEVEL_FULL,
+ presults);
+
+ if (Status == VL53L1_ERROR_NONE) {
+ pRangingMeasurementData->StreamCount = presults->stream_count;
+
+ /* in case of lite ranging or autonomous the following function
+ * returns index = 0
+ */
+ presults_data = &(presults->data[0]);
+ Status = SetSimpleData(Dev, 1,
+ presults->device_status,
+ presults_data,
+ pRangingMeasurementData);
+ }
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+
+
+
+/* End Group PAL Measurement Functions */
+
+
+/* Group Calibration functions */
+VL53L1_Error VL53L1_SetTuningParameter(VL53L1_DEV Dev,
+ uint16_t TuningParameterId, int32_t TuningParameterValue)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (TuningParameterId >= 32768)
+ Status = set_tuning_parm(Dev,
+ TuningParameterId,
+ TuningParameterValue);
+ else {
+ if (TuningParameterId < VL53L1_TUNING_MAX_TUNABLE_KEY)
+ BDTable[TuningParameterId] = TuningParameterValue;
+ else
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ }
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_GetTuningParameter(VL53L1_DEV Dev,
+ uint16_t TuningParameterId, int32_t *pTuningParameterValue)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (TuningParameterId >= 32768)
+ Status = get_tuning_parm(Dev,
+ TuningParameterId,
+ pTuningParameterValue);
+ else {
+ if (TuningParameterId < VL53L1_TUNING_MAX_TUNABLE_KEY)
+ *pTuningParameterValue = BDTable[TuningParameterId];
+ else
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ }
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+VL53L1_Error VL53L1_PerformRefSpadManagement(VL53L1_DEV Dev)
+{
+#ifdef VL53L1_NOCALIB
+ VL53L1_Error Status = VL53L1_ERROR_NOT_SUPPORTED;
+
+ SUPPRESS_UNUSED_WARNING(Dev);
+
+ LOG_FUNCTION_START("");
+#else
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ VL53L1_Error RawStatus;
+ uint8_t dcrbuffer[24];
+ uint8_t *comms_buffer;
+ uint8_t numloc[2] = {5,3};
+ VL53L1_LLDriverData_t *pdev;
+ VL53L1_customer_nvm_managed_t *pc;
+ VL53L1_PresetModes PresetMode;
+
+ LOG_FUNCTION_START("");
+
+ pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+ pc = &pdev->customer;
+
+ if (Status == VL53L1_ERROR_NONE)
+ {
+ PresetMode = PALDevDataGet(Dev, CurrentParameters.PresetMode);
+ Status = VL53L1_run_ref_spad_char(Dev, &RawStatus);
+ /* We discovered RefSpad mngt badly breaks some preset mode
+ * The WA is to apply again the current one
+ */
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_SetPresetMode(Dev, PresetMode);
+ }
+
+ if (Status == VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_HIGH) {
+ /* Fix ticket #466282 RefSpad management error/warning -29
+ * force usage of location 3 and 5 refspads in registers
+ */
+ Status = VL53L1_read_nvm_raw_data(Dev,
+ (uint8_t)(0xA0 >> 2),
+ (uint8_t)(24 >> 2),
+ dcrbuffer);
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_WriteMulti( Dev,
+ VL53L1_REF_SPAD_MAN__NUM_REQUESTED_REF_SPADS,
+ numloc, 2);
+
+ if (Status == VL53L1_ERROR_NONE) {
+ pc->ref_spad_man__num_requested_ref_spads = numloc[0];
+ pc->ref_spad_man__ref_location = numloc[1];
+ }
+
+ if (Status == VL53L1_ERROR_NONE)
+ comms_buffer = &dcrbuffer[16];
+
+ /*
+ * update & copy reference SPAD enables to customer nvm managed
+ */
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_WriteMulti(Dev,
+ VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_REF_0,
+ comms_buffer, 6);
+
+ if (Status == VL53L1_ERROR_NONE) {
+ pc->global_config__spad_enables_ref_0 = comms_buffer[0];
+ pc->global_config__spad_enables_ref_1 = comms_buffer[1];
+ pc->global_config__spad_enables_ref_2 = comms_buffer[2];
+ pc->global_config__spad_enables_ref_3 = comms_buffer[3];
+ pc->global_config__spad_enables_ref_4 = comms_buffer[4];
+ pc->global_config__spad_enables_ref_5 = comms_buffer[5];
+ }
+ /* End of fix ticket #466282 */
+ }
+
+#endif
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+VL53L1_Error VL53L1_SetXTalkCompensationEnable(VL53L1_DEV Dev,
+ uint8_t XTalkCompensationEnable)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (XTalkCompensationEnable == 0)
+ Status = VL53L1_disable_xtalk_compensation(Dev);
+ else
+ Status = VL53L1_enable_xtalk_compensation(Dev);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+VL53L1_Error VL53L1_GetXTalkCompensationEnable(VL53L1_DEV Dev,
+ uint8_t *pXTalkCompensationEnable)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ VL53L1_get_xtalk_compensation_enable(
+ Dev,
+ pXTalkCompensationEnable);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_PerformSingleTargetXTalkCalibration(VL53L1_DEV Dev,
+ int32_t XTalkCalDistance)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (XTalkCalDistance > 0) {
+ BDTable[VL53L1_TUNING_SINGLE_TARGET_XTALK_TARGET_DISTANCE_MM] =
+ XTalkCalDistance;
+ Status = SingleTargetXTalkCalibration(Dev);
+ } else
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+VL53L1_Error VL53L1_SetOffsetCalibrationMode(VL53L1_DEV Dev,
+ VL53L1_OffsetCalibrationModes OffsetCalibrationMode)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ VL53L1_OffsetCalibrationMode offset_cal_mode;
+
+ LOG_FUNCTION_START("");
+
+ if (OffsetCalibrationMode == VL53L1_OFFSETCALIBRATIONMODE_STANDARD) {
+ offset_cal_mode = VL53L1_DEVICEPRESETMODE_STANDARD_RANGING;
+ } else if (OffsetCalibrationMode ==
+ VL53L1_OFFSETCALIBRATIONMODE_PRERANGE_ONLY) {
+ offset_cal_mode =
+ VL53L1_OFFSETCALIBRATIONMODE__MM1_MM2__STANDARD_PRE_RANGE_ONLY;
+ } else {
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ }
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_set_offset_calibration_mode(Dev,
+ offset_cal_mode);
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+#ifdef OFFSET_CALIB
+VL53L1_Error VL53L1_PerformOffsetCalibration(VL53L1_DEV Dev,
+ int32_t CalDistanceMilliMeter)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ VL53L1_Error UnfilteredStatus;
+ VL53L1_OffsetCalibrationMode offset_cal_mode;
+
+ LOG_FUNCTION_START("");
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_get_offset_calibration_mode(Dev,
+ &offset_cal_mode);
+
+ if (Status != VL53L1_ERROR_NONE) {
+ LOG_FUNCTION_END(Status);
+ return Status;
+ }
+
+ if ((offset_cal_mode ==
+ VL53L1_OFFSETCALIBRATIONMODE__MM1_MM2__STANDARD) ||
+ (offset_cal_mode ==
+ VL53L1_OFFSETCALIBRATIONMODE__MM1_MM2__STANDARD_PRE_RANGE_ONLY
+ )) {
+ if (Status == VL53L1_ERROR_NONE)
+ Status = VL53L1_run_offset_calibration(
+ Dev,
+ (int16_t)CalDistanceMilliMeter,
+ &UnfilteredStatus);
+ } else {
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ }
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+#endif
+#ifdef OFFSET_CALIB_EMPTY
+VL53L1_Error VL53L1_PerformOffsetCalibration(VL53L1_DEV Dev,
+ int32_t CalDistanceMilliMeter)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NOT_SUPPORTED;
+ SUPPRESS_UNUSED_WARNING(Dev);
+ SUPPRESS_UNUSED_WARNING(CalDistanceMilliMeter);
+ return Status;
+}
+#endif
+
+VL53L1_Error VL53L1_PerformOffsetSimpleCalibration(VL53L1_DEV Dev,
+ int32_t CalDistanceMilliMeter)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ int32_t sum_ranging;
+ uint8_t offset_meas;
+ uint8_t Max;
+ uint8_t total_count;
+ int16_t meanDistance_mm;
+ int16_t offset;
+ VL53L1_RangingMeasurementData_t RangingMeasurementData;
+ VL53L1_LLDriverData_t *pdev;
+
+ LOG_FUNCTION_START("");
+
+ pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+ /* Disable any offsets */
+ pdev->customer.algo__part_to_part_range_offset_mm = 0;
+ pdev->customer.mm_config__inner_offset_mm = 0;
+ pdev->customer.mm_config__outer_offset_mm = 0;
+
+ Max = BDTable[VL53L1_TUNING_MAX_SIMPLE_OFFSET_CALIBRATION_SAMPLE_NUMBER];
+
+ Status = VL53L1_StartMeasurement(Dev);
+ sum_ranging = 0;
+ offset_meas = 0;
+ total_count = 0;
+ while ((Status == VL53L1_ERROR_NONE) && (offset_meas < Max)) {
+ Status = VL53L1_WaitMeasurementDataReady(Dev);
+ if (Status == VL53L1_ERROR_NONE) {
+ Status = VL53L1_GetRangingMeasurementData(Dev,
+ &RangingMeasurementData);
+ }
+ if (Status == VL53L1_ERROR_NONE) {
+ if (RangingMeasurementData.RangeStatus ==
+ VL53L1_RANGESTATUS_RANGE_VALID) {
+ sum_ranging = sum_ranging +
+ RangingMeasurementData.RangeMilliMeter;
+ total_count++;
+ }
+ }
+ if (Status == VL53L1_ERROR_NONE) {
+ Status = VL53L1_ClearInterruptAndStartMeasurement(
+ Dev);
+ }
+ offset_meas++;
+ }
+
+ VL53L1_StopMeasurement(Dev);
+
+ /* no valid values found */
+ if (total_count == 0) {
+ Status = VL53L1_ERROR_OFFSET_CAL_NO_SAMPLE_FAIL;
+ }
+
+ /* check overflow (unlikely if target is near to the device) */
+ if ((sum_ranging < 0) ||
+ (sum_ranging > ((int32_t) total_count * 0xffff))) {
+ Status = VL53L1_WARNING_OFFSET_CAL_SIGMA_TOO_HIGH;
+ }
+
+ if (Status == VL53L1_ERROR_NONE) {
+ meanDistance_mm = (int16_t)(sum_ranging / total_count);
+ offset = (int16_t)CalDistanceMilliMeter - meanDistance_mm;
+ pdev->customer.algo__part_to_part_range_offset_mm = 0;
+ pdev->customer.mm_config__inner_offset_mm = offset;
+ pdev->customer.mm_config__outer_offset_mm = offset;
+
+ Status = VL53L1_set_customer_nvm_managed(Dev,
+ &(pdev->customer));
+ }
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+VL53L1_Error VL53L1_SetCalibrationData(VL53L1_DEV Dev,
+ VL53L1_CalibrationData_t *pCalibrationData)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ VL53L1_CustomerNvmManaged_t *pC;
+ VL53L1_calibration_data_t cal_data;
+ uint32_t x;
+
+ LOG_FUNCTION_START("");
+
+ cal_data.struct_version = pCalibrationData->struct_version -
+ VL53L1_ADDITIONAL_CALIBRATION_DATA_STRUCT_VERSION;
+
+
+
+ /* memcpy(DEST, SRC, N) */
+ memcpy(
+ &(cal_data.add_off_cal_data),
+ &(pCalibrationData->add_off_cal_data),
+ sizeof(VL53L1_additional_offset_cal_data_t));
+
+ /* memcpy (DEST, SRC, N) */
+ memcpy(
+ &(cal_data.optical_centre),
+ &(pCalibrationData->optical_centre),
+ sizeof(VL53L1_optical_centre_t));
+
+ /* memcpy (DEST, SRC, N) */
+ memcpy(
+ &(cal_data.gain_cal),
+ &(pCalibrationData->gain_cal),
+ sizeof(VL53L1_gain_calibration_data_t));
+
+ /* memcpy (DEST, SRC, N) */
+ memcpy(
+ &(cal_data.cal_peak_rate_map),
+ &(pCalibrationData->cal_peak_rate_map),
+ sizeof(VL53L1_cal_peak_rate_map_t));
+
+ pC = &pCalibrationData->customer;
+ x = pC->algo__crosstalk_compensation_plane_offset_kcps;
+ cal_data.customer.algo__crosstalk_compensation_plane_offset_kcps =
+ (uint16_t)(x&0x0000FFFF);
+
+ cal_data.customer.global_config__spad_enables_ref_0 =
+ pC->global_config__spad_enables_ref_0;
+ cal_data.customer.global_config__spad_enables_ref_1 =
+ pC->global_config__spad_enables_ref_1;
+ cal_data.customer.global_config__spad_enables_ref_2 =
+ pC->global_config__spad_enables_ref_2;
+ cal_data.customer.global_config__spad_enables_ref_3 =
+ pC->global_config__spad_enables_ref_3;
+ cal_data.customer.global_config__spad_enables_ref_4 =
+ pC->global_config__spad_enables_ref_4;
+ cal_data.customer.global_config__spad_enables_ref_5 =
+ pC->global_config__spad_enables_ref_5;
+ cal_data.customer.global_config__ref_en_start_select =
+ pC->global_config__ref_en_start_select;
+ cal_data.customer.ref_spad_man__num_requested_ref_spads =
+ pC->ref_spad_man__num_requested_ref_spads;
+ cal_data.customer.ref_spad_man__ref_location =
+ pC->ref_spad_man__ref_location;
+ cal_data.customer.algo__crosstalk_compensation_x_plane_gradient_kcps =
+ pC->algo__crosstalk_compensation_x_plane_gradient_kcps;
+ cal_data.customer.algo__crosstalk_compensation_y_plane_gradient_kcps =
+ pC->algo__crosstalk_compensation_y_plane_gradient_kcps;
+ cal_data.customer.ref_spad_char__total_rate_target_mcps =
+ pC->ref_spad_char__total_rate_target_mcps;
+ cal_data.customer.algo__part_to_part_range_offset_mm =
+ pC->algo__part_to_part_range_offset_mm;
+ cal_data.customer.mm_config__inner_offset_mm =
+ pC->mm_config__inner_offset_mm;
+ cal_data.customer.mm_config__outer_offset_mm =
+ pC->mm_config__outer_offset_mm;
+
+ Status = VL53L1_set_part_to_part_data(Dev, &cal_data);
+ LOG_FUNCTION_END(Status);
+ return Status;
+
+}
+
+VL53L1_Error VL53L1_GetCalibrationData(VL53L1_DEV Dev,
+ VL53L1_CalibrationData_t *pCalibrationData)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ VL53L1_calibration_data_t cal_data;
+ VL53L1_CustomerNvmManaged_t *pC;
+ VL53L1_customer_nvm_managed_t *pC2;
+
+ LOG_FUNCTION_START("");
+
+ /* struct_version is filled inside get part to part function */
+ Status = VL53L1_get_part_to_part_data(Dev, &cal_data);
+
+ pCalibrationData->struct_version = cal_data.struct_version +
+ VL53L1_ADDITIONAL_CALIBRATION_DATA_STRUCT_VERSION;
+
+
+ /* memcpy(DEST, SRC, N) */
+ memcpy(
+ &(pCalibrationData->add_off_cal_data),
+ &(cal_data.add_off_cal_data),
+ sizeof(VL53L1_additional_offset_cal_data_t));
+
+ /* memcpy (DEST, SRC, N) */
+ memcpy(
+ &(pCalibrationData->optical_centre),
+ &(cal_data.optical_centre),
+ sizeof(VL53L1_optical_centre_t));
+
+ /* memcpy (DEST, SRC, N) */
+ memcpy(
+ &(pCalibrationData->gain_cal),
+ &(cal_data.gain_cal),
+ sizeof(VL53L1_gain_calibration_data_t));
+
+ /* memcpy (DEST, SRC, N) */
+ memcpy(
+ &(pCalibrationData->cal_peak_rate_map),
+ &(cal_data.cal_peak_rate_map),
+ sizeof(VL53L1_cal_peak_rate_map_t));
+
+
+ pC = &pCalibrationData->customer;
+ pC2 = &cal_data.customer;
+ pC->global_config__spad_enables_ref_0 =
+ pC2->global_config__spad_enables_ref_0;
+ pC->global_config__spad_enables_ref_1 =
+ pC2->global_config__spad_enables_ref_1;
+ pC->global_config__spad_enables_ref_2 =
+ pC2->global_config__spad_enables_ref_2;
+ pC->global_config__spad_enables_ref_3 =
+ pC2->global_config__spad_enables_ref_3;
+ pC->global_config__spad_enables_ref_4 =
+ pC2->global_config__spad_enables_ref_4;
+ pC->global_config__spad_enables_ref_5 =
+ pC2->global_config__spad_enables_ref_5;
+ pC->global_config__ref_en_start_select =
+ pC2->global_config__ref_en_start_select;
+ pC->ref_spad_man__num_requested_ref_spads =
+ pC2->ref_spad_man__num_requested_ref_spads;
+ pC->ref_spad_man__ref_location =
+ pC2->ref_spad_man__ref_location;
+ pC->algo__crosstalk_compensation_x_plane_gradient_kcps =
+ pC2->algo__crosstalk_compensation_x_plane_gradient_kcps;
+ pC->algo__crosstalk_compensation_y_plane_gradient_kcps =
+ pC2->algo__crosstalk_compensation_y_plane_gradient_kcps;
+ pC->ref_spad_char__total_rate_target_mcps =
+ pC2->ref_spad_char__total_rate_target_mcps;
+ pC->algo__part_to_part_range_offset_mm =
+ pC2->algo__part_to_part_range_offset_mm;
+ pC->mm_config__inner_offset_mm =
+ pC2->mm_config__inner_offset_mm;
+ pC->mm_config__outer_offset_mm =
+ pC2->mm_config__outer_offset_mm;
+
+ pC->algo__crosstalk_compensation_plane_offset_kcps =
+ (uint32_t)(
+ pC2->algo__crosstalk_compensation_plane_offset_kcps);
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+
+VL53L1_Error VL53L1_GetOpticalCenter(VL53L1_DEV Dev,
+ FixPoint1616_t *pOpticalCenterX,
+ FixPoint1616_t *pOpticalCenterY)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ VL53L1_calibration_data_t CalibrationData;
+
+ LOG_FUNCTION_START("");
+
+ *pOpticalCenterX = 0;
+ *pOpticalCenterY = 0;
+ Status = VL53L1_get_part_to_part_data(Dev, &CalibrationData);
+ if (Status == VL53L1_ERROR_NONE) {
+ *pOpticalCenterX = VL53L1_FIXPOINT44TOFIXPOINT1616(
+ CalibrationData.optical_centre.x_centre);
+ *pOpticalCenterY = VL53L1_FIXPOINT44TOFIXPOINT1616(
+ CalibrationData.optical_centre.y_centre);
+ }
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+/* END Group Calibration functions */
+
+
+/* Group PAL detection triggered events Functions */
+
+VL53L1_Error VL53L1_SetThresholdConfig(VL53L1_DEV Dev,
+ VL53L1_DetectionConfig_t *pConfig)
+{
+#define BADTHRESBOUNDS(T) \
+ (((T.CrossMode == VL53L1_THRESHOLD_OUT_OF_WINDOW) || \
+ (T.CrossMode == VL53L1_THRESHOLD_IN_WINDOW)) && (T.Low > T.High))
+
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ VL53L1_GPIO_interrupt_config_t Cfg;
+ uint16_t g;
+ FixPoint1616_t gain, high1616, low1616;
+ VL53L1_LLDriverData_t *pdev;
+
+ LOG_FUNCTION_START("");
+
+ pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ Status = VL53L1_get_GPIO_interrupt_config(Dev, &Cfg);
+ if (Status == VL53L1_ERROR_NONE) {
+ if (pConfig->DetectionMode == VL53L1_DETECTION_NORMAL_RUN) {
+ Cfg.intr_new_measure_ready = 1;
+ Status = VL53L1_set_GPIO_interrupt_config_struct(Dev,
+ Cfg);
+ } else {
+ if (BADTHRESBOUNDS(pConfig->Distance))
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ if ((Status == VL53L1_ERROR_NONE) &&
+ (BADTHRESBOUNDS(pConfig->Rate)))
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ if (Status == VL53L1_ERROR_NONE) {
+ Cfg.intr_new_measure_ready = 0;
+ Cfg.intr_no_target = pConfig->IntrNoTarget;
+ /* fix ticket 466238
+ * Apply invert distance gain to thresholds */
+ g = pdev->gain_cal.standard_ranging_gain_factor;
+ /* gain is ufix 5.11, convert to 16.16 */
+ gain = (FixPoint1616_t) (g << 5);
+ high1616 = (FixPoint1616_t)
+ (pConfig->Distance.High << 16);
+ low1616 = (FixPoint1616_t)
+ (pConfig->Distance.Low << 16);
+ /* +32768 to round the results*/
+ high1616 = (high1616 + 32768) / gain;
+ low1616 = (low1616 + 32768) / gain;
+ Cfg.threshold_distance_high = (uint16_t)
+ (high1616 & 0xFFFF);
+ Cfg.threshold_distance_low = (uint16_t)
+ (low1616 & 0xFFFF);
+ /* end fix ticket 466238 */
+ Cfg.threshold_rate_high =
+ VL53L1_FIXPOINT1616TOFIXPOINT97(
+ pConfig->Rate.High);
+ Cfg.threshold_rate_low =
+ VL53L1_FIXPOINT1616TOFIXPOINT97(
+ pConfig->Rate.Low);
+
+ Cfg.intr_mode_distance = ConvertModeToLLD(
+ &Status,
+ pConfig->Distance.CrossMode);
+ if (Status == VL53L1_ERROR_NONE)
+ Cfg.intr_mode_rate = ConvertModeToLLD(
+ &Status,
+ pConfig->Rate.CrossMode);
+ }
+
+ /* Refine thresholds combination now */
+ if (Status == VL53L1_ERROR_NONE) {
+ Cfg.intr_combined_mode = 1;
+ switch (pConfig->DetectionMode) {
+ case VL53L1_DETECTION_DISTANCE_ONLY:
+ Cfg.threshold_rate_high = 0;
+ Cfg.threshold_rate_low = 0;
+ break;
+ case VL53L1_DETECTION_RATE_ONLY:
+ Cfg.threshold_distance_high = 0;
+ Cfg.threshold_distance_low = 0;
+ break;
+ case VL53L1_DETECTION_DISTANCE_OR_RATE:
+ /* Nothing to do all is already
+ * in place
+ */
+ break;
+ case VL53L1_DETECTION_DISTANCE_AND_RATE:
+ Cfg.intr_combined_mode = 0;
+ break;
+ default:
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ }
+ }
+
+ if (Status == VL53L1_ERROR_NONE)
+ Status =
+ VL53L1_set_GPIO_interrupt_config_struct(Dev,
+ Cfg);
+
+ }
+ }
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+VL53L1_Error VL53L1_GetThresholdConfig(VL53L1_DEV Dev,
+ VL53L1_DetectionConfig_t *pConfig)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+ VL53L1_GPIO_interrupt_config_t Cfg;
+
+ LOG_FUNCTION_START("");
+
+ Status = VL53L1_get_GPIO_interrupt_config(Dev, &Cfg);
+
+ if (Status != VL53L1_ERROR_NONE) {
+ LOG_FUNCTION_END(Status);
+ return Status;
+ }
+
+ pConfig->IntrNoTarget = Cfg.intr_no_target;
+ pConfig->Distance.High = Cfg.threshold_distance_high;
+ pConfig->Distance.Low = Cfg.threshold_distance_low;
+ pConfig->Rate.High =
+ VL53L1_FIXPOINT97TOFIXPOINT1616(
+ Cfg.threshold_rate_high);
+ pConfig->Rate.Low =
+ VL53L1_FIXPOINT97TOFIXPOINT1616(Cfg.threshold_rate_low);
+ pConfig->Distance.CrossMode =
+ ConvertModeFromLLD(&Status, Cfg.intr_mode_distance);
+ if (Status == VL53L1_ERROR_NONE)
+ pConfig->Rate.CrossMode =
+ ConvertModeFromLLD(&Status, Cfg.intr_mode_rate);
+
+ if (Cfg.intr_new_measure_ready == 1) {
+ pConfig->DetectionMode = VL53L1_DETECTION_NORMAL_RUN;
+ } else {
+ /* Refine thresholds combination now */
+ if (Status == VL53L1_ERROR_NONE) {
+ if (Cfg.intr_combined_mode == 0)
+ pConfig->DetectionMode =
+ VL53L1_DETECTION_DISTANCE_AND_RATE;
+ else {
+ if ((Cfg.threshold_distance_high == 0) &&
+ (Cfg.threshold_distance_low == 0))
+ pConfig->DetectionMode =
+ VL53L1_DETECTION_RATE_ONLY;
+ else if ((Cfg.threshold_rate_high == 0) &&
+ (Cfg.threshold_rate_low == 0))
+ pConfig->DetectionMode =
+ VL53L1_DETECTION_DISTANCE_ONLY;
+ else
+ pConfig->DetectionMode =
+ VL53L1_DETECTION_DISTANCE_OR_RATE;
+ }
+ }
+ }
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
+
+/* End Group PAL IRQ Triggered events Functions */
+
+static VL53L1_Error get_tuning_parm(
+ VL53L1_DEV Dev,
+ VL53L1_TuningParms tuning_parm_key,
+ int32_t *ptuning_parm_value)
+{
+
+ /*
+ * Gets the requested tuning parm value
+ * - Large case statement for returns
+ * - if key does not match, INVALID parm error returned
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ switch (tuning_parm_key) {
+
+ case VL53L1_TUNINGPARM_LITE_LONG_SIGMA_THRESH_MM:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_long_sigma_thresh_mm;
+ break;
+ case VL53L1_TUNINGPARM_LITE_MED_SIGMA_THRESH_MM:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_med_sigma_thresh_mm;
+ break;
+ case VL53L1_TUNINGPARM_LITE_SHORT_SIGMA_THRESH_MM:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_short_sigma_thresh_mm;
+ break;
+ case VL53L1_TUNINGPARM_LITE_LONG_MIN_COUNT_RATE_RTN_MCPS:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_long_min_count_rate_rtn_mcps;
+ break;
+ case VL53L1_TUNINGPARM_LITE_MED_MIN_COUNT_RATE_RTN_MCPS:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_med_min_count_rate_rtn_mcps;
+ break;
+ case VL53L1_TUNINGPARM_LITE_SHORT_MIN_COUNT_RATE_RTN_MCPS:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_short_min_count_rate_rtn_mcps;
+ break;
+
+ default:
+ *ptuning_parm_value = 0x7FFFFFFF;
+ status = VL53L1_ERROR_INVALID_PARAMS;
+ break;
+
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+static VL53L1_Error set_tuning_parm(
+ VL53L1_DEV Dev,
+ VL53L1_TuningParms tuning_parm_key,
+ int32_t tuning_parm_value)
+{
+
+ /*
+ * Sets the requested tuning parm value
+ * - Large case statement for set value
+ * - if key does not match, INVALID parm error returned
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ switch (tuning_parm_key) {
+
+ case VL53L1_TUNINGPARM_LITE_LONG_SIGMA_THRESH_MM:
+ pdev->tuning_parms.tp_lite_long_sigma_thresh_mm =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_MED_SIGMA_THRESH_MM:
+ pdev->tuning_parms.tp_lite_med_sigma_thresh_mm =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_SHORT_SIGMA_THRESH_MM:
+ pdev->tuning_parms.tp_lite_short_sigma_thresh_mm =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_LONG_MIN_COUNT_RATE_RTN_MCPS:
+ pdev->tuning_parms.tp_lite_long_min_count_rate_rtn_mcps =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_MED_MIN_COUNT_RATE_RTN_MCPS:
+ pdev->tuning_parms.tp_lite_med_min_count_rate_rtn_mcps =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_SHORT_MIN_COUNT_RATE_RTN_MCPS:
+ pdev->tuning_parms.tp_lite_short_min_count_rate_rtn_mcps =
+ (uint16_t)tuning_parm_value;
+ break;
+
+ default:
+ status = VL53L1_ERROR_INVALID_PARAMS;
+ break;
+
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
diff --git a/src/lib/vl53l1/core/src/vl53l1_api_calibration.c b/src/lib/vl53l1/core/src/vl53l1_api_calibration.c
new file mode 100644
index 0000000000..f20eea8da0
--- /dev/null
+++ b/src/lib/vl53l1/core/src/vl53l1_api_calibration.c
@@ -0,0 +1,842 @@
+/*******************************************************************************
+ Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ ******************************************************************************/
+
+/**
+ * @file vl53l1_api_core.c
+ *
+ * @brief EwokPlus25 low level API function definition
+ */
+
+
+#include "vl53l1_ll_def.h"
+#include "vl53l1_ll_device.h"
+#include "vl53l1_platform.h"
+#include "vl53l1_register_map.h"
+#include "vl53l1_register_funcs.h"
+#include "vl53l1_register_settings.h"
+#include "vl53l1_core.h"
+#include "vl53l1_wait.h"
+#include "vl53l1_api_preset_modes.h"
+#include "vl53l1_silicon_core.h"
+#include "vl53l1_api_core.h"
+#include "vl53l1_api_calibration.h"
+
+#ifdef VL53L1_LOG_ENABLE
+ #include "vl53l1_api_debug.h"
+#endif
+#ifdef VL53L1_LOGGING
+ #include "vl53l1_debug.h"
+#endif
+
+#define LOG_FUNCTION_START(fmt, ...) \
+ _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_CORE, fmt, ##__VA_ARGS__)
+#define LOG_FUNCTION_END(status, ...) \
+ _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_CORE, status, ##__VA_ARGS__)
+#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
+ _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_CORE, status, \
+ fmt, ##__VA_ARGS__)
+
+#define trace_print(level, ...) \
+ _LOG_TRACE_PRINT(VL53L1_TRACE_MODULE_CORE, \
+ level, VL53L1_TRACE_FUNCTION_NONE, ##__VA_ARGS__)
+
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_run_ref_spad_char(
+ VL53L1_DEV Dev,
+ VL53L1_Error *pcal_status)
+{
+ /*
+ * Runs Reference SPAD Characterisation
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint8_t comms_buffer[6];
+
+ VL53L1_refspadchar_config_t *prefspadchar = &(pdev->refspadchar);
+
+ LOG_FUNCTION_START("");
+
+ /*
+ * Ensure power force is enabled
+ */
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_enable_powerforce(Dev);
+
+ /*
+ * Configure device
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_set_ref_spad_char_config(
+ Dev,
+ prefspadchar->vcsel_period,
+ prefspadchar->timeout_us,
+ prefspadchar->target_count_rate_mcps,
+ prefspadchar->max_count_rate_limit_mcps,
+ prefspadchar->min_count_rate_limit_mcps,
+ pdev->stat_nvm.osc_measured__fast_osc__frequency);
+
+ /*
+ * Run device test
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_run_device_test(
+ Dev,
+ prefspadchar->device_test_mode);
+
+ /*
+ * Read results
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_ReadMulti(
+ Dev,
+ VL53L1_REF_SPAD_CHAR_RESULT__NUM_ACTUAL_REF_SPADS,
+ comms_buffer,
+ 2);
+
+ if (status == VL53L1_ERROR_NONE) {
+ pdev->dbg_results.ref_spad_char_result__num_actual_ref_spads =
+ comms_buffer[0];
+ pdev->dbg_results.ref_spad_char_result__ref_location =
+ comms_buffer[1];
+ }
+
+ /*
+ * copy results to customer nvm managed G02 registers
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_WriteMulti(
+ Dev,
+ VL53L1_REF_SPAD_MAN__NUM_REQUESTED_REF_SPADS,
+ comms_buffer,
+ 2);
+
+ if (status == VL53L1_ERROR_NONE) {
+ pdev->customer.ref_spad_man__num_requested_ref_spads =
+ comms_buffer[0];
+ pdev->customer.ref_spad_man__ref_location =
+ comms_buffer[1];
+ }
+
+ /* After Ref Spad Char the final set of good SPAD enables
+ * are stored in the NCY results registers below
+ *
+ * - RESULT__SPARE_0_SD_1
+ * - RESULT__SPARE_1_SD_1
+ * - RESULT__SPARE_2_SD_1
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_ReadMulti(
+ Dev,
+ VL53L1_RESULT__SPARE_0_SD1,
+ comms_buffer,
+ 6);
+
+ /*
+ * copy reference SPAD enables to customer nvm managed
+ * G02 registers
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_WriteMulti(
+ Dev,
+ VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_REF_0,
+ comms_buffer,
+ 6);
+
+ if (status == VL53L1_ERROR_NONE) {
+ pdev->customer.global_config__spad_enables_ref_0 =
+ comms_buffer[0];
+ pdev->customer.global_config__spad_enables_ref_1 =
+ comms_buffer[1];
+ pdev->customer.global_config__spad_enables_ref_2 =
+ comms_buffer[2];
+ pdev->customer.global_config__spad_enables_ref_3 =
+ comms_buffer[3];
+ pdev->customer.global_config__spad_enables_ref_4 =
+ comms_buffer[4];
+ pdev->customer.global_config__spad_enables_ref_5 =
+ comms_buffer[5];
+ }
+
+#ifdef VL53L1_LOG_ENABLE
+ /* Print customer nvm managed data */
+ if (status == VL53L1_ERROR_NONE)
+ VL53L1_print_customer_nvm_managed(
+ &(pdev->customer),
+ "run_ref_spad_char():pdev->lldata.customer.",
+ VL53L1_TRACE_MODULE_REF_SPAD_CHAR);
+#endif
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ switch (pdev->sys_results.result__range_status) {
+
+ case VL53L1_DEVICEERROR_REFSPADCHARNOTENOUGHDPADS:
+ status = VL53L1_WARNING_REF_SPAD_CHAR_NOT_ENOUGH_SPADS;
+ break;
+
+ case VL53L1_DEVICEERROR_REFSPADCHARMORETHANTARGET:
+ status = VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_HIGH;
+ break;
+
+ case VL53L1_DEVICEERROR_REFSPADCHARLESSTHANTARGET:
+ status = VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_LOW;
+ break;
+ }
+ }
+
+ /*
+ * Save unfiltered status
+ */
+
+ *pcal_status = status;
+
+ /* Status exception code */
+
+ IGNORE_STATUS(
+ IGNORE_REF_SPAD_CHAR_NOT_ENOUGH_SPADS,
+ VL53L1_WARNING_REF_SPAD_CHAR_NOT_ENOUGH_SPADS,
+ status);
+
+ IGNORE_STATUS(
+ IGNORE_REF_SPAD_CHAR_RATE_TOO_HIGH,
+ VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_HIGH,
+ status);
+
+ IGNORE_STATUS(
+ IGNORE_REF_SPAD_CHAR_RATE_TOO_LOW,
+ VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_LOW,
+ status);
+
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+VL53L1_Error VL53L1_run_offset_calibration(
+ VL53L1_DEV Dev,
+ int16_t cal_distance_mm,
+ VL53L1_Error *pcal_status)
+{
+ /*
+ * Runs offset calibration
+ *
+ * Recommended tuning parm settings:
+ *
+ * - pre_num_of_samples = 32
+ * - mm1_num_of_samples = 100
+ * - mm2_num_of_samples = 64
+ * - target_distance_mm = 140mm
+ * - target reflectance = 5%
+ *
+ * Standard Ranging (sigma delta mode):
+ * - dss_config__target_total_rate_mcps = 20.0 -40.0 Mcps
+ * - phasecal_config_timeout_us = 1000
+ * - range_config_timeout_us = 13000
+ * - mm_config_timeout_us = 13000
+ *
+ *
+ * Note: function parms simplified as part of
+ * Patch_CalFunctionSimplification_11791
+ *
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ VL53L1_DevicePresetModes device_preset_modes[VL53L1_MAX_OFFSET_RANGE_RESULTS];
+
+ VL53L1_range_results_t range_results;
+ VL53L1_range_results_t *prange_results = &range_results;
+ VL53L1_range_data_t *prange_data = NULL;
+ VL53L1_offset_range_data_t *poffset = NULL;
+
+ uint8_t i = 0;
+ uint8_t m = 0;
+ uint8_t measurement_mode =
+ VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK;
+ uint16_t manual_effective_spads =
+ pdev->gen_cfg.dss_config__manual_effective_spads_select;
+
+ uint8_t num_of_samples[VL53L1_MAX_OFFSET_RANGE_RESULTS];
+
+ LOG_FUNCTION_START("");
+
+ /* select requested offset calibration mode */
+
+ switch (pdev->offset_calibration_mode) {
+
+ default:
+ device_preset_modes[0] =
+ VL53L1_DEVICEPRESETMODE_STANDARD_RANGING;
+ device_preset_modes[1] =
+ VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM1_CAL;
+ device_preset_modes[2] =
+ VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM2_CAL;
+ break;
+ }
+
+ /* initialise num_of_samples */
+ /* Start Patch_CalFunctionSimplification_11791 */
+ num_of_samples[0] = pdev->offsetcal_cfg.pre_num_of_samples;
+ num_of_samples[1] = pdev->offsetcal_cfg.mm1_num_of_samples;
+ num_of_samples[2] = pdev->offsetcal_cfg.mm2_num_of_samples;
+ /* End Patch_CalFunctionSimplification_11791 */
+
+ /* force all offsets to zero */
+
+ switch (pdev->offset_calibration_mode) {
+
+ case VL53L1_OFFSETCALIBRATIONMODE__MM1_MM2__STANDARD_PRE_RANGE_ONLY:
+ /* only run pre range */
+ pdev->offset_results.active_results = 1;
+
+ break;
+
+ default:
+
+ pdev->customer.mm_config__inner_offset_mm = 0;
+ pdev->customer.mm_config__outer_offset_mm = 0;
+ pdev->offset_results.active_results =
+ VL53L1_MAX_OFFSET_RANGE_RESULTS;
+
+ break;
+ }
+
+ pdev->customer.algo__part_to_part_range_offset_mm = 0;
+
+ /* initialise offset range results */
+
+ pdev->offset_results.max_results = VL53L1_MAX_OFFSET_RANGE_RESULTS;
+ pdev->offset_results.cal_distance_mm = cal_distance_mm;
+
+ for (m = 0 ; m < VL53L1_MAX_OFFSET_RANGE_RESULTS; m++) {
+
+ poffset = &(pdev->offset_results.data[m]);
+ poffset->preset_mode = 0;
+ poffset->no_of_samples = 0;
+ poffset->effective_spads = 0;
+ poffset->peak_rate_mcps = 0;
+ poffset->sigma_mm = 0;
+ poffset->median_range_mm = 0;
+ }
+
+ for (m = 0 ; m < pdev->offset_results.active_results ; m++) {
+
+ poffset = &(pdev->offset_results.data[m]);
+
+ poffset->preset_mode = device_preset_modes[m];
+
+ /* Apply preset mode */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_set_preset_mode(
+ Dev,
+ device_preset_modes[m],
+ /* Start Patch_CalFunctionSimplification_11791 */
+ pdev->offsetcal_cfg.dss_config__target_total_rate_mcps,
+ pdev->offsetcal_cfg.phasecal_config_timeout_us,
+ pdev->offsetcal_cfg.mm_config_timeout_us,
+ pdev->offsetcal_cfg.range_config_timeout_us,
+ /* End Patch_CalFunctionSimplification_11791 */
+ 100);
+
+ pdev->gen_cfg.dss_config__manual_effective_spads_select =
+ manual_effective_spads;
+
+ /* Initialise device and start range */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_init_and_start_range(
+ Dev,
+ measurement_mode,
+ VL53L1_DEVICECONFIGLEVEL_CUSTOMER_ONWARDS);
+
+ for (i = 0 ; i <= (num_of_samples[m]+2) ; i++) {
+
+ /* Wait for range completion */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_wait_for_range_completion(Dev);
+
+ /*
+ * Get Device Results
+ * - Checks the stream count is the expected one
+ * - Read device system results
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_get_device_results(
+ Dev,
+ VL53L1_DEVICERESULTSLEVEL_FULL,
+ prange_results);
+
+ /*
+ * Ignore 1st two ranges to give the sigma delta initial
+ * phase time to settle
+ *
+ * accummulate range results if range is successful
+ */
+
+ prange_data = &(prange_results->data[0]);
+
+ if (prange_results->stream_count > 1) {
+
+ if (prange_data->range_status ==
+ VL53L1_DEVICEERROR_RANGECOMPLETE) {
+
+ poffset->no_of_samples++;
+ poffset->effective_spads +=
+ (uint32_t)prange_data->actual_effective_spads;
+ poffset->peak_rate_mcps +=
+ (uint32_t)prange_data->peak_signal_count_rate_mcps;
+ poffset->sigma_mm +=
+ (uint32_t)prange_data->sigma_mm;
+ poffset->median_range_mm +=
+ (int32_t)prange_data->median_range_mm;
+
+ poffset->dss_config__roi_mode_control =
+ pdev->gen_cfg.dss_config__roi_mode_control;
+ poffset->dss_config__manual_effective_spads_select =
+ pdev->gen_cfg.dss_config__manual_effective_spads_select;
+ }
+ }
+
+ /*
+ * Conditional wait for firmware ready. Only waits for timed
+ * and single shot modes. Mode check is performed inside the
+ * wait function
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_wait_for_firmware_ready(Dev);
+
+ /*
+ * Send ranging handshake
+ *
+ * - Update Zone management
+ * - Update GPH registers
+ * - Clear current interrupt
+ * - Initialise SYSTEM__MODE_START for next range (if there is one!)
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_clear_interrupt_and_enable_next_range(
+ Dev,
+ measurement_mode);
+ }
+
+ /* Stop range */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_stop_range(Dev);
+
+ /* Wait for Stop (abort) range to complete */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WaitUs(Dev, 1000);
+
+ /* generate average values */
+ if (poffset->no_of_samples > 0) {
+
+ poffset->effective_spads += (poffset->no_of_samples/2);
+ poffset->effective_spads /= poffset->no_of_samples;
+
+ poffset->peak_rate_mcps += (poffset->no_of_samples/2);
+ poffset->peak_rate_mcps /= poffset->no_of_samples;
+
+ poffset->sigma_mm += (poffset->no_of_samples/2);
+ poffset->sigma_mm /= poffset->no_of_samples;
+
+ poffset->median_range_mm += (poffset->no_of_samples/2);
+ poffset->median_range_mm /= poffset->no_of_samples;
+
+ poffset->range_mm_offset = (int32_t)cal_distance_mm;
+ poffset->range_mm_offset -= poffset->median_range_mm;
+
+ /* remember the number of SPADs for standard ranging */
+ if (poffset->preset_mode ==
+ VL53L1_DEVICEPRESETMODE_STANDARD_RANGING)
+ manual_effective_spads =
+ (uint16_t)poffset->effective_spads;
+ }
+ }
+
+ /* Calculate offsets */
+
+ switch (pdev->offset_calibration_mode) {
+
+ case VL53L1_OFFSETCALIBRATIONMODE__MM1_MM2__STANDARD_PRE_RANGE_ONLY:
+
+ /* copy offsets to customer data structure */
+ pdev->customer.mm_config__inner_offset_mm +=
+ (int16_t)pdev->offset_results.data[0].range_mm_offset;
+ pdev->customer.mm_config__outer_offset_mm +=
+ (int16_t)pdev->offset_results.data[0].range_mm_offset;
+ break;
+
+ default:
+ /* copy offsets to customer data structure */
+ pdev->customer.mm_config__inner_offset_mm =
+ (int16_t)pdev->offset_results.data[1].range_mm_offset;
+ pdev->customer.mm_config__outer_offset_mm =
+ (int16_t)pdev->offset_results.data[2].range_mm_offset;
+ pdev->customer.algo__part_to_part_range_offset_mm = 0;
+
+ /* copy average rate and effective SPAD count to
+ additional offset calibration data structure */
+
+ pdev->add_off_cal_data.result__mm_inner_actual_effective_spads =
+ (uint16_t)pdev->offset_results.data[1].effective_spads;
+ pdev->add_off_cal_data.result__mm_outer_actual_effective_spads =
+ (uint16_t)pdev->offset_results.data[2].effective_spads;
+
+ pdev->add_off_cal_data.result__mm_inner_peak_signal_count_rtn_mcps =
+ (uint16_t)pdev->offset_results.data[1].peak_rate_mcps;
+ pdev->add_off_cal_data.result__mm_outer_peak_signal_count_rtn_mcps =
+ (uint16_t)pdev->offset_results.data[2].peak_rate_mcps;
+
+ break;
+ }
+
+
+ /* apply to device */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_set_customer_nvm_managed(
+ Dev,
+ &(pdev->customer));
+
+ /*
+ * Check the peak rates, sigma, min spads for each stage
+ */
+
+ for (m = 0 ; m < pdev->offset_results.active_results ; m++) {
+
+ poffset = &(pdev->offset_results.data[m]);
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ pdev->offset_results.cal_report = m;
+
+ if (poffset->no_of_samples < num_of_samples[m])
+ status = VL53L1_WARNING_OFFSET_CAL_MISSING_SAMPLES;
+
+ /* only check sigma for the pre-range as
+ * the it is not calculated by the device
+ * for the MM1 and MM2 stages
+ */
+ if (m == 0 && poffset->sigma_mm >
+ ((uint32_t)VL53L1_OFFSET_CAL_MAX_SIGMA_MM<<5))
+ status = VL53L1_WARNING_OFFSET_CAL_SIGMA_TOO_HIGH;
+
+ if (poffset->peak_rate_mcps >
+ VL53L1_OFFSET_CAL_MAX_PRE_PEAK_RATE_MCPS)
+ status = VL53L1_WARNING_OFFSET_CAL_RATE_TOO_HIGH;
+
+ if (poffset->dss_config__manual_effective_spads_select <
+ VL53L1_OFFSET_CAL_MIN_EFFECTIVE_SPADS)
+ status = VL53L1_WARNING_OFFSET_CAL_SPAD_COUNT_TOO_LOW;
+
+ if (poffset->dss_config__manual_effective_spads_select == 0)
+ status = VL53L1_ERROR_OFFSET_CAL_NO_SPADS_ENABLED_FAIL;
+
+ if (poffset->no_of_samples == 0)
+ status = VL53L1_ERROR_OFFSET_CAL_NO_SAMPLE_FAIL;
+ }
+ }
+
+ /*
+ * Save unfiltered status
+ */
+
+ pdev->offset_results.cal_status = status;
+ *pcal_status = pdev->offset_results.cal_status;
+
+ /* Status exception codes */
+
+ IGNORE_STATUS(
+ IGNORE_OFFSET_CAL_MISSING_SAMPLES,
+ VL53L1_WARNING_OFFSET_CAL_MISSING_SAMPLES,
+ status);
+
+ IGNORE_STATUS(
+ IGNORE_OFFSET_CAL_SIGMA_TOO_HIGH,
+ VL53L1_WARNING_OFFSET_CAL_SIGMA_TOO_HIGH,
+ status);
+
+ IGNORE_STATUS(
+ IGNORE_OFFSET_CAL_RATE_TOO_HIGH,
+ VL53L1_WARNING_OFFSET_CAL_RATE_TOO_HIGH,
+ status);
+
+ IGNORE_STATUS(
+ IGNORE_OFFSET_CAL_SPAD_COUNT_TOO_LOW,
+ VL53L1_WARNING_OFFSET_CAL_SPAD_COUNT_TOO_LOW,
+ status);
+
+#ifdef VL53L1_LOG_ENABLE
+
+ /* Prints out the offset calibration data for debug */
+
+ VL53L1_print_customer_nvm_managed(
+ &(pdev->customer),
+ "run_offset_calibration():pdev->lldata.customer.",
+ VL53L1_TRACE_MODULE_OFFSET_DATA);
+
+ VL53L1_print_additional_offset_cal_data(
+ &(pdev->add_off_cal_data),
+ "run_offset_calibration():pdev->lldata.add_off_cal_data.",
+ VL53L1_TRACE_MODULE_OFFSET_DATA);
+
+ VL53L1_print_offset_range_results(
+ &(pdev->offset_results),
+ "run_offset_calibration():pdev->lldata.offset_results.",
+ VL53L1_TRACE_MODULE_OFFSET_DATA);
+#endif
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_run_spad_rate_map(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceTestMode device_test_mode,
+ VL53L1_DeviceSscArray array_select,
+ uint32_t ssc_config_timeout_us,
+ VL53L1_spad_rate_data_t *pspad_rate_data)
+{
+
+ /**
+ * Runs SPAD Rate Map
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ /*
+ * Ensure power force is enabled
+ */
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_powerforce(Dev);
+
+ /*
+ * Configure the test
+ */
+
+ if (status == VL53L1_ERROR_NONE) {
+ pdev->ssc_cfg.array_select = array_select;
+ pdev->ssc_cfg.timeout_us = ssc_config_timeout_us;
+ status =
+ VL53L1_set_ssc_config(
+ Dev,
+ &(pdev->ssc_cfg),
+ pdev->stat_nvm.osc_measured__fast_osc__frequency);
+ }
+
+ /*
+ * Run device test
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_run_device_test(
+ Dev,
+ device_test_mode);
+
+ /*
+ * Read Rate Data from Patch Ram
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_get_spad_rate_data(
+ Dev,
+ pspad_rate_data);
+
+ if (device_test_mode == VL53L1_DEVICETESTMODE_LCR_VCSEL_ON)
+ pspad_rate_data->fractional_bits = 7;
+ else
+ pspad_rate_data->fractional_bits = 15;
+
+ /* Ensure power force is disabled */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_disable_powerforce(Dev);
+
+#ifdef VL53L1_LOG_ENABLE
+ /* Print return rate data and map */
+
+ if (status == VL53L1_ERROR_NONE) {
+ VL53L1_print_spad_rate_data(
+ pspad_rate_data,
+ "run_spad_rate_map():",
+ VL53L1_TRACE_MODULE_SPAD_RATE_MAP);
+ VL53L1_print_spad_rate_map(
+ pspad_rate_data,
+ "run_spad_rate_map():",
+ VL53L1_TRACE_MODULE_SPAD_RATE_MAP);
+ }
+#endif
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_run_device_test(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceTestMode device_test_mode)
+{
+ /*
+ * Runs the selected Device Test Mode
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint8_t comms_buffer[2];
+ uint8_t gpio_hv_mux__ctrl = 0;
+
+ LOG_FUNCTION_START("");
+
+ /*
+ * Get current interrupt config
+ */
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status =
+ VL53L1_RdByte(
+ Dev,
+ VL53L1_GPIO_HV_MUX__CTRL,
+ &gpio_hv_mux__ctrl);
+
+ if (status == VL53L1_ERROR_NONE)
+ pdev->stat_cfg.gpio_hv_mux__ctrl = gpio_hv_mux__ctrl;
+
+ /*
+ * Trigger the test
+ */
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_start_test(
+ Dev,
+ device_test_mode);
+
+ /*
+ * Wait for test completion
+ */
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_wait_for_test_completion(Dev);
+
+ /*
+ * Read range and report status
+ */
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_ReadMulti(
+ Dev,
+ VL53L1_RESULT__RANGE_STATUS,
+ comms_buffer,
+ 2);
+
+ if (status == VL53L1_ERROR_NONE) {
+ pdev->sys_results.result__range_status = comms_buffer[0];
+ pdev->sys_results.result__report_status = comms_buffer[1];
+ }
+
+ /* mask range status bits */
+
+ pdev->sys_results.result__range_status &=
+ VL53L1_RANGE_STATUS__RANGE_STATUS_MASK;
+
+ if (status == VL53L1_ERROR_NONE) {
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ " Device Test Complete:\n\t%-32s = %3u\n\t%-32s = %3u\n",
+ "result__range_status",
+ pdev->sys_results.result__range_status,
+ "result__report_status",
+ pdev->sys_results.result__report_status);
+
+ /*
+ * Clear interrupt
+ */
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_clear_interrupt(Dev);
+ }
+
+ /*
+ * Clear test mode register
+ * - required so that next test command will trigger
+ * internal MCU interrupt
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_start_test(
+ Dev,
+ 0x00);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
diff --git a/src/lib/vl53l1/core/src/vl53l1_api_core.c b/src/lib/vl53l1/core/src/vl53l1_api_core.c
new file mode 100644
index 0000000000..afc1ae0083
--- /dev/null
+++ b/src/lib/vl53l1/core/src/vl53l1_api_core.c
@@ -0,0 +1,3510 @@
+/*******************************************************************************
+ Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ ******************************************************************************/
+
+/**
+ * @file vl53l1_api_core.c
+ *
+ * @brief EwokPlus25 low level API function definition
+ */
+
+
+#include "vl53l1_ll_def.h"
+#include "vl53l1_ll_device.h"
+#include "vl53l1_platform.h"
+#include "vl53l1_register_map.h"
+#include "vl53l1_register_settings.h"
+#include "vl53l1_register_funcs.h"
+#include "vl53l1_nvm_map.h"
+#include "vl53l1_core.h"
+#include "vl53l1_wait.h"
+#include "vl53l1_api_preset_modes.h"
+#include "vl53l1_silicon_core.h"
+#include "vl53l1_api_core.h"
+#include "vl53l1_tuning_parm_defaults.h"
+
+#ifdef VL53L1_LOG_ENABLE
+#include "vl53l1_api_debug.h"
+#endif
+
+#define LOG_FUNCTION_START(fmt, ...) \
+ _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_CORE, fmt, ##__VA_ARGS__)
+#define LOG_FUNCTION_END(status, ...) \
+ _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_CORE, status, ##__VA_ARGS__)
+#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
+ _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_CORE, status, \
+ fmt, ##__VA_ARGS__)
+
+#define trace_print(level, ...) \
+ _LOG_TRACE_PRINT(VL53L1_TRACE_MODULE_CORE, \
+ level, VL53L1_TRACE_FUNCTION_NONE, ##__VA_ARGS__)
+
+#define VL53L1_MAX_I2C_XFER_SIZE 256
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_get_version(
+ VL53L1_DEV Dev,
+ VL53L1_ll_version_t *pdata)
+{
+ /*
+ * respond with the #define values from version.h
+ * using memcpy(dst, src, size in bytes)
+ */
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ VL53L1_init_version(Dev);
+
+ memcpy(pdata, &(pdev->version), sizeof(VL53L1_ll_version_t));
+
+ return VL53L1_ERROR_NONE;
+}
+
+VL53L1_Error VL53L1_get_device_firmware_version(
+ VL53L1_DEV Dev,
+ uint16_t *pfw_version)
+{
+ /*
+ * Read Firmware version from device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_RdWord(
+ Dev,
+ VL53L1_MCU_GENERAL_PURPOSE__GP_0,
+ pfw_version);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_data_init(
+ VL53L1_DEV Dev,
+ uint8_t read_p2p_data)
+{
+ /*
+ * Initialise pdev data structure
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ VL53L1_init_ll_driver_state(
+ Dev,
+ VL53L1_DEVICESTATE_UNKNOWN);
+
+ pdev->wait_method = VL53L1_WAIT_METHOD_BLOCKING;
+ pdev->preset_mode = VL53L1_DEVICEPRESETMODE_STANDARD_RANGING;
+ pdev->measurement_mode = VL53L1_DEVICEMEASUREMENTMODE_STOP;
+
+ pdev->offset_calibration_mode =
+ VL53L1_OFFSETCALIBRATIONMODE__MM1_MM2__STANDARD;
+ pdev->offset_correction_mode =
+ VL53L1_OFFSETCORRECTIONMODE__MM1_MM2_OFFSETS;
+
+ pdev->phasecal_config_timeout_us = 1000;
+ pdev->mm_config_timeout_us = 2000;
+ pdev->range_config_timeout_us = 13000;
+ pdev->inter_measurement_period_ms = 100;
+ pdev->dss_config__target_total_rate_mcps = 0x0A00;
+ pdev->debug_mode = 0x00;
+
+ /* initialise gain calibration values to tuning parameter values */
+
+ pdev->gain_cal.standard_ranging_gain_factor =
+ VL53L1_TUNINGPARM_LITE_RANGING_GAIN_FACTOR_DEFAULT;
+
+ /*
+ * Initialise version structure
+ */
+ VL53L1_init_version(Dev);
+
+ /*
+ * For C-API one time initialization only read device G02 registers
+ * containing data copied from NVM
+ *
+ * Contains the key NVM data e.g identification info fast oscillator
+ * freq, max trim and laser safety info
+ */
+
+ if (read_p2p_data > 0 && status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_read_p2p_data(Dev);
+
+ /* Initialise Ref SPAD Char configuration structure */
+#ifndef VL53L1_NOCALIB
+ status =
+ VL53L1_init_refspadchar_config_struct(
+ &(pdev->refspadchar));
+#endif
+
+ /* Initialise SPAD Self Check (SSC) configuration structure */
+#ifndef VL53L1_NOCALIB
+ status =
+ VL53L1_init_ssc_config_struct(
+ &(pdev->ssc_cfg));
+#endif
+
+ /* Initialise Private Xtalk configuration structure
+ * - Fill with customer NVM data to begin
+ */
+ status =
+ VL53L1_init_xtalk_config_struct(
+ &(pdev->customer),
+ &(pdev->xtalk_cfg));
+
+ /* Initialise Offset Calibration configuration structure
+ */
+#ifndef VL53L1_NOCALIB
+ status =
+ VL53L1_init_offset_cal_config_struct(
+ &(pdev->offsetcal_cfg));
+#endif
+
+ /* Initialise Tuning Parameter structure
+ * - Added as part of Patch_AddingTuningParmStorage_11821
+ */
+ status =
+ VL53L1_init_tuning_parm_storage_struct(
+ &(pdev->tuning_parms));
+
+ status = VL53L1_set_vhv_loopbound(Dev,
+ VL53L1_TUNINGPARM_VHV_LOOPBOUND_DEFAULT);
+
+ /*
+ * Initialise default settings - much happen *after*
+ * reading /setting of static_nvm_managed
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_set_preset_mode(
+ Dev,
+ pdev->preset_mode,
+ pdev->dss_config__target_total_rate_mcps, /* 9.7 format 20Mcps */
+ pdev->phasecal_config_timeout_us,
+ pdev->mm_config_timeout_us,
+ pdev->range_config_timeout_us,
+ pdev->inter_measurement_period_ms);
+
+ /* Initial Low Power Auto Mode data structures */
+ /* Added for Patch_LowPowerAutoMode */
+ VL53L1_low_power_auto_data_init(
+ Dev
+ );
+
+#ifdef VL53L1_LOG_ENABLE
+
+ /* Prints out the initial calibration data for debug */
+
+ VL53L1_print_static_nvm_managed(
+ &(pdev->stat_nvm),
+ "data_init():pdev->lldata.stat_nvm.",
+ VL53L1_TRACE_MODULE_DATA_INIT);
+
+ VL53L1_print_customer_nvm_managed(
+ &(pdev->customer),
+ "data_init():pdev->lldata.customer.",
+ VL53L1_TRACE_MODULE_DATA_INIT);
+
+ VL53L1_print_nvm_copy_data(
+ &(pdev->nvm_copy_data),
+ "data_init():pdev->lldata.nvm_copy_data.",
+ VL53L1_TRACE_MODULE_DATA_INIT);
+
+ VL53L1_print_additional_offset_cal_data(
+ &(pdev->add_off_cal_data),
+ "data_init():pdev->lldata.add_off_cal_data.",
+ VL53L1_TRACE_MODULE_DATA_INIT);
+
+ VL53L1_print_user_zone(
+ &(pdev->mm_roi),
+ "data_init():pdev->lldata.mm_roi.",
+ VL53L1_TRACE_MODULE_DATA_INIT);
+
+ VL53L1_print_optical_centre(
+ &(pdev->optical_centre),
+ "data_init():pdev->lldata.optical_centre.",
+ VL53L1_TRACE_MODULE_DATA_INIT);
+
+ VL53L1_print_cal_peak_rate_map(
+ &(pdev->cal_peak_rate_map),
+ "data_init():pdev->lldata.cal_peak_rate_map.",
+ VL53L1_TRACE_MODULE_DATA_INIT);
+
+#endif
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_read_p2p_data(
+ VL53L1_DEV Dev)
+{
+
+ /*
+ * For C-API one time initialization only reads device
+ * G02 registers containing data copied from NVM
+ *
+ * Contains the key NVM data e.g identification info
+ * fast oscillator freq, max trim and laser safety info
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_get_static_nvm_managed(
+ Dev,
+ &(pdev->stat_nvm));
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_get_customer_nvm_managed(
+ Dev,
+ &(pdev->customer));
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ status = VL53L1_get_nvm_copy_data(
+ Dev,
+ &(pdev->nvm_copy_data));
+
+ /* copy Return Good SPADs to buffer */
+ if (status == VL53L1_ERROR_NONE)
+ VL53L1_copy_rtn_good_spads_to_buffer(
+ &(pdev->nvm_copy_data),
+ &(pdev->rtn_good_spads[0]));
+ }
+
+ /*
+ * read slow osc calibration value
+ * counts per ms
+ */
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_RdWord(
+ Dev,
+ VL53L1_RESULT__OSC_CALIBRATE_VAL,
+ &(pdev->dbg_results.result__osc_calibrate_val));
+
+ /*
+ * Check if there a sensible value for osc_measured__fast_osc__frequency
+ */
+
+ if (pdev->stat_nvm.osc_measured__fast_osc__frequency < 0x1000) {
+ trace_print(
+ VL53L1_TRACE_LEVEL_WARNING,
+ "\nInvalid %s value (0x%04X) - forcing to 0x%04X\n\n",
+ "pdev->stat_nvm.osc_measured__fast_osc__frequency",
+ pdev->stat_nvm.osc_measured__fast_osc__frequency,
+ 0xBCCC);
+ pdev->stat_nvm.osc_measured__fast_osc__frequency = 0xBCCC;
+ }
+
+ /*
+ * Get MM ROI - contains optical centre as SPAD number
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_get_mode_mitigation_roi(
+ Dev,
+ &(pdev->mm_roi));
+
+ /* catch parts where the optical centre is
+ * no programmed in to the NVM
+ */
+
+ if (pdev->optical_centre.x_centre == 0 &&
+ pdev->optical_centre.y_centre == 0) {
+ pdev->optical_centre.x_centre =
+ pdev->mm_roi.x_centre << 4;
+ pdev->optical_centre.y_centre =
+ pdev->mm_roi.y_centre << 4;
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_software_reset(
+ VL53L1_DEV Dev)
+{
+ /**
+ * Sets and clears the software reset register VL53L1_SOFT_RESET.
+ * and waits for the firmware to boot
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* apply reset - note despite the name soft reset is active low! */
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_WrByte(
+ Dev,
+ VL53L1_SOFT_RESET,
+ 0x00);
+
+ /* wait for a while before releasing the reset */
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_WaitUs(
+ Dev,
+ VL53L1_SOFTWARE_RESET_DURATION_US);
+
+ /* release reset */
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WrByte(
+ Dev,
+ VL53L1_SOFT_RESET,
+ 0x01);
+
+ /* wait for firmware boot to complete */
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_wait_for_boot_completion(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_part_to_part_data(
+ VL53L1_DEV Dev,
+ VL53L1_calibration_data_t *pcal_data)
+{
+ /**
+ * Uses memcpy to copy input data to pdev->customer
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint32_t tempu32;
+
+ LOG_FUNCTION_START("");
+
+ if (pcal_data->struct_version !=
+ VL53L1_LL_CALIBRATION_DATA_STRUCT_VERSION) {
+ status = VL53L1_ERROR_INVALID_PARAMS;
+ }
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ /* memcpy(DEST, SRC, N) */
+ memcpy(
+ &(pdev->customer),
+ &(pcal_data->customer),
+ sizeof(VL53L1_customer_nvm_managed_t));
+
+ /* memcpy(DEST, SRC, N) */
+ memcpy(
+ &(pdev->add_off_cal_data),
+ &(pcal_data->add_off_cal_data),
+ sizeof(VL53L1_additional_offset_cal_data_t));
+
+ /* memcpy(DEST, SRC, N) */
+ memcpy(
+ &(pdev->gain_cal),
+ &(pcal_data->gain_cal),
+ sizeof(VL53L1_gain_calibration_data_t));
+
+ /* memcpy(DEST, SRC, N) */
+ memcpy(
+ &(pdev->cal_peak_rate_map),
+ &(pcal_data->cal_peak_rate_map),
+ sizeof(VL53L1_cal_peak_rate_map_t));
+
+ /*
+ * Update internal xtalk data structures
+ */
+
+ pdev->xtalk_cfg.algo__crosstalk_compensation_plane_offset_kcps =
+ pdev->customer.algo__crosstalk_compensation_plane_offset_kcps;
+ pdev->xtalk_cfg.algo__crosstalk_compensation_x_plane_gradient_kcps =
+ pdev->customer.algo__crosstalk_compensation_x_plane_gradient_kcps;
+ pdev->xtalk_cfg.algo__crosstalk_compensation_y_plane_gradient_kcps =
+ pdev->customer.algo__crosstalk_compensation_y_plane_gradient_kcps;
+
+ /* Assess and update customer packet xtalk parameters */
+
+ if (pdev->xtalk_cfg.global_crosstalk_compensation_enable == 0x00) {
+ pdev->customer.algo__crosstalk_compensation_plane_offset_kcps =
+ 0x00;
+ pdev->customer.algo__crosstalk_compensation_x_plane_gradient_kcps =
+ 0x00;
+ pdev->customer.algo__crosstalk_compensation_y_plane_gradient_kcps =
+ 0x00;
+ } else {
+ tempu32 = VL53L1_calc_crosstalk_plane_offset_with_margin(
+ pdev->xtalk_cfg.algo__crosstalk_compensation_plane_offset_kcps,
+ pdev->xtalk_cfg.lite_mode_crosstalk_margin_kcps);
+ if (tempu32 > 0xFFFF) { /* clip to 16 bits */
+ tempu32 = 0xFFFF;
+ }
+ pdev->customer.algo__crosstalk_compensation_plane_offset_kcps =
+ (uint16_t)tempu32;
+ }
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_get_part_to_part_data(
+ VL53L1_DEV Dev,
+ VL53L1_calibration_data_t *pcal_data)
+{
+ /**
+ * Uses memcpy to copy pdev->customer to output data
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ pcal_data->struct_version =
+ VL53L1_LL_CALIBRATION_DATA_STRUCT_VERSION;
+
+ /* memcpy(DEST, SRC, N) */
+ memcpy(
+ &(pcal_data->customer),
+ &(pdev->customer),
+ sizeof(VL53L1_customer_nvm_managed_t));
+
+ /* Overwrite Struct with xtalk config parameters */
+ /* - customer struct versions are not golden copy */
+
+ if (pdev->xtalk_cfg.algo__crosstalk_compensation_plane_offset_kcps > 0xFFFF) {
+ pcal_data->customer.algo__crosstalk_compensation_plane_offset_kcps =
+ 0xFFFF;
+ } else {
+ pcal_data->customer.algo__crosstalk_compensation_plane_offset_kcps =
+ (uint16_t)pdev->xtalk_cfg.algo__crosstalk_compensation_plane_offset_kcps;
+ }
+ pcal_data->customer.algo__crosstalk_compensation_x_plane_gradient_kcps =
+ pdev->xtalk_cfg.algo__crosstalk_compensation_x_plane_gradient_kcps;
+ pcal_data->customer.algo__crosstalk_compensation_y_plane_gradient_kcps =
+ pdev->xtalk_cfg.algo__crosstalk_compensation_y_plane_gradient_kcps;
+
+ /* memcpy(DEST, SRC, N) */
+ memcpy(
+ &(pcal_data->add_off_cal_data),
+ &(pdev->add_off_cal_data),
+ sizeof(VL53L1_additional_offset_cal_data_t));
+
+ /* memcpy(DEST, SRC, N) */
+ memcpy(
+ &(pcal_data->optical_centre),
+ &(pdev->optical_centre),
+ sizeof(VL53L1_optical_centre_t));
+
+ /* memcpy(DEST, SRC, N) */
+ memcpy(
+ &(pcal_data->gain_cal),
+ &(pdev->gain_cal),
+ sizeof(VL53L1_gain_calibration_data_t));
+
+ /* memcpy(DEST, SRC, N) */
+ memcpy(
+ &(pcal_data->cal_peak_rate_map),
+ &(pdev->cal_peak_rate_map),
+ sizeof(VL53L1_cal_peak_rate_map_t));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_inter_measurement_period_ms(
+ VL53L1_DEV Dev,
+ uint32_t inter_measurement_period_ms)
+{
+ /**
+ * Convenience function for setting the inter measurement period
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ if (pdev->dbg_results.result__osc_calibrate_val == 0)
+ status = VL53L1_ERROR_DIVISION_BY_ZERO;
+
+ if (status == VL53L1_ERROR_NONE) {
+ pdev->inter_measurement_period_ms = inter_measurement_period_ms;
+ pdev->tim_cfg.system__intermeasurement_period = \
+ inter_measurement_period_ms *
+ (uint32_t)pdev->dbg_results.result__osc_calibrate_val;
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_get_inter_measurement_period_ms(
+ VL53L1_DEV Dev,
+ uint32_t *pinter_measurement_period_ms)
+{
+ /**
+ * Convenience function for getting the inter measurement period
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ if (pdev->dbg_results.result__osc_calibrate_val == 0)
+ status = VL53L1_ERROR_DIVISION_BY_ZERO;
+
+ if (status == VL53L1_ERROR_NONE)
+ *pinter_measurement_period_ms = \
+ pdev->tim_cfg.system__intermeasurement_period /
+ (uint32_t)pdev->dbg_results.result__osc_calibrate_val;
+
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_timeouts_us(
+ VL53L1_DEV Dev,
+ uint32_t phasecal_config_timeout_us,
+ uint32_t mm_config_timeout_us,
+ uint32_t range_config_timeout_us)
+{
+ /**
+ * Convenience function for setting the MM and range
+ * timeouts
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ if (pdev->stat_nvm.osc_measured__fast_osc__frequency == 0)
+ status = VL53L1_ERROR_DIVISION_BY_ZERO;
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ pdev->phasecal_config_timeout_us = phasecal_config_timeout_us;
+ pdev->mm_config_timeout_us = mm_config_timeout_us;
+ pdev->range_config_timeout_us = range_config_timeout_us;
+
+ status =
+ VL53L1_calc_timeout_register_values(
+ phasecal_config_timeout_us,
+ mm_config_timeout_us,
+ range_config_timeout_us,
+ pdev->stat_nvm.osc_measured__fast_osc__frequency,
+ &(pdev->gen_cfg),
+ &(pdev->tim_cfg));
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_get_timeouts_us(
+ VL53L1_DEV Dev,
+ uint32_t *pphasecal_config_timeout_us,
+ uint32_t *pmm_config_timeout_us,
+ uint32_t *prange_config_timeout_us)
+{
+ /**
+ * Convenience function for getting the MM and range
+ * timeouts
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint32_t macro_period_us = 0;
+ uint16_t timeout_encoded = 0;
+
+ LOG_FUNCTION_START("");
+
+ if (pdev->stat_nvm.osc_measured__fast_osc__frequency == 0)
+ status = VL53L1_ERROR_DIVISION_BY_ZERO;
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ /* Update Macro Period for Range A VCSEL Period */
+ macro_period_us =
+ VL53L1_calc_macro_period_us(
+ pdev->stat_nvm.osc_measured__fast_osc__frequency,
+ pdev->tim_cfg.range_config__vcsel_period_a);
+
+ /* Get Phase Cal Timing A timeout */
+
+ *pphasecal_config_timeout_us =
+ VL53L1_calc_timeout_us(
+ (uint32_t)pdev->gen_cfg.phasecal_config__timeout_macrop,
+ macro_period_us);
+
+ /* Get MM Timing A timeout */
+
+ timeout_encoded =
+ (uint16_t)pdev->tim_cfg.mm_config__timeout_macrop_a_hi;
+ timeout_encoded = (timeout_encoded << 8) +
+ (uint16_t)pdev->tim_cfg.mm_config__timeout_macrop_a_lo;
+
+ *pmm_config_timeout_us =
+ VL53L1_calc_decoded_timeout_us(
+ timeout_encoded,
+ macro_period_us);
+
+ /* Get Range Timing A timeout */
+
+ timeout_encoded =
+ (uint16_t)pdev->tim_cfg.range_config__timeout_macrop_a_hi;
+ timeout_encoded = (timeout_encoded << 8) +
+ (uint16_t)pdev->tim_cfg.range_config__timeout_macrop_a_lo;
+
+ *prange_config_timeout_us =
+ VL53L1_calc_decoded_timeout_us(
+ timeout_encoded,
+ macro_period_us);
+
+ pdev->phasecal_config_timeout_us = *pphasecal_config_timeout_us;
+ pdev->mm_config_timeout_us = *pmm_config_timeout_us;
+ pdev->range_config_timeout_us = *prange_config_timeout_us;
+
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_calibration_repeat_period(
+ VL53L1_DEV Dev,
+ uint16_t cal_config__repeat_period)
+{
+ /**
+ * Convenience function for setting calibration repeat period
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ pdev->gen_cfg.cal_config__repeat_rate = cal_config__repeat_period;
+
+ return status;
+
+}
+
+
+VL53L1_Error VL53L1_get_calibration_repeat_period(
+ VL53L1_DEV Dev,
+ uint16_t *pcal_config__repeat_period)
+{
+ /**
+ * Convenience function for getting calibration repeat period
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ *pcal_config__repeat_period = pdev->gen_cfg.cal_config__repeat_rate;
+
+ return status;
+
+}
+
+
+VL53L1_Error VL53L1_set_sequence_config_bit(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceSequenceConfig bit_id,
+ uint8_t value)
+{
+ /**
+ * Convenience function for setting sequence
+ * config enable bits
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint8_t bit_mask = 0x01;
+ uint8_t clr_mask = 0xFF - bit_mask;
+ uint8_t bit_value = value & bit_mask;
+
+ if (bit_id <= VL53L1_DEVICESEQUENCECONFIG_RANGE) {
+
+ if (bit_id > 0) {
+ bit_mask = 0x01 << bit_id;
+ bit_value = bit_value << bit_id;
+ clr_mask = 0xFF - bit_mask;
+ }
+
+ pdev->dyn_cfg.system__sequence_config = \
+ (pdev->dyn_cfg.system__sequence_config & clr_mask) | \
+ bit_value;
+
+ } else {
+ status = VL53L1_ERROR_INVALID_PARAMS;
+ }
+
+ return status;
+
+}
+
+
+VL53L1_Error VL53L1_get_sequence_config_bit(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceSequenceConfig bit_id,
+ uint8_t *pvalue)
+{
+ /**
+ * Convenience function for getting sequence
+ * config enable bits
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint8_t bit_mask = 0x01;
+
+ if (bit_id <= VL53L1_DEVICESEQUENCECONFIG_RANGE) {
+
+ if (bit_id > 0) {
+ bit_mask = 0x01 << bit_id;
+ }
+
+ *pvalue =
+ pdev->dyn_cfg.system__sequence_config & bit_mask;
+
+ if (bit_id > 0) {
+ *pvalue = *pvalue >> bit_id;
+ }
+
+ } else {
+ status = VL53L1_ERROR_INVALID_PARAMS;
+ }
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_interrupt_polarity(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceInterruptPolarity interrupt_polarity)
+{
+ /**
+ * Convenience function for setting interrupt polarity
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ pdev->stat_cfg.gpio_hv_mux__ctrl = \
+ (pdev->stat_cfg.gpio_hv_mux__ctrl & \
+ VL53L1_DEVICEINTERRUPTPOLARITY_CLEAR_MASK) | \
+ (interrupt_polarity & \
+ VL53L1_DEVICEINTERRUPTPOLARITY_BIT_MASK);
+
+ return status;
+
+}
+
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_set_refspadchar_config_struct(
+ VL53L1_DEV Dev,
+ VL53L1_refspadchar_config_t *pdata)
+{
+ /*
+ * Allows user config of Ref SPAD Char data structure
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ pdev->refspadchar.device_test_mode = pdata->device_test_mode;
+ pdev->refspadchar.vcsel_period = pdata->vcsel_period;
+ pdev->refspadchar.timeout_us = pdata->timeout_us;
+ pdev->refspadchar.target_count_rate_mcps =
+ pdata->target_count_rate_mcps;
+ pdev->refspadchar.min_count_rate_limit_mcps =
+ pdata->min_count_rate_limit_mcps;
+ pdev->refspadchar.max_count_rate_limit_mcps =
+ pdata->max_count_rate_limit_mcps;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_get_refspadchar_config_struct(
+ VL53L1_DEV Dev,
+ VL53L1_refspadchar_config_t *pdata)
+{
+ /*
+ * Allows user config of Ref SPAD Char data structure
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ pdata->device_test_mode = pdev->refspadchar.device_test_mode;
+ pdata->vcsel_period = pdev->refspadchar.vcsel_period;
+ pdata->timeout_us = pdev->refspadchar.timeout_us;
+ pdata->target_count_rate_mcps = pdev->refspadchar.target_count_rate_mcps;
+ pdata->min_count_rate_limit_mcps =
+ pdev->refspadchar.min_count_rate_limit_mcps;
+ pdata->max_count_rate_limit_mcps =
+ pdev->refspadchar.max_count_rate_limit_mcps;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_set_range_ignore_threshold(
+ VL53L1_DEV Dev,
+ uint8_t range_ignore_thresh_mult,
+ uint16_t range_ignore_threshold_mcps)
+{
+ /**
+ * Convenience function for setting Range Ignore Threshold
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ pdev->xtalk_cfg.crosstalk_range_ignore_threshold_rate_mcps =
+ range_ignore_threshold_mcps;
+
+ pdev->xtalk_cfg.crosstalk_range_ignore_threshold_mult =
+ range_ignore_thresh_mult;
+
+ return status;
+
+}
+
+VL53L1_Error VL53L1_get_range_ignore_threshold(
+ VL53L1_DEV Dev,
+ uint8_t *prange_ignore_thresh_mult,
+ uint16_t *prange_ignore_threshold_mcps_internal,
+ uint16_t *prange_ignore_threshold_mcps_current)
+{
+ /**
+ * Convenience function for retrieving Range Ignore Threshold
+ * - Returns both the calculated internal value
+ * - and the value currently applied to device reg settings
+ *
+ * Values both in fixed point 3.13 Mcps per spad
+ *
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ *prange_ignore_thresh_mult =
+ pdev->xtalk_cfg.crosstalk_range_ignore_threshold_mult;
+
+ *prange_ignore_threshold_mcps_current =
+ pdev->stat_cfg.algo__range_ignore_threshold_mcps;
+
+ *prange_ignore_threshold_mcps_internal =
+ pdev->xtalk_cfg.crosstalk_range_ignore_threshold_rate_mcps;
+
+ return status;
+
+}
+
+
+
+VL53L1_Error VL53L1_get_interrupt_polarity(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceInterruptPolarity *pinterrupt_polarity)
+{
+ /**
+ * Convenience function for getting interrupt polarity
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ *pinterrupt_polarity = \
+ pdev->stat_cfg.gpio_hv_mux__ctrl & \
+ VL53L1_DEVICEINTERRUPTPOLARITY_BIT_MASK ;
+
+ return status;
+
+}
+
+
+VL53L1_Error VL53L1_set_user_zone(
+ VL53L1_DEV Dev,
+ VL53L1_user_zone_t *puser_zone)
+{
+ /**
+ * Convenience function for setting the user ROI
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ /* convert (row,col) location into a SPAD number */
+ VL53L1_encode_row_col(
+ puser_zone->y_centre,
+ puser_zone->x_centre,
+ &(pdev->dyn_cfg.roi_config__user_roi_centre_spad));
+
+ /* merge x and y sizes */
+ VL53L1_encode_zone_size(
+ puser_zone->width,
+ puser_zone->height,
+ &(pdev->dyn_cfg.roi_config__user_roi_requested_global_xy_size));
+
+ /* need to add checks to ensure ROI is within array */
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_get_user_zone(
+ VL53L1_DEV Dev,
+ VL53L1_user_zone_t *puser_zone)
+{
+ /**
+ * Convenience function for getting the user ROI
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ /* convert SPAD number into (row,col) location*/
+ VL53L1_decode_row_col(
+ pdev->dyn_cfg.roi_config__user_roi_centre_spad,
+ &(puser_zone->y_centre),
+ &(puser_zone->x_centre));
+
+ /* extract x and y sizes */
+ VL53L1_decode_zone_size(
+ pdev->dyn_cfg.roi_config__user_roi_requested_global_xy_size,
+ &(puser_zone->width),
+ &(puser_zone->height));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+
+VL53L1_Error VL53L1_get_mode_mitigation_roi(
+ VL53L1_DEV Dev,
+ VL53L1_user_zone_t *pmm_roi)
+{
+ /**
+ * Convenience function for getting the mode mitigation ROI
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint8_t x = 0;
+ uint8_t y = 0;
+ uint8_t xy_size = 0;
+
+ LOG_FUNCTION_START("");
+
+ /* convert SPAD number into (row,col) location */
+ VL53L1_decode_row_col(
+ pdev->nvm_copy_data.roi_config__mode_roi_centre_spad,
+ &y,
+ &x);
+
+ pmm_roi->x_centre = x;
+ pmm_roi->y_centre = y;
+
+ /* extract x and y sizes
+ *
+ * Important: the sense of the device width and height is swapped
+ * versus the API sense
+ *
+ * MS Nibble = height
+ * LS Nibble = width
+ */
+ xy_size = pdev->nvm_copy_data.roi_config__mode_roi_xy_size;
+
+ pmm_roi->height = xy_size >> 4;
+ pmm_roi->width = xy_size & 0x0F;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+VL53L1_Error VL53L1_get_preset_mode_timing_cfg(
+ VL53L1_DEV Dev,
+ VL53L1_DevicePresetModes device_preset_mode,
+ uint16_t *pdss_config__target_total_rate_mcps,
+ uint32_t *pphasecal_config_timeout_us,
+ uint32_t *pmm_config_timeout_us,
+ uint32_t *prange_config_timeout_us)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+
+ switch (device_preset_mode) {
+
+ case VL53L1_DEVICEPRESETMODE_STANDARD_RANGING:
+ case VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_SHORT_RANGE:
+ case VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_LONG_RANGE:
+ case VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM1_CAL:
+ case VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM2_CAL:
+ case VL53L1_DEVICEPRESETMODE_OLT:
+ *pdss_config__target_total_rate_mcps =
+ pdev->tuning_parms.tp_dss_target_lite_mcps;
+ *pphasecal_config_timeout_us =
+ pdev->tuning_parms.tp_phasecal_timeout_lite_us;
+ *pmm_config_timeout_us =
+ pdev->tuning_parms.tp_mm_timeout_lite_us;
+ *prange_config_timeout_us =
+ pdev->tuning_parms.tp_range_timeout_lite_us;
+ break;
+
+ case VL53L1_DEVICEPRESETMODE_TIMED_RANGING:
+ case VL53L1_DEVICEPRESETMODE_TIMED_RANGING_SHORT_RANGE:
+ case VL53L1_DEVICEPRESETMODE_TIMED_RANGING_LONG_RANGE:
+ case VL53L1_DEVICEPRESETMODE_SINGLESHOT_RANGING:
+ *pdss_config__target_total_rate_mcps =
+ pdev->tuning_parms.tp_dss_target_timed_mcps;
+ *pphasecal_config_timeout_us =
+ pdev->tuning_parms.tp_phasecal_timeout_timed_us;
+ *pmm_config_timeout_us =
+ pdev->tuning_parms.tp_mm_timeout_timed_us;
+ *prange_config_timeout_us =
+ pdev->tuning_parms.tp_range_timeout_timed_us;
+ break;
+
+ case VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_SHORT_RANGE:
+ case VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_MEDIUM_RANGE:
+ case VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_LONG_RANGE:
+ *pdss_config__target_total_rate_mcps =
+ pdev->tuning_parms.tp_dss_target_timed_mcps;
+ *pphasecal_config_timeout_us =
+ pdev->tuning_parms.tp_phasecal_timeout_timed_us;
+ *pmm_config_timeout_us =
+ pdev->tuning_parms.tp_mm_timeout_lpa_us;
+ *prange_config_timeout_us =
+ pdev->tuning_parms.tp_range_timeout_lpa_us;
+ break;
+
+ default:
+ status = VL53L1_ERROR_INVALID_PARAMS;
+ break;
+
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_preset_mode(
+ VL53L1_DEV Dev,
+ VL53L1_DevicePresetModes device_preset_mode,
+ uint16_t dss_config__target_total_rate_mcps,
+ uint32_t phasecal_config_timeout_us,
+ uint32_t mm_config_timeout_us,
+ uint32_t range_config_timeout_us,
+ uint32_t inter_measurement_period_ms)
+{
+ /**
+ * Initializes static and dynamic data structures for
+ * the provided preset mode
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ VL53L1_static_config_t *pstatic = &(pdev->stat_cfg);
+ VL53L1_general_config_t *pgeneral = &(pdev->gen_cfg);
+ VL53L1_timing_config_t *ptiming = &(pdev->tim_cfg);
+ VL53L1_dynamic_config_t *pdynamic = &(pdev->dyn_cfg);
+ VL53L1_system_control_t *psystem = &(pdev->sys_ctrl);
+ VL53L1_tuning_parm_storage_t *ptuning_parms = &(pdev->tuning_parms);
+ VL53L1_low_power_auto_data_t *plpadata =
+ &(pdev->low_power_auto_data);
+
+ LOG_FUNCTION_START("");
+
+ /* save input settings */
+ pdev->preset_mode = device_preset_mode;
+ pdev->mm_config_timeout_us = mm_config_timeout_us;
+ pdev->range_config_timeout_us = range_config_timeout_us;
+ pdev->inter_measurement_period_ms = inter_measurement_period_ms;
+
+ /* Reset LL Driver state variables */
+
+ VL53L1_init_ll_driver_state(
+ Dev,
+ VL53L1_DEVICESTATE_SW_STANDBY);
+
+ /* apply selected preset */
+
+ switch (device_preset_mode) {
+
+ case VL53L1_DEVICEPRESETMODE_STANDARD_RANGING:
+ status = VL53L1_preset_mode_standard_ranging(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+ break;
+
+ case VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_SHORT_RANGE:
+ status = VL53L1_preset_mode_standard_ranging_short_range(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+ break;
+
+ case VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_LONG_RANGE:
+ status = VL53L1_preset_mode_standard_ranging_long_range(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+ break;
+
+#ifndef VL53L1_NOCALIB
+ case VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM1_CAL:
+ status = VL53L1_preset_mode_standard_ranging_mm1_cal(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+ break;
+
+ case VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM2_CAL:
+ status = VL53L1_preset_mode_standard_ranging_mm2_cal(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+ break;
+#endif
+
+ case VL53L1_DEVICEPRESETMODE_TIMED_RANGING:
+ status = VL53L1_preset_mode_timed_ranging(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+ break;
+
+ case VL53L1_DEVICEPRESETMODE_TIMED_RANGING_SHORT_RANGE:
+ status = VL53L1_preset_mode_timed_ranging_short_range(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+ break;
+
+ case VL53L1_DEVICEPRESETMODE_TIMED_RANGING_LONG_RANGE:
+ status = VL53L1_preset_mode_timed_ranging_long_range(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+ break;
+
+ case VL53L1_DEVICEPRESETMODE_OLT:
+ status = VL53L1_preset_mode_olt(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+ break;
+
+ case VL53L1_DEVICEPRESETMODE_SINGLESHOT_RANGING:
+ status = VL53L1_preset_mode_singleshot_ranging(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+ break;
+
+ case VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_SHORT_RANGE:
+ status = VL53L1_preset_mode_low_power_auto_short_ranging(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms,
+ plpadata);
+ break;
+
+ case VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_MEDIUM_RANGE:
+ status = VL53L1_preset_mode_low_power_auto_ranging(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms,
+ plpadata);
+ break;
+
+ case VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_LONG_RANGE:
+ status = VL53L1_preset_mode_low_power_auto_long_ranging(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms,
+ plpadata);
+ break;
+
+ default:
+ status = VL53L1_ERROR_INVALID_PARAMS;
+ break;
+
+ }
+
+ /* update DSS target */
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ pstatic->dss_config__target_total_rate_mcps =
+ dss_config__target_total_rate_mcps;
+ pdev->dss_config__target_total_rate_mcps =
+ dss_config__target_total_rate_mcps;
+
+ }
+
+ /*
+ * Update the register timeout values based on input
+ * real time values and preset mode VCSEL periods
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_set_timeouts_us(
+ Dev,
+ phasecal_config_timeout_us,
+ mm_config_timeout_us,
+ range_config_timeout_us);
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_set_inter_measurement_period_ms(
+ Dev,
+ inter_measurement_period_ms);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_enable_xtalk_compensation(
+ VL53L1_DEV Dev)
+{
+ /**
+ * Currently a very simple function to copy
+ * private xtalk parms into customer section and apply to device
+ *
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint32_t tempu32;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ /* Fill Public customer NVM data with Xtalk parms */
+ tempu32 = VL53L1_calc_crosstalk_plane_offset_with_margin(
+ pdev->xtalk_cfg.algo__crosstalk_compensation_plane_offset_kcps,
+ pdev->xtalk_cfg.lite_mode_crosstalk_margin_kcps);
+ if (tempu32 > 0xFFFF) {
+ tempu32 = 0xFFFF;
+ }
+ pdev->customer.algo__crosstalk_compensation_plane_offset_kcps =
+ (uint16_t)tempu32;
+
+ pdev->customer.algo__crosstalk_compensation_x_plane_gradient_kcps =
+ pdev->xtalk_cfg.algo__crosstalk_compensation_x_plane_gradient_kcps;
+
+ pdev->customer.algo__crosstalk_compensation_y_plane_gradient_kcps =
+ pdev->xtalk_cfg.algo__crosstalk_compensation_y_plane_gradient_kcps;
+
+ /* Enable Xtalk compensation */
+ pdev->xtalk_cfg.global_crosstalk_compensation_enable = 0x01;
+
+ /* Update Range Ignore Threshold Xtalk Parameter */
+
+ if (status == VL53L1_ERROR_NONE) {
+ pdev->xtalk_cfg.crosstalk_range_ignore_threshold_rate_mcps =
+ VL53L1_calc_range_ignore_threshold(
+ pdev->xtalk_cfg.algo__crosstalk_compensation_plane_offset_kcps,
+ pdev->xtalk_cfg.algo__crosstalk_compensation_x_plane_gradient_kcps,
+ pdev->xtalk_cfg.algo__crosstalk_compensation_y_plane_gradient_kcps,
+ pdev->xtalk_cfg.crosstalk_range_ignore_threshold_mult);
+ }
+
+ /* Apply to device */
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status =
+ VL53L1_set_customer_nvm_managed(
+ Dev,
+ &(pdev->customer));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+
+}
+
+void VL53L1_get_xtalk_compensation_enable(
+ VL53L1_DEV Dev,
+ uint8_t *pcrosstalk_compensation_enable)
+{
+ /**
+ * Currently a very simple function to return
+ *
+ * - this flags whether xtalk compensation is enabled for all modes
+ * or not.
+ *
+ * #1 - Enabled
+ * #0 - Disabled
+ *
+ */
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ /* Extract Xtalk Compensation Enable Status*/
+
+ *pcrosstalk_compensation_enable =
+ pdev->xtalk_cfg.global_crosstalk_compensation_enable;
+
+}
+
+
+VL53L1_Error VL53L1_get_lite_xtalk_margin_kcps(
+ VL53L1_DEV Dev,
+ int16_t *pxtalk_margin)
+{
+
+ /*
+ * Gets the Xtalk Margin Factor in Kcps (fixed point 9.7)
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ *pxtalk_margin = pdev->xtalk_cfg.lite_mode_crosstalk_margin_kcps;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+
+}
+
+VL53L1_Error VL53L1_set_lite_xtalk_margin_kcps(
+ VL53L1_DEV Dev,
+ int16_t xtalk_margin)
+{
+
+ /*
+ * Sets the offset calibration mode
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ pdev->xtalk_cfg.lite_mode_crosstalk_margin_kcps = xtalk_margin;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_restore_xtalk_nvm_default(
+ VL53L1_DEV Dev)
+{
+
+ /*
+ * Returns xtalk rate values to defaults as extracted from device NVM
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ pdev->xtalk_cfg.algo__crosstalk_compensation_plane_offset_kcps =
+ pdev->xtalk_cfg.nvm_default__crosstalk_compensation_plane_offset_kcps;
+ pdev->xtalk_cfg.algo__crosstalk_compensation_x_plane_gradient_kcps =
+ pdev->xtalk_cfg.nvm_default__crosstalk_compensation_x_plane_gradient_kcps;
+ pdev->xtalk_cfg.algo__crosstalk_compensation_y_plane_gradient_kcps =
+ pdev->xtalk_cfg.nvm_default__crosstalk_compensation_y_plane_gradient_kcps;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+VL53L1_Error VL53L1_disable_xtalk_compensation(
+ VL53L1_DEV Dev)
+{
+ /**
+ * Currently a very simple function to clear
+ * customer xtalk parms and apply to device
+ *
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ /* Fill Public customer NVM data with Xtalk parms */
+ pdev->customer.algo__crosstalk_compensation_plane_offset_kcps =
+ 0x00;
+
+ pdev->customer.algo__crosstalk_compensation_x_plane_gradient_kcps =
+ 0x00;
+
+ pdev->customer.algo__crosstalk_compensation_y_plane_gradient_kcps =
+ 0x00;
+
+
+ /* Disable Global Xtalk comnpensation */
+ pdev->xtalk_cfg.global_crosstalk_compensation_enable = 0x00;
+
+ /* Update Range Ignore Threshold Xtalk Parameter */
+
+ if (status == VL53L1_ERROR_NONE) {
+ pdev->xtalk_cfg.crosstalk_range_ignore_threshold_rate_mcps =
+ 0x0000;
+ }
+
+ /* Apply to device */
+
+ if (status == VL53L1_ERROR_NONE) { /*lint !e774 always true*/
+ status =
+ VL53L1_set_customer_nvm_managed(
+ Dev,
+ &(pdev->customer));
+ }
+ LOG_FUNCTION_END(status);
+
+ return status;
+
+}
+
+VL53L1_Error VL53L1_get_lite_sigma_threshold(
+ VL53L1_DEV Dev,
+ uint16_t *plite_sigma)
+{
+
+ /*
+ * Gets the Sigma Threshold value for Lite Mode
+ *
+ * (fixed point 14.2)
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ *plite_sigma =
+ pdev->tim_cfg.range_config__sigma_thresh;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+
+}
+
+VL53L1_Error VL53L1_set_lite_sigma_threshold(
+ VL53L1_DEV Dev,
+ uint16_t lite_sigma)
+{
+
+ /*
+ * Sets the Sigma threshold value for Lite mode
+ *
+ * (fixed point 14.2)
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ pdev->tim_cfg.range_config__sigma_thresh = lite_sigma;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+
+}
+
+VL53L1_Error VL53L1_get_lite_min_count_rate(
+ VL53L1_DEV Dev,
+ uint16_t *plite_mincountrate)
+{
+
+ /*
+ * Gets the Min Count Rate value for Lite Mode
+ *
+ * (fixed point 9.7 Mcps)
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ *plite_mincountrate =
+ pdev->tim_cfg.range_config__min_count_rate_rtn_limit_mcps;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+
+}
+
+VL53L1_Error VL53L1_set_lite_min_count_rate(
+ VL53L1_DEV Dev,
+ uint16_t lite_mincountrate)
+{
+
+ /*
+ * Sets the Min COunt Rate value for Lite mode
+ *
+ * (fixed point 19.7Mcps)
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ pdev->tim_cfg.range_config__min_count_rate_rtn_limit_mcps =
+ lite_mincountrate;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+
+}
+
+VL53L1_Error VL53L1_get_vhv_loopbound(
+ VL53L1_DEV Dev,
+ uint8_t *pvhv_loopbound)
+{
+
+ /*
+ * Gets the VHV Loop bound parm
+ * - extracts only bits 7:2 from internal stat nvm parm
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ *pvhv_loopbound = pdev->stat_nvm.vhv_config__timeout_macrop_loop_bound / 4 ;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+
+}
+
+
+
+VL53L1_Error VL53L1_set_vhv_loopbound(
+ VL53L1_DEV Dev,
+ uint8_t vhv_loopbound)
+{
+
+ /*
+ * Sets the VHV Loop bound parm
+ * - sets only bits 7:2
+ * - bits 1:0 remain unchanged
+ * - ensure that any change here is followed by a
+ * init_and_start_range with full i2c packet
+ * configuration.
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ pdev->stat_nvm.vhv_config__timeout_macrop_loop_bound =
+ (pdev->stat_nvm.vhv_config__timeout_macrop_loop_bound & 0x03) +
+ (vhv_loopbound * 4);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+
+}
+
+
+
+VL53L1_Error VL53L1_get_vhv_config(
+ VL53L1_DEV Dev,
+ uint8_t *pvhv_init_en,
+ uint8_t *pvhv_init_value)
+{
+
+ /*
+ * Gets the VHV config init data
+ */
+
+ /*!<
+ info: \n
+ - msb = 7
+ - lsb = 0
+ - i2c_size = 1
+
+ fields: \n
+ - [7] = vhv0_init_enable
+ - [5:0] = vhv0_init_value
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ *pvhv_init_en = (pdev->stat_nvm.vhv_config__init & 0x80) >> 7;
+ *pvhv_init_value =
+ (pdev->stat_nvm.vhv_config__init & 0x7F);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+
+}
+
+
+
+VL53L1_Error VL53L1_set_vhv_config(
+ VL53L1_DEV Dev,
+ uint8_t vhv_init_en,
+ uint8_t vhv_init_value)
+{
+
+ /*
+ * Sets the VHV Config init
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ pdev->stat_nvm.vhv_config__init =
+ ((vhv_init_en & 0x01) << 7) +
+ (vhv_init_value & 0x7F);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+
+}
+
+
+
+VL53L1_Error VL53L1_init_and_start_range(
+ VL53L1_DEV Dev,
+ uint8_t measurement_mode,
+ VL53L1_DeviceConfigLevel device_config_level)
+{
+ /*
+ * Builds and sends a single I2C multiple byte transaction to
+ * initialize the device and start a range measurement.
+ *
+ * The level of initialization is controlled by the
+ * device_config_level input parameter
+ *
+ * system_control is always sent as the last byte of this
+ * register group (mode_start) either triggers the range
+ * or enables the next range
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint8_t buffer[VL53L1_MAX_I2C_XFER_SIZE];
+
+ VL53L1_static_nvm_managed_t *pstatic_nvm = &(pdev->stat_nvm);
+ VL53L1_customer_nvm_managed_t *pcustomer_nvm = &(pdev->customer);
+ VL53L1_static_config_t *pstatic = &(pdev->stat_cfg);
+ VL53L1_general_config_t *pgeneral = &(pdev->gen_cfg);
+ VL53L1_timing_config_t *ptiming = &(pdev->tim_cfg);
+ VL53L1_dynamic_config_t *pdynamic = &(pdev->dyn_cfg);
+ VL53L1_system_control_t *psystem = &(pdev->sys_ctrl);
+
+ VL53L1_ll_driver_state_t *pstate = &(pdev->ll_state);
+
+ uint8_t *pbuffer = &buffer[0];
+ uint16_t i = 0;
+ uint16_t i2c_index = 0;
+ uint16_t i2c_buffer_offset_bytes = 0;
+ uint16_t i2c_buffer_size_bytes = 0;
+
+ LOG_FUNCTION_START("");
+
+ /* save measurement mode */
+ pdev->measurement_mode = measurement_mode;
+
+ /* Merge measurement mode with mode_start */
+
+ psystem->system__mode_start =
+ (psystem->system__mode_start &
+ VL53L1_DEVICEMEASUREMENTMODE_STOP_MASK) |
+ measurement_mode;
+
+ /* copy in rit from xtalk config */
+
+ pdev->stat_cfg.algo__range_ignore_threshold_mcps =
+ pdev->xtalk_cfg.crosstalk_range_ignore_threshold_rate_mcps;
+
+ /* Start Patch_LowPowerAutoMode */
+
+ /* doing this ensures stop_range followed by a get_device_results does
+ * not mess up the counters */
+
+ if (pdev->low_power_auto_data.low_power_auto_range_count == 0xFF) {
+ pdev->low_power_auto_data.low_power_auto_range_count = 0x0;
+ }
+
+ /* For Presence. Override threshold config */
+ if ((pdev->low_power_auto_data.is_low_power_auto_mode == 1) &&
+ (pdev->low_power_auto_data.low_power_auto_range_count == 0)) {
+ /* save interrupt config */
+ pdev->low_power_auto_data.saved_interrupt_config =
+ pdev->gen_cfg.system__interrupt_config_gpio;
+ /* set intr_new_measure_ready */
+ pdev->gen_cfg.system__interrupt_config_gpio = 1 << 5;
+ /* check MM1/MM2 disabled? */
+ if ((pdev->dyn_cfg.system__sequence_config & (
+ VL53L1_SEQUENCE_MM1_EN | VL53L1_SEQUENCE_MM2_EN)) ==
+ 0x0) {
+ pdev->customer.algo__part_to_part_range_offset_mm =
+ pdev->customer.mm_config__outer_offset_mm * 4;
+ } else {
+ pdev->customer.algo__part_to_part_range_offset_mm = 0x0;
+ }
+
+ /* make sure config gets written out */
+ if (device_config_level <
+ VL53L1_DEVICECONFIGLEVEL_CUSTOMER_ONWARDS) {
+ device_config_level =
+ VL53L1_DEVICECONFIGLEVEL_CUSTOMER_ONWARDS;
+ }
+ }
+
+ if ((pdev->low_power_auto_data.is_low_power_auto_mode == 1) &&
+ (pdev->low_power_auto_data.low_power_auto_range_count == 1)) {
+ /* restore interrupt config */
+ pdev->gen_cfg.system__interrupt_config_gpio =
+ pdev->low_power_auto_data.saved_interrupt_config;
+
+ /* make sure config gets written out including VHV config */
+ device_config_level = VL53L1_DEVICECONFIGLEVEL_FULL;
+ }
+
+ /* End Patch_LowPowerAutoMode */
+
+ /*
+ * Determine Initial I2C index
+ */
+
+ switch (device_config_level) {
+ case VL53L1_DEVICECONFIGLEVEL_FULL:
+ i2c_index = VL53L1_STATIC_NVM_MANAGED_I2C_INDEX;
+ break;
+ case VL53L1_DEVICECONFIGLEVEL_CUSTOMER_ONWARDS:
+ i2c_index = VL53L1_CUSTOMER_NVM_MANAGED_I2C_INDEX;
+ break;
+ case VL53L1_DEVICECONFIGLEVEL_STATIC_ONWARDS:
+ i2c_index = VL53L1_STATIC_CONFIG_I2C_INDEX;
+ break;
+ case VL53L1_DEVICECONFIGLEVEL_GENERAL_ONWARDS:
+ i2c_index = VL53L1_GENERAL_CONFIG_I2C_INDEX;
+ break;
+ case VL53L1_DEVICECONFIGLEVEL_TIMING_ONWARDS:
+ i2c_index = VL53L1_TIMING_CONFIG_I2C_INDEX;
+ break;
+ case VL53L1_DEVICECONFIGLEVEL_DYNAMIC_ONWARDS:
+ i2c_index = VL53L1_DYNAMIC_CONFIG_I2C_INDEX;
+ break;
+ default:
+ i2c_index = VL53L1_SYSTEM_CONTROL_I2C_INDEX;
+ break;
+ }
+
+ /* I2C Buffer size */
+
+ i2c_buffer_size_bytes = \
+ (VL53L1_SYSTEM_CONTROL_I2C_INDEX +
+ VL53L1_SYSTEM_CONTROL_I2C_SIZE_BYTES) -
+ i2c_index;
+
+ /* Initialize buffer */
+
+ pbuffer = &buffer[0];
+ for (i = 0 ; i < i2c_buffer_size_bytes ; i++) {
+ *pbuffer++ = 0;
+ }
+
+ /* Build I2C buffer */
+
+ if (device_config_level >= VL53L1_DEVICECONFIGLEVEL_FULL &&
+ status == VL53L1_ERROR_NONE) {
+
+ i2c_buffer_offset_bytes = \
+ VL53L1_STATIC_NVM_MANAGED_I2C_INDEX - i2c_index;
+
+ status =
+ VL53L1_i2c_encode_static_nvm_managed(
+ pstatic_nvm,
+ VL53L1_STATIC_NVM_MANAGED_I2C_SIZE_BYTES,
+ &buffer[i2c_buffer_offset_bytes]);
+ }
+
+ if (device_config_level >= VL53L1_DEVICECONFIGLEVEL_CUSTOMER_ONWARDS &&
+ status == VL53L1_ERROR_NONE) {
+
+ i2c_buffer_offset_bytes = \
+ VL53L1_CUSTOMER_NVM_MANAGED_I2C_INDEX - i2c_index;
+
+ status =
+ VL53L1_i2c_encode_customer_nvm_managed(
+ pcustomer_nvm,
+ VL53L1_CUSTOMER_NVM_MANAGED_I2C_SIZE_BYTES,
+ &buffer[i2c_buffer_offset_bytes]);
+ }
+
+ if (device_config_level >= VL53L1_DEVICECONFIGLEVEL_STATIC_ONWARDS &&
+ status == VL53L1_ERROR_NONE) {
+
+ i2c_buffer_offset_bytes = \
+ VL53L1_STATIC_CONFIG_I2C_INDEX - i2c_index;
+
+ status =
+ VL53L1_i2c_encode_static_config(
+ pstatic,
+ VL53L1_STATIC_CONFIG_I2C_SIZE_BYTES,
+ &buffer[i2c_buffer_offset_bytes]);
+ }
+
+ if (device_config_level >= VL53L1_DEVICECONFIGLEVEL_GENERAL_ONWARDS &&
+ status == VL53L1_ERROR_NONE) {
+
+ i2c_buffer_offset_bytes =
+ VL53L1_GENERAL_CONFIG_I2C_INDEX - i2c_index;
+
+ status =
+ VL53L1_i2c_encode_general_config(
+ pgeneral,
+ VL53L1_GENERAL_CONFIG_I2C_SIZE_BYTES,
+ &buffer[i2c_buffer_offset_bytes]);
+ }
+
+ if (device_config_level >= VL53L1_DEVICECONFIGLEVEL_TIMING_ONWARDS &&
+ status == VL53L1_ERROR_NONE) {
+
+ i2c_buffer_offset_bytes = \
+ VL53L1_TIMING_CONFIG_I2C_INDEX - i2c_index;
+
+ status =
+ VL53L1_i2c_encode_timing_config(
+ ptiming,
+ VL53L1_TIMING_CONFIG_I2C_SIZE_BYTES,
+ &buffer[i2c_buffer_offset_bytes]);
+ }
+
+ if (device_config_level >= VL53L1_DEVICECONFIGLEVEL_DYNAMIC_ONWARDS &&
+ status == VL53L1_ERROR_NONE) {
+
+ i2c_buffer_offset_bytes = \
+ VL53L1_DYNAMIC_CONFIG_I2C_INDEX - i2c_index;
+
+ /* If in back to back mode, use GPH ID from cfg_state */
+ if ((psystem->system__mode_start &
+ VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK) ==
+ VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK) {
+ pdynamic->system__grouped_parameter_hold_0 = pstate->cfg_gph_id | 0x01;
+ pdynamic->system__grouped_parameter_hold_1 = pstate->cfg_gph_id | 0x01;
+ pdynamic->system__grouped_parameter_hold = pstate->cfg_gph_id;
+ }
+ status =
+ VL53L1_i2c_encode_dynamic_config(
+ pdynamic,
+ VL53L1_DYNAMIC_CONFIG_I2C_SIZE_BYTES,
+ &buffer[i2c_buffer_offset_bytes]);
+ }
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ i2c_buffer_offset_bytes = \
+ VL53L1_SYSTEM_CONTROL_I2C_INDEX - i2c_index;
+
+ status =
+ VL53L1_i2c_encode_system_control(
+ psystem,
+ VL53L1_SYSTEM_CONTROL_I2C_SIZE_BYTES,
+ &buffer[i2c_buffer_offset_bytes]);
+ }
+
+ /* Send I2C Buffer */
+
+ if (status == VL53L1_ERROR_NONE) {
+ status =
+ VL53L1_WriteMulti(
+ Dev,
+ i2c_index,
+ buffer,
+ (uint32_t)i2c_buffer_size_bytes);
+ }
+
+ /*
+ * Update LL Driver State
+ */
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_update_ll_driver_rd_state(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_update_ll_driver_cfg_state(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_stop_range(
+ VL53L1_DEV Dev)
+{
+ /*
+ * Stops any in process range using the ABORT command
+ * Also clears all of the measurement mode bits
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ /* Merge ABORT mode with mode_start */
+
+ pdev->sys_ctrl.system__mode_start =
+ (pdev->sys_ctrl.system__mode_start & VL53L1_DEVICEMEASUREMENTMODE_STOP_MASK) |
+ VL53L1_DEVICEMEASUREMENTMODE_ABORT;
+
+ status = VL53L1_set_system_control(
+ Dev,
+ &pdev->sys_ctrl);
+
+ /* Abort bit is auto clear so clear register group structure to match */
+ pdev->sys_ctrl.system__mode_start =
+ (pdev->sys_ctrl.system__mode_start & VL53L1_DEVICEMEASUREMENTMODE_STOP_MASK);
+
+ /* reset zone dynamic info */
+ VL53L1_init_ll_driver_state(
+ Dev,
+ VL53L1_DEVICESTATE_SW_STANDBY);
+
+ /* reset low power auto */
+ if (pdev->low_power_auto_data.is_low_power_auto_mode == 1)
+ VL53L1_low_power_auto_data_stop_range(Dev);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_get_measurement_results(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceResultsLevel device_results_level)
+{
+ /*
+ * Read via a single I2C multiple byte transaction all
+ * of the requested device measurement data results
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint8_t buffer[VL53L1_MAX_I2C_XFER_SIZE];
+
+ VL53L1_system_results_t *psystem_results = &(pdev->sys_results);
+ VL53L1_core_results_t *pcore_results = &(pdev->core_results);
+ VL53L1_debug_results_t *pdebug_results = &(pdev->dbg_results);
+
+ uint16_t i2c_index = VL53L1_SYSTEM_RESULTS_I2C_INDEX;
+ uint16_t i2c_buffer_offset_bytes = 0;
+ uint16_t i2c_buffer_size_bytes = 0;
+
+ LOG_FUNCTION_START("");
+
+ /* Determine multi byte read transaction size */
+
+ switch (device_results_level) {
+ case VL53L1_DEVICERESULTSLEVEL_FULL:
+ i2c_buffer_size_bytes =
+ (VL53L1_DEBUG_RESULTS_I2C_INDEX +
+ VL53L1_DEBUG_RESULTS_I2C_SIZE_BYTES) -
+ i2c_index;
+ break;
+ case VL53L1_DEVICERESULTSLEVEL_UPTO_CORE:
+ i2c_buffer_size_bytes =
+ (VL53L1_CORE_RESULTS_I2C_INDEX +
+ VL53L1_CORE_RESULTS_I2C_SIZE_BYTES) -
+ i2c_index;
+ break;
+ default:
+ i2c_buffer_size_bytes =
+ VL53L1_SYSTEM_RESULTS_I2C_SIZE_BYTES;
+ break;
+ }
+
+ /* Read Result Data */
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status =
+ VL53L1_ReadMulti(
+ Dev,
+ i2c_index,
+ buffer,
+ (uint32_t)i2c_buffer_size_bytes);
+
+ /* Decode I2C buffer */
+
+ if (device_results_level >= VL53L1_DEVICERESULTSLEVEL_FULL &&
+ status == VL53L1_ERROR_NONE) {
+
+ i2c_buffer_offset_bytes =
+ VL53L1_DEBUG_RESULTS_I2C_INDEX - i2c_index;
+
+ status =
+ VL53L1_i2c_decode_debug_results(
+ VL53L1_DEBUG_RESULTS_I2C_SIZE_BYTES,
+ &buffer[i2c_buffer_offset_bytes],
+ pdebug_results);
+ }
+
+ if (device_results_level >= VL53L1_DEVICERESULTSLEVEL_UPTO_CORE &&
+ status == VL53L1_ERROR_NONE) {
+
+ i2c_buffer_offset_bytes =
+ VL53L1_CORE_RESULTS_I2C_INDEX - i2c_index;
+
+ status =
+ VL53L1_i2c_decode_core_results(
+ VL53L1_CORE_RESULTS_I2C_SIZE_BYTES,
+ &buffer[i2c_buffer_offset_bytes],
+ pcore_results);
+ }
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ i2c_buffer_offset_bytes = 0;
+ status =
+ VL53L1_i2c_decode_system_results(
+ VL53L1_SYSTEM_RESULTS_I2C_SIZE_BYTES,
+ &buffer[i2c_buffer_offset_bytes],
+ psystem_results);
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_get_device_results(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceResultsLevel device_results_level,
+ VL53L1_range_results_t *prange_results)
+{
+ /*
+ * Wrapper function using the functions below
+ *
+ * VL53L1_get_measurement_results()
+ * VL53L1_init_and_start_range()
+ * VL53L1_copy_sys_and_core_results_to_range_results()
+ *
+ * The input measurement mode controls what happens next ...
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+ VL53L1_LLDriverResults_t *pres =
+ VL53L1DevStructGetLLResultsHandle(Dev);
+
+ VL53L1_range_results_t *presults = &(pres->range_results);
+
+ LOG_FUNCTION_START("");
+
+ /* Get device results */
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_get_measurement_results(
+ Dev,
+ device_results_level);
+
+ if (status == VL53L1_ERROR_NONE)
+ VL53L1_copy_sys_and_core_results_to_range_results(
+ (int32_t)pdev->gain_cal.standard_ranging_gain_factor,
+ &(pdev->sys_results),
+ &(pdev->core_results),
+ presults);
+
+ /* Start Patch_LowPowerAutoMode */
+ /* process results from first range of low power auto */
+ if (pdev->low_power_auto_data.is_low_power_auto_mode == 1) {
+ /* change to manual calibrations. Only needed on the
+ * first range out */
+ if ((status == VL53L1_ERROR_NONE) &&
+ (pdev->low_power_auto_data.low_power_auto_range_count == 0)) {
+ status = VL53L1_low_power_auto_setup_manual_calibration(
+ Dev);
+ pdev->low_power_auto_data.low_power_auto_range_count = 1;
+ } else if ((status == VL53L1_ERROR_NONE) &&
+ (pdev->low_power_auto_data.low_power_auto_range_count == 1)) {
+ pdev->low_power_auto_data.low_power_auto_range_count = 2;
+ }
+
+ /* perform DSS calculation. This can be performed every range */
+ if ((pdev->low_power_auto_data.low_power_auto_range_count != 0xFF) &&
+ (status == VL53L1_ERROR_NONE)) {
+ status = VL53L1_low_power_auto_update_DSS(
+ Dev);
+ }
+
+ }
+ /* End Patch_LowPowerAutoMode */
+
+ /* copy current state into results */
+
+ presults->cfg_device_state = pdev->ll_state.cfg_device_state;
+ presults->rd_device_state = pdev->ll_state.rd_device_state;
+
+ /* copy internal structure to supplied output pointer */
+
+ memcpy(
+ prange_results,
+ presults,
+ sizeof(VL53L1_range_results_t));
+
+ /*
+ * Check LL driver and Device are in Sync
+ * If not an error is raised
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_check_ll_driver_rd_state(Dev);
+
+#ifdef VL53L1_LOG_ENABLE
+ if (status == VL53L1_ERROR_NONE)
+ VL53L1_print_range_results(
+ presults,
+ "get_device_results():pdev->llresults.range_results.",
+ VL53L1_TRACE_MODULE_RANGE_RESULTS_DATA);
+#endif
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_clear_interrupt_and_enable_next_range(
+ VL53L1_DEV Dev,
+ uint8_t measurement_mode)
+{
+
+ /*
+ * Enable next range by sending handshake which
+ * clears the interrupt
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Dynamic Management */
+ /* Current results analysis and generate next settings */
+
+
+ /* Dynamic GPH Management */
+ /* Setup GPH absorption point and config values for next measurement */
+
+ /* Update GPH registers, clear interrupt and set measurement mode */
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_init_and_start_range(
+ Dev,
+ measurement_mode,
+ VL53L1_DEVICECONFIGLEVEL_GENERAL_ONWARDS);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+void VL53L1_copy_sys_and_core_results_to_range_results(
+ int32_t gain_factor,
+ VL53L1_system_results_t *psys,
+ VL53L1_core_results_t *pcore,
+ VL53L1_range_results_t *presults)
+{
+ uint8_t i = 0;
+
+ VL53L1_range_data_t *pdata;
+ int32_t range_mm = 0;
+ uint32_t tmpu32 = 0;
+
+ LOG_FUNCTION_START("");
+
+ /* copy results */
+
+ presults->stream_count = psys->result__stream_count;
+
+ pdata = &(presults->data[0]);
+
+ for (i = 0 ; i < 2 ; i++) {
+
+ pdata->range_id = i;
+ pdata->time_stamp = 0;
+
+ if ((psys->result__stream_count == 0) &&
+ ((psys->result__range_status & VL53L1_RANGE_STATUS__RANGE_STATUS_MASK) ==
+ VL53L1_DEVICEERROR_RANGECOMPLETE)) {
+ pdata->range_status = VL53L1_DEVICEERROR_RANGECOMPLETE_NO_WRAP_CHECK;
+ } else {
+ pdata->range_status =
+ psys->result__range_status & VL53L1_RANGE_STATUS__RANGE_STATUS_MASK;
+ }
+
+ switch (i) {
+
+ case 0:
+
+ if (psys->result__report_status == VL53L1_DEVICEREPORTSTATUS_MM1)
+ pdata->actual_effective_spads =
+ psys->result__mm_inner_actual_effective_spads_sd0;
+ else if (psys->result__report_status == VL53L1_DEVICEREPORTSTATUS_MM2)
+ pdata->actual_effective_spads =
+ psys->result__mm_outer_actual_effective_spads_sd0;
+ else
+ pdata->actual_effective_spads =
+ psys->result__dss_actual_effective_spads_sd0;
+
+ pdata->peak_signal_count_rate_mcps =
+ psys->result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0;
+ pdata->avg_signal_count_rate_mcps =
+ psys->result__avg_signal_count_rate_mcps_sd0;
+ pdata->ambient_count_rate_mcps =
+ psys->result__ambient_count_rate_mcps_sd0;
+
+ /* Start Patch_SigmaEstimateAccuracyImprovement */
+
+ /* shift up sigma estimate to 7 bit fractional and clip to 9 bit int */
+ tmpu32 = ((uint32_t)psys->result__sigma_sd0 << 5);
+ if (tmpu32 > 0xFFFF) {
+ tmpu32 = 0xFFFF;
+ }
+ pdata->sigma_mm = (uint16_t)tmpu32;
+
+ /* End Patch_SigmaEstimateAccuracyImprovement */
+
+ pdata->median_phase =
+ psys->result__phase_sd0;
+
+ range_mm =
+ (int32_t)psys->result__final_crosstalk_corrected_range_mm_sd0;
+
+ /* apply correction gain */
+ range_mm *= gain_factor;
+ range_mm += 0x0400;
+ range_mm /= 0x0800;
+
+ pdata->median_range_mm = (int16_t)range_mm;
+
+ pdata->ranging_total_events =
+ pcore->result_core__ranging_total_events_sd0;
+ pdata->signal_total_events =
+ pcore->result_core__signal_total_events_sd0;
+ pdata->total_periods_elapsed =
+ pcore->result_core__total_periods_elapsed_sd0;
+ pdata->ambient_window_events =
+ pcore->result_core__ambient_window_events_sd0;
+
+ break;
+ case 1:
+
+ pdata->actual_effective_spads =
+ psys->result__dss_actual_effective_spads_sd1;
+ pdata->peak_signal_count_rate_mcps =
+ psys->result__peak_signal_count_rate_mcps_sd1;
+ pdata->avg_signal_count_rate_mcps =
+ 0xFFFF;
+ pdata->ambient_count_rate_mcps =
+ psys->result__ambient_count_rate_mcps_sd1;
+
+ /* Start Patch_SigmaEstimateAccuracyImprovement */
+
+ /* shift up sigma estimate to 7 bit fractional and clip to 9 bit int */
+ tmpu32 = ((uint32_t)psys->result__sigma_sd1 << 5);
+ if (tmpu32 > 0xFFFF) {
+ tmpu32 = 0xFFFF;
+ }
+ pdata->sigma_mm = (uint16_t)tmpu32;
+
+ /* End Patch_SigmaEstimateAccuracyImprovement */
+
+ pdata->median_phase =
+ psys->result__phase_sd1;
+
+ range_mm =
+ (int32_t)psys->result__final_crosstalk_corrected_range_mm_sd1;
+
+ /* apply correction gain */
+ range_mm *= gain_factor;
+ range_mm += 0x0400;
+ range_mm /= 0x0800;
+
+ pdata->median_range_mm = (int16_t)range_mm;
+
+ pdata->ranging_total_events =
+ pcore->result_core__ranging_total_events_sd1;
+ pdata->signal_total_events =
+ pcore->result_core__signal_total_events_sd1;
+ pdata->total_periods_elapsed =
+ pcore->result_core__total_periods_elapsed_sd1;
+ pdata->ambient_window_events =
+ pcore->result_core__ambient_window_events_sd1;
+
+ break;
+ }
+
+ pdata++;
+ }
+
+ /* Update Global Device Status for results
+ * - Default to no update
+ */
+
+ presults->device_status = VL53L1_DEVICEERROR_NOUPDATE;
+
+ /* Check range status
+ * - If device error condition, update device status
+ * - Remove device status from range status output this should
+ * only contain information relating to range data
+ */
+
+ switch (psys->result__range_status &
+ VL53L1_RANGE_STATUS__RANGE_STATUS_MASK) {
+
+ case VL53L1_DEVICEERROR_VCSELCONTINUITYTESTFAILURE:
+ case VL53L1_DEVICEERROR_VCSELWATCHDOGTESTFAILURE:
+ case VL53L1_DEVICEERROR_NOVHVVALUEFOUND:
+ case VL53L1_DEVICEERROR_USERROICLIP:
+ case VL53L1_DEVICEERROR_MULTCLIPFAIL:
+
+ presults->device_status = (psys->result__range_status &
+ VL53L1_RANGE_STATUS__RANGE_STATUS_MASK);
+
+ presults->data[0].range_status = VL53L1_DEVICEERROR_NOUPDATE;
+ break;
+
+ }
+
+ LOG_FUNCTION_END(0);
+}
+
+/*
+ * Configure the GPIO interrupt config, from the given input
+ */
+
+VL53L1_Error VL53L1_set_GPIO_interrupt_config(
+ VL53L1_DEV Dev,
+ VL53L1_GPIO_Interrupt_Mode intr_mode_distance,
+ VL53L1_GPIO_Interrupt_Mode intr_mode_rate,
+ uint8_t intr_new_measure_ready,
+ uint8_t intr_no_target,
+ uint8_t intr_combined_mode,
+ uint16_t thresh_distance_high,
+ uint16_t thresh_distance_low,
+ uint16_t thresh_rate_high,
+ uint16_t thresh_rate_low
+ )
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+ VL53L1_GPIO_interrupt_config_t *pintconf = &(pdev->gpio_interrupt_config);
+
+ LOG_FUNCTION_START("");
+
+ /* update local data structure */
+ pintconf->intr_mode_distance = intr_mode_distance;
+ pintconf->intr_mode_rate = intr_mode_rate;
+ pintconf->intr_new_measure_ready = intr_new_measure_ready;
+ pintconf->intr_no_target = intr_no_target;
+ pintconf->intr_combined_mode = intr_combined_mode;
+ pintconf->threshold_distance_high = thresh_distance_high;
+ pintconf->threshold_distance_low = thresh_distance_low;
+ pintconf->threshold_rate_high = thresh_rate_high;
+ pintconf->threshold_rate_low = thresh_rate_low;
+
+ /* encoded interrupt config */
+ pdev->gen_cfg.system__interrupt_config_gpio =
+ VL53L1_encode_GPIO_interrupt_config(pintconf);
+
+
+ /* set thresholds */
+ status = VL53L1_set_GPIO_thresholds_from_struct(
+ Dev,
+ pintconf);
+
+ LOG_FUNCTION_END(status);
+ return status;
+}
+
+/*
+ * Configure the GPIO interrupt config, from the given structure
+ */
+
+VL53L1_Error VL53L1_set_GPIO_interrupt_config_struct(
+ VL53L1_DEV Dev,
+ VL53L1_GPIO_interrupt_config_t intconf)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+ VL53L1_GPIO_interrupt_config_t *pintconf = &(pdev->gpio_interrupt_config);
+
+ LOG_FUNCTION_START("");
+
+ /* using memcpy(dst, src, size in bytes) */
+ memcpy(pintconf, &(intconf), sizeof(VL53L1_GPIO_interrupt_config_t));
+
+ /* encoded interrupt config */
+ pdev->gen_cfg.system__interrupt_config_gpio =
+ VL53L1_encode_GPIO_interrupt_config(pintconf);
+
+ /* set thresholds */
+ status = VL53L1_set_GPIO_thresholds_from_struct(
+ Dev,
+ pintconf);
+
+ LOG_FUNCTION_END(status);
+ return status;
+}
+
+/*
+ * Retrieve GPIO interrupt config structure
+ */
+
+VL53L1_Error VL53L1_get_GPIO_interrupt_config(
+ VL53L1_DEV Dev,
+ VL53L1_GPIO_interrupt_config_t *pintconf)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ /*
+ * Decode the system__interrupt_config_gpio register
+ * This makes sure the structure is in line with the register
+ */
+ pdev->gpio_interrupt_config = VL53L1_decode_GPIO_interrupt_config(
+ pdev->gen_cfg.system__interrupt_config_gpio);
+
+ /*
+ * Readout the system thresholds
+ */
+ pdev->gpio_interrupt_config.threshold_distance_high =
+ pdev->dyn_cfg.system__thresh_high;
+ pdev->gpio_interrupt_config.threshold_distance_low =
+ pdev->dyn_cfg.system__thresh_low;
+
+ pdev->gpio_interrupt_config.threshold_rate_high =
+ pdev->gen_cfg.system__thresh_rate_high;
+ pdev->gpio_interrupt_config.threshold_rate_low =
+ pdev->gen_cfg.system__thresh_rate_low;
+
+ if (pintconf == &(pdev->gpio_interrupt_config)) {
+ /* Cowardly refusing to copy the same memory locations */
+ } else {
+
+ /* using memcpy(dst, src, size in bytes) */
+ memcpy(pintconf, &(pdev->gpio_interrupt_config),
+ sizeof(VL53L1_GPIO_interrupt_config_t));
+ }
+
+ LOG_FUNCTION_END(status);
+ return status;
+}
+
+VL53L1_Error VL53L1_set_offset_calibration_mode(
+ VL53L1_DEV Dev,
+ VL53L1_OffsetCalibrationMode offset_cal_mode)
+{
+
+ /*
+ * Sets the offset calibration mode
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ pdev->offset_calibration_mode = offset_cal_mode;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_get_offset_calibration_mode(
+ VL53L1_DEV Dev,
+ VL53L1_OffsetCalibrationMode *poffset_cal_mode)
+{
+
+ /*
+ * Gets the offset calibration mode
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ *poffset_cal_mode = pdev->offset_calibration_mode;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_offset_correction_mode(
+ VL53L1_DEV Dev,
+ VL53L1_OffsetCorrectionMode offset_cor_mode)
+{
+
+ /*
+ * Sets the offset correction mode
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ pdev->offset_correction_mode = offset_cor_mode;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_get_offset_correction_mode(
+ VL53L1_DEV Dev,
+ VL53L1_OffsetCorrectionMode *poffset_cor_mode)
+{
+
+ /*
+ * Gets the offset correction mode
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ *poffset_cor_mode = pdev->offset_correction_mode;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+/* Start Patch_AddedTuningParms_11761 */
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_get_tuning_debug_data(
+ VL53L1_DEV Dev,
+ VL53L1_tuning_parameters_t *ptun_data)
+{
+ /*
+ * Helper function to extract all tuning parm values
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ ptun_data->vl53l1_tuningparm_version =
+ pdev->tuning_parms.tp_tuning_parm_version;
+
+ ptun_data->vl53l1_tuningparm_key_table_version =
+ pdev->tuning_parms.tp_tuning_parm_key_table_version;
+
+
+ ptun_data->vl53l1_tuningparm_lld_version =
+ pdev->tuning_parms.tp_tuning_parm_lld_version;
+
+ ptun_data->vl53l1_tuningparm_lite_min_clip_mm =
+ pdev->tuning_parms.tp_lite_min_clip;
+
+ ptun_data->vl53l1_tuningparm_lite_long_sigma_thresh_mm =
+ pdev->tuning_parms.tp_lite_long_sigma_thresh_mm;
+
+ ptun_data->vl53l1_tuningparm_lite_med_sigma_thresh_mm =
+ pdev->tuning_parms.tp_lite_med_sigma_thresh_mm;
+
+ ptun_data->vl53l1_tuningparm_lite_short_sigma_thresh_mm =
+ pdev->tuning_parms.tp_lite_short_sigma_thresh_mm;
+
+ ptun_data->vl53l1_tuningparm_lite_long_min_count_rate_rtn_mcps =
+ pdev->tuning_parms.tp_lite_long_min_count_rate_rtn_mcps;
+
+ ptun_data->vl53l1_tuningparm_lite_med_min_count_rate_rtn_mcps =
+ pdev->tuning_parms.tp_lite_med_min_count_rate_rtn_mcps;
+
+ ptun_data->vl53l1_tuningparm_lite_short_min_count_rate_rtn_mcps =
+ pdev->tuning_parms.tp_lite_short_min_count_rate_rtn_mcps;
+
+ ptun_data->vl53l1_tuningparm_lite_sigma_est_pulse_width =
+ pdev->tuning_parms.tp_lite_sigma_est_pulse_width_ns;
+
+ ptun_data->vl53l1_tuningparm_lite_sigma_est_amb_width_ns =
+ pdev->tuning_parms.tp_lite_sigma_est_amb_width_ns;
+
+ ptun_data->vl53l1_tuningparm_lite_sigma_ref_mm =
+ pdev->tuning_parms.tp_lite_sigma_ref_mm;
+
+ ptun_data->vl53l1_tuningparm_lite_rit_mult =
+ pdev->xtalk_cfg.crosstalk_range_ignore_threshold_mult;
+
+ ptun_data->vl53l1_tuningparm_lite_seed_config =
+ pdev->tuning_parms.tp_lite_seed_cfg ;
+
+ ptun_data->vl53l1_tuningparm_lite_quantifier =
+ pdev->tuning_parms.tp_lite_quantifier;
+
+ ptun_data->vl53l1_tuningparm_lite_first_order_select =
+ pdev->tuning_parms.tp_lite_first_order_select;
+
+ ptun_data->vl53l1_tuningparm_lite_xtalk_margin_kcps =
+ pdev->xtalk_cfg.lite_mode_crosstalk_margin_kcps;
+
+ ptun_data->vl53l1_tuningparm_initial_phase_rtn_lite_long_range =
+ pdev->tuning_parms.tp_init_phase_rtn_lite_long;
+
+ ptun_data->vl53l1_tuningparm_initial_phase_rtn_lite_med_range =
+ pdev->tuning_parms.tp_init_phase_rtn_lite_med;
+
+ ptun_data->vl53l1_tuningparm_initial_phase_rtn_lite_short_range =
+ pdev->tuning_parms.tp_init_phase_rtn_lite_short;
+
+ ptun_data->vl53l1_tuningparm_initial_phase_ref_lite_long_range =
+ pdev->tuning_parms.tp_init_phase_ref_lite_long;
+
+ ptun_data->vl53l1_tuningparm_initial_phase_ref_lite_med_range =
+ pdev->tuning_parms.tp_init_phase_ref_lite_med;
+
+ ptun_data->vl53l1_tuningparm_initial_phase_ref_lite_short_range =
+ pdev->tuning_parms.tp_init_phase_ref_lite_short;
+
+ ptun_data->vl53l1_tuningparm_timed_seed_config =
+ pdev->tuning_parms.tp_timed_seed_cfg;
+
+ ptun_data->vl53l1_tuningparm_vhv_loopbound =
+ pdev->stat_nvm.vhv_config__timeout_macrop_loop_bound;
+
+ ptun_data->vl53l1_tuningparm_refspadchar_device_test_mode =
+ pdev->refspadchar.device_test_mode;
+
+ ptun_data->vl53l1_tuningparm_refspadchar_vcsel_period =
+ pdev->refspadchar.vcsel_period;
+
+ ptun_data->vl53l1_tuningparm_refspadchar_phasecal_timeout_us =
+ pdev->refspadchar.timeout_us;
+
+ ptun_data->vl53l1_tuningparm_refspadchar_target_count_rate_mcps =
+ pdev->refspadchar.target_count_rate_mcps;
+
+ ptun_data->vl53l1_tuningparm_refspadchar_min_countrate_limit_mcps =
+ pdev->refspadchar.min_count_rate_limit_mcps;
+
+ ptun_data->vl53l1_tuningparm_refspadchar_max_countrate_limit_mcps =
+ pdev->refspadchar.max_count_rate_limit_mcps;
+
+ ptun_data->vl53l1_tuningparm_offset_cal_dss_rate_mcps =
+ pdev->offsetcal_cfg.dss_config__target_total_rate_mcps;
+
+ ptun_data->vl53l1_tuningparm_offset_cal_phasecal_timeout_us =
+ pdev->offsetcal_cfg.phasecal_config_timeout_us;
+
+ ptun_data->vl53l1_tuningparm_offset_cal_mm_timeout_us =
+ pdev->offsetcal_cfg.mm_config_timeout_us;
+
+ ptun_data->vl53l1_tuningparm_offset_cal_range_timeout_us =
+ pdev->offsetcal_cfg.range_config_timeout_us;
+
+ ptun_data->vl53l1_tuningparm_offset_cal_pre_samples =
+ pdev->offsetcal_cfg.pre_num_of_samples;
+
+ ptun_data->vl53l1_tuningparm_offset_cal_mm1_samples =
+ pdev->offsetcal_cfg.mm1_num_of_samples;
+
+ ptun_data->vl53l1_tuningparm_offset_cal_mm2_samples =
+ pdev->offsetcal_cfg.mm2_num_of_samples;
+
+ ptun_data->vl53l1_tuningparm_spadmap_vcsel_period =
+ pdev->ssc_cfg.vcsel_period;
+
+ ptun_data->vl53l1_tuningparm_spadmap_vcsel_start =
+ pdev->ssc_cfg.vcsel_start;
+
+ ptun_data->vl53l1_tuningparm_spadmap_rate_limit_mcps =
+ pdev->ssc_cfg.rate_limit_mcps;
+
+ ptun_data->vl53l1_tuningparm_lite_dss_config_target_total_rate_mcps =
+ pdev->tuning_parms.tp_dss_target_lite_mcps;
+
+ ptun_data->vl53l1_tuningparm_timed_dss_config_target_total_rate_mcps =
+ pdev->tuning_parms.tp_dss_target_timed_mcps;
+
+ ptun_data->vl53l1_tuningparm_lite_phasecal_config_timeout_us =
+ pdev->tuning_parms.tp_phasecal_timeout_lite_us;
+
+ ptun_data->vl53l1_tuningparm_timed_phasecal_config_timeout_us =
+ pdev->tuning_parms.tp_phasecal_timeout_timed_us;
+
+ ptun_data->vl53l1_tuningparm_lite_mm_config_timeout_us =
+ pdev->tuning_parms.tp_mm_timeout_lite_us;
+
+ ptun_data->vl53l1_tuningparm_timed_mm_config_timeout_us =
+ pdev->tuning_parms.tp_mm_timeout_timed_us;
+
+ ptun_data->vl53l1_tuningparm_lite_range_config_timeout_us =
+ pdev->tuning_parms.tp_range_timeout_lite_us;
+
+ ptun_data->vl53l1_tuningparm_timed_range_config_timeout_us =
+ pdev->tuning_parms.tp_range_timeout_timed_us;
+
+ ptun_data->vl53l1_tuningparm_lowpowerauto_vhv_loop_bound =
+ pdev->low_power_auto_data.vhv_loop_bound;
+
+ ptun_data->vl53l1_tuningparm_lowpowerauto_mm_config_timeout_us =
+ pdev->tuning_parms.tp_mm_timeout_lpa_us;
+
+ ptun_data->vl53l1_tuningparm_lowpowerauto_range_config_timeout_us =
+ pdev->tuning_parms.tp_range_timeout_lpa_us;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_get_tuning_parm(
+ VL53L1_DEV Dev,
+ VL53L1_TuningParms tuning_parm_key,
+ int32_t *ptuning_parm_value)
+{
+
+ /*
+ * Gets the requested tuning parm value
+ * - Large case statement for returns
+ * - if key does not match, INVALID parm error returned
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ switch (tuning_parm_key) {
+
+ case VL53L1_TUNINGPARM_VERSION:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_tuning_parm_version;
+ break;
+ case VL53L1_TUNINGPARM_KEY_TABLE_VERSION:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_tuning_parm_key_table_version;
+ break;
+ case VL53L1_TUNINGPARM_LLD_VERSION:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_tuning_parm_lld_version;
+ break;
+ case VL53L1_TUNINGPARM_CONSISTENCY_LITE_PHASE_TOLERANCE:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_consistency_lite_phase_tolerance;
+ break;
+ case VL53L1_TUNINGPARM_PHASECAL_TARGET:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_phasecal_target;
+ break;
+ case VL53L1_TUNINGPARM_LITE_CAL_REPEAT_RATE:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_cal_repeat_rate;
+ break;
+ case VL53L1_TUNINGPARM_LITE_RANGING_GAIN_FACTOR:
+ *ptuning_parm_value =
+ (int32_t)pdev->gain_cal.standard_ranging_gain_factor;
+ break;
+ case VL53L1_TUNINGPARM_LITE_MIN_CLIP_MM:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_min_clip;
+ break;
+ case VL53L1_TUNINGPARM_LITE_LONG_SIGMA_THRESH_MM:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_long_sigma_thresh_mm;
+ break;
+ case VL53L1_TUNINGPARM_LITE_MED_SIGMA_THRESH_MM:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_med_sigma_thresh_mm;
+ break;
+ case VL53L1_TUNINGPARM_LITE_SHORT_SIGMA_THRESH_MM:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_short_sigma_thresh_mm;
+ break;
+ case VL53L1_TUNINGPARM_LITE_LONG_MIN_COUNT_RATE_RTN_MCPS:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_long_min_count_rate_rtn_mcps;
+ break;
+ case VL53L1_TUNINGPARM_LITE_MED_MIN_COUNT_RATE_RTN_MCPS:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_med_min_count_rate_rtn_mcps;
+ break;
+ case VL53L1_TUNINGPARM_LITE_SHORT_MIN_COUNT_RATE_RTN_MCPS:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_short_min_count_rate_rtn_mcps;
+ break;
+ case VL53L1_TUNINGPARM_LITE_SIGMA_EST_PULSE_WIDTH:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_sigma_est_pulse_width_ns;
+ break;
+ case VL53L1_TUNINGPARM_LITE_SIGMA_EST_AMB_WIDTH_NS:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_sigma_est_amb_width_ns;
+ break;
+ case VL53L1_TUNINGPARM_LITE_SIGMA_REF_MM:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_sigma_ref_mm;
+ break;
+ case VL53L1_TUNINGPARM_LITE_RIT_MULT:
+ *ptuning_parm_value =
+ (int32_t)pdev->xtalk_cfg.crosstalk_range_ignore_threshold_mult;
+ break;
+ case VL53L1_TUNINGPARM_LITE_SEED_CONFIG:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_seed_cfg ;
+ break;
+ case VL53L1_TUNINGPARM_LITE_QUANTIFIER:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_quantifier;
+ break;
+ case VL53L1_TUNINGPARM_LITE_FIRST_ORDER_SELECT:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_lite_first_order_select;
+ break;
+ case VL53L1_TUNINGPARM_LITE_XTALK_MARGIN_KCPS:
+ *ptuning_parm_value =
+ (int32_t)pdev->xtalk_cfg.lite_mode_crosstalk_margin_kcps;
+ break;
+ case VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_LONG_RANGE:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_init_phase_rtn_lite_long;
+ break;
+ case VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_MED_RANGE:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_init_phase_rtn_lite_med;
+ break;
+ case VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_SHORT_RANGE:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_init_phase_rtn_lite_short;
+ break;
+ case VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_LONG_RANGE:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_init_phase_ref_lite_long;
+ break;
+ case VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_MED_RANGE:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_init_phase_ref_lite_med;
+ break;
+ case VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_SHORT_RANGE:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_init_phase_ref_lite_short;
+ break;
+ case VL53L1_TUNINGPARM_TIMED_SEED_CONFIG:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_timed_seed_cfg;
+ break;
+ case VL53L1_TUNINGPARM_VHV_LOOPBOUND:
+ *ptuning_parm_value =
+ (int32_t)pdev->stat_nvm.vhv_config__timeout_macrop_loop_bound;
+ break;
+ case VL53L1_TUNINGPARM_REFSPADCHAR_DEVICE_TEST_MODE:
+ *ptuning_parm_value =
+ (int32_t)pdev->refspadchar.device_test_mode;
+ break;
+ case VL53L1_TUNINGPARM_REFSPADCHAR_VCSEL_PERIOD:
+ *ptuning_parm_value =
+ (int32_t)pdev->refspadchar.vcsel_period;
+ break;
+ case VL53L1_TUNINGPARM_REFSPADCHAR_PHASECAL_TIMEOUT_US:
+ *ptuning_parm_value =
+ (int32_t)pdev->refspadchar.timeout_us;
+ break;
+ case VL53L1_TUNINGPARM_REFSPADCHAR_TARGET_COUNT_RATE_MCPS:
+ *ptuning_parm_value =
+ (int32_t)pdev->refspadchar.target_count_rate_mcps;
+ break;
+ case VL53L1_TUNINGPARM_REFSPADCHAR_MIN_COUNTRATE_LIMIT_MCPS:
+ *ptuning_parm_value =
+ (int32_t)pdev->refspadchar.min_count_rate_limit_mcps;
+ break;
+ case VL53L1_TUNINGPARM_REFSPADCHAR_MAX_COUNTRATE_LIMIT_MCPS:
+ *ptuning_parm_value =
+ (int32_t)pdev->refspadchar.max_count_rate_limit_mcps;
+ break;
+ case VL53L1_TUNINGPARM_OFFSET_CAL_DSS_RATE_MCPS:
+ *ptuning_parm_value =
+ (int32_t)pdev->offsetcal_cfg.dss_config__target_total_rate_mcps;;
+ break;
+ case VL53L1_TUNINGPARM_OFFSET_CAL_PHASECAL_TIMEOUT_US:
+ *ptuning_parm_value =
+ (int32_t)pdev->offsetcal_cfg.phasecal_config_timeout_us;
+ break;
+ case VL53L1_TUNINGPARM_OFFSET_CAL_MM_TIMEOUT_US:
+ *ptuning_parm_value =
+ (int32_t)pdev->offsetcal_cfg.mm_config_timeout_us;
+ break;
+ case VL53L1_TUNINGPARM_OFFSET_CAL_RANGE_TIMEOUT_US:
+ *ptuning_parm_value =
+ (int32_t)pdev->offsetcal_cfg.range_config_timeout_us;
+ break;
+ case VL53L1_TUNINGPARM_OFFSET_CAL_PRE_SAMPLES:
+ *ptuning_parm_value =
+ (int32_t)pdev->offsetcal_cfg.pre_num_of_samples;
+ break;
+ case VL53L1_TUNINGPARM_OFFSET_CAL_MM1_SAMPLES:
+ *ptuning_parm_value =
+ (int32_t)pdev->offsetcal_cfg.mm1_num_of_samples;
+ break;
+ case VL53L1_TUNINGPARM_OFFSET_CAL_MM2_SAMPLES:
+ *ptuning_parm_value =
+ (int32_t)pdev->offsetcal_cfg.mm2_num_of_samples;
+ break;
+ case VL53L1_TUNINGPARM_SPADMAP_VCSEL_PERIOD:
+ *ptuning_parm_value =
+ (int32_t)pdev->ssc_cfg.vcsel_period;
+ break;
+ case VL53L1_TUNINGPARM_SPADMAP_VCSEL_START:
+ *ptuning_parm_value =
+ (int32_t)pdev->ssc_cfg.vcsel_start;
+ break;
+ case VL53L1_TUNINGPARM_SPADMAP_RATE_LIMIT_MCPS:
+ *ptuning_parm_value =
+ (int32_t)pdev->ssc_cfg.rate_limit_mcps;
+ break;
+ case VL53L1_TUNINGPARM_LITE_DSS_CONFIG_TARGET_TOTAL_RATE_MCPS:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_dss_target_lite_mcps;
+ break;
+ case VL53L1_TUNINGPARM_TIMED_DSS_CONFIG_TARGET_TOTAL_RATE_MCPS:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_dss_target_timed_mcps;
+ break;
+ case VL53L1_TUNINGPARM_LITE_PHASECAL_CONFIG_TIMEOUT_US:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_phasecal_timeout_lite_us;
+ break;
+ case VL53L1_TUNINGPARM_TIMED_PHASECAL_CONFIG_TIMEOUT_US:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_phasecal_timeout_timed_us;
+ break;
+ case VL53L1_TUNINGPARM_LITE_MM_CONFIG_TIMEOUT_US:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_mm_timeout_lite_us;
+ break;
+ case VL53L1_TUNINGPARM_TIMED_MM_CONFIG_TIMEOUT_US:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_mm_timeout_timed_us;
+ break;
+ case VL53L1_TUNINGPARM_LITE_RANGE_CONFIG_TIMEOUT_US:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_range_timeout_lite_us;
+ break;
+ case VL53L1_TUNINGPARM_TIMED_RANGE_CONFIG_TIMEOUT_US:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_range_timeout_timed_us;
+ break;
+ case VL53L1_TUNINGPARM_LOWPOWERAUTO_VHV_LOOP_BOUND:
+ *ptuning_parm_value =
+ (int32_t)pdev->low_power_auto_data.vhv_loop_bound;
+ break;
+ case VL53L1_TUNINGPARM_LOWPOWERAUTO_MM_CONFIG_TIMEOUT_US:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_mm_timeout_lpa_us;
+ break;
+ case VL53L1_TUNINGPARM_LOWPOWERAUTO_RANGE_CONFIG_TIMEOUT_US:
+ *ptuning_parm_value =
+ (int32_t)pdev->tuning_parms.tp_range_timeout_lpa_us;
+ break;
+
+
+ default:
+ *ptuning_parm_value = 0x7FFFFFFF;
+ status = VL53L1_ERROR_INVALID_PARAMS;
+ break;
+
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_set_tuning_parm(
+ VL53L1_DEV Dev,
+ VL53L1_TuningParms tuning_parm_key,
+ int32_t tuning_parm_value)
+{
+
+ /*
+ * Sets the requested tuning parm value
+ * - Large case statement for set value
+ * - if key does not match, INVALID parm error returned
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ switch (tuning_parm_key) {
+
+ case VL53L1_TUNINGPARM_VERSION:
+ pdev->tuning_parms.tp_tuning_parm_version =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_KEY_TABLE_VERSION:
+ pdev->tuning_parms.tp_tuning_parm_key_table_version =
+ (uint16_t)tuning_parm_value;
+
+ /* Perform Key Table Check
+ *
+ * - If does not match default, key table
+ * format does not match tuning file,
+ * error should be thrown
+ *
+ */
+
+ if ((uint16_t)tuning_parm_value
+ != VL53L1_TUNINGPARM_KEY_TABLE_VERSION_DEFAULT) {
+ status = VL53L1_ERROR_TUNING_PARM_KEY_MISMATCH;
+ }
+ break;
+ case VL53L1_TUNINGPARM_LLD_VERSION:
+ pdev->tuning_parms.tp_tuning_parm_lld_version =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_CONSISTENCY_LITE_PHASE_TOLERANCE:
+ pdev->tuning_parms.tp_consistency_lite_phase_tolerance =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_PHASECAL_TARGET:
+ pdev->tuning_parms.tp_phasecal_target =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_CAL_REPEAT_RATE:
+ pdev->tuning_parms.tp_cal_repeat_rate =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_RANGING_GAIN_FACTOR:
+ pdev->gain_cal.standard_ranging_gain_factor =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_MIN_CLIP_MM:
+ pdev->tuning_parms.tp_lite_min_clip =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_LONG_SIGMA_THRESH_MM:
+ pdev->tuning_parms.tp_lite_long_sigma_thresh_mm =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_MED_SIGMA_THRESH_MM:
+ pdev->tuning_parms.tp_lite_med_sigma_thresh_mm =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_SHORT_SIGMA_THRESH_MM:
+ pdev->tuning_parms.tp_lite_short_sigma_thresh_mm =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_LONG_MIN_COUNT_RATE_RTN_MCPS:
+ pdev->tuning_parms.tp_lite_long_min_count_rate_rtn_mcps =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_MED_MIN_COUNT_RATE_RTN_MCPS:
+ pdev->tuning_parms.tp_lite_med_min_count_rate_rtn_mcps =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_SHORT_MIN_COUNT_RATE_RTN_MCPS:
+ pdev->tuning_parms.tp_lite_short_min_count_rate_rtn_mcps =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_SIGMA_EST_PULSE_WIDTH:
+ pdev->tuning_parms.tp_lite_sigma_est_pulse_width_ns =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_SIGMA_EST_AMB_WIDTH_NS:
+ pdev->tuning_parms.tp_lite_sigma_est_amb_width_ns =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_SIGMA_REF_MM:
+ pdev->tuning_parms.tp_lite_sigma_ref_mm =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_RIT_MULT:
+ pdev->xtalk_cfg.crosstalk_range_ignore_threshold_mult =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_SEED_CONFIG:
+ pdev->tuning_parms.tp_lite_seed_cfg =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_QUANTIFIER:
+ pdev->tuning_parms.tp_lite_quantifier =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_FIRST_ORDER_SELECT:
+ pdev->tuning_parms.tp_lite_first_order_select =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_XTALK_MARGIN_KCPS:
+ pdev->xtalk_cfg.lite_mode_crosstalk_margin_kcps =
+ (int16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_LONG_RANGE:
+ pdev->tuning_parms.tp_init_phase_rtn_lite_long =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_MED_RANGE:
+ pdev->tuning_parms.tp_init_phase_rtn_lite_med =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_SHORT_RANGE:
+ pdev->tuning_parms.tp_init_phase_rtn_lite_short =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_LONG_RANGE:
+ pdev->tuning_parms.tp_init_phase_ref_lite_long =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_MED_RANGE:
+ pdev->tuning_parms.tp_init_phase_ref_lite_med =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_SHORT_RANGE:
+ pdev->tuning_parms.tp_init_phase_ref_lite_short =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_TIMED_SEED_CONFIG:
+ pdev->tuning_parms.tp_timed_seed_cfg =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_VHV_LOOPBOUND:
+ pdev->stat_nvm.vhv_config__timeout_macrop_loop_bound =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_REFSPADCHAR_DEVICE_TEST_MODE:
+ pdev->refspadchar.device_test_mode =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_REFSPADCHAR_VCSEL_PERIOD:
+ pdev->refspadchar.vcsel_period =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_REFSPADCHAR_PHASECAL_TIMEOUT_US:
+ pdev->refspadchar.timeout_us =
+ (uint32_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_REFSPADCHAR_TARGET_COUNT_RATE_MCPS:
+ pdev->refspadchar.target_count_rate_mcps =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_REFSPADCHAR_MIN_COUNTRATE_LIMIT_MCPS:
+ pdev->refspadchar.min_count_rate_limit_mcps =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_REFSPADCHAR_MAX_COUNTRATE_LIMIT_MCPS:
+ pdev->refspadchar.max_count_rate_limit_mcps =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_OFFSET_CAL_DSS_RATE_MCPS:
+ pdev->offsetcal_cfg.dss_config__target_total_rate_mcps =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_OFFSET_CAL_PHASECAL_TIMEOUT_US:
+ pdev->offsetcal_cfg.phasecal_config_timeout_us =
+ (uint32_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_OFFSET_CAL_MM_TIMEOUT_US:
+ pdev->offsetcal_cfg.mm_config_timeout_us =
+ (uint32_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_OFFSET_CAL_RANGE_TIMEOUT_US:
+ pdev->offsetcal_cfg.range_config_timeout_us =
+ (uint32_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_OFFSET_CAL_PRE_SAMPLES:
+ pdev->offsetcal_cfg.pre_num_of_samples =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_OFFSET_CAL_MM1_SAMPLES:
+ pdev->offsetcal_cfg.mm1_num_of_samples =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_OFFSET_CAL_MM2_SAMPLES:
+ pdev->offsetcal_cfg.mm2_num_of_samples =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_SPADMAP_VCSEL_PERIOD:
+ pdev->ssc_cfg.vcsel_period =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_SPADMAP_VCSEL_START:
+ pdev->ssc_cfg.vcsel_start =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_SPADMAP_RATE_LIMIT_MCPS:
+ pdev->ssc_cfg.rate_limit_mcps =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_DSS_CONFIG_TARGET_TOTAL_RATE_MCPS:
+ pdev->tuning_parms.tp_dss_target_lite_mcps =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_TIMED_DSS_CONFIG_TARGET_TOTAL_RATE_MCPS:
+ pdev->tuning_parms.tp_dss_target_timed_mcps =
+ (uint16_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_PHASECAL_CONFIG_TIMEOUT_US:
+ pdev->tuning_parms.tp_phasecal_timeout_lite_us =
+ (uint32_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_TIMED_PHASECAL_CONFIG_TIMEOUT_US:
+ pdev->tuning_parms.tp_phasecal_timeout_timed_us =
+ (uint32_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_MM_CONFIG_TIMEOUT_US:
+ pdev->tuning_parms.tp_mm_timeout_lite_us =
+ (uint32_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_TIMED_MM_CONFIG_TIMEOUT_US:
+ pdev->tuning_parms.tp_mm_timeout_timed_us =
+ (uint32_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LITE_RANGE_CONFIG_TIMEOUT_US:
+ pdev->tuning_parms.tp_range_timeout_lite_us =
+ (uint32_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_TIMED_RANGE_CONFIG_TIMEOUT_US:
+ pdev->tuning_parms.tp_range_timeout_timed_us =
+ (uint32_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LOWPOWERAUTO_VHV_LOOP_BOUND:
+ pdev->low_power_auto_data.vhv_loop_bound =
+ (uint8_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LOWPOWERAUTO_MM_CONFIG_TIMEOUT_US:
+ pdev->tuning_parms.tp_mm_timeout_lpa_us =
+ (uint32_t)tuning_parm_value;
+ break;
+ case VL53L1_TUNINGPARM_LOWPOWERAUTO_RANGE_CONFIG_TIMEOUT_US:
+ pdev->tuning_parms.tp_range_timeout_lpa_us =
+ (uint32_t)tuning_parm_value;
+ break;
+
+
+ default:
+ status = VL53L1_ERROR_INVALID_PARAMS;
+ break;
+
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+/* End Patch_AddedTuningParms_11761 */
diff --git a/src/lib/vl53l1/core/src/vl53l1_api_debug.c b/src/lib/vl53l1/core/src/vl53l1_api_debug.c
new file mode 100644
index 0000000000..2b5570afeb
--- /dev/null
+++ b/src/lib/vl53l1/core/src/vl53l1_api_debug.c
@@ -0,0 +1,1707 @@
+/*******************************************************************************
+ Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ ******************************************************************************/
+
+/**
+ * @file vl53l1_api_debug.c
+ * @brief EwokPlus25 low level Driver debug function definition
+ */
+
+#include "vl53l1_ll_def.h"
+#include "vl53l1_ll_device.h"
+#include "vl53l1_register_structs.h"
+#include "vl53l1_core.h"
+#include "vl53l1_api_debug.h"
+
+#define LOG_FUNCTION_START(fmt, ...) \
+ _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_CORE, fmt, ##__VA_ARGS__)
+#define LOG_FUNCTION_END(status, ...) \
+ _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_CORE, status, ##__VA_ARGS__)
+#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
+ _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_CORE, status, \
+ fmt, ##__VA_ARGS__)
+
+#define trace_print(level, ...) \
+ _LOG_TRACE_PRINT(trace_flags, \
+ level, VL53L1_TRACE_FUNCTION_NONE, ##__VA_ARGS__)
+
+
+/* Start Patch_AdditionalDebugData_11823 */
+
+VL53L1_Error VL53L1_get_additional_data(
+ VL53L1_DEV Dev,
+ VL53L1_additional_data_t *pdata)
+{
+ /*
+ * Gets the addition debug data
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ /* get LL Driver configuration parameters */
+
+ pdata->preset_mode = pdev->preset_mode;
+ pdata->measurement_mode = pdev->measurement_mode;
+
+ pdata->phasecal_config_timeout_us = pdev->phasecal_config_timeout_us;
+ pdata->mm_config_timeout_us = pdev->mm_config_timeout_us;
+ pdata->range_config_timeout_us = pdev->range_config_timeout_us;
+ pdata->inter_measurement_period_ms = pdev->inter_measurement_period_ms;
+ pdata->dss_config__target_total_rate_mcps =
+ pdev->dss_config__target_total_rate_mcps;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+/* End Patch_AdditionalDebugData_11823 */
+
+#ifdef VL53L1_LOG_ENABLE
+
+void VL53L1_signed_fixed_point_sprintf(
+ int32_t signed_fp_value,
+ uint8_t frac_bits,
+ uint16_t buf_size,
+ char *pbuffer)
+{
+ /*
+ * Converts input signed fixed point number into a string
+ */
+
+ uint32_t fp_value = 0;
+ uint32_t unity_fp_value = 0;
+ uint32_t sign_bit = 0;
+ uint32_t int_part = 0;
+ uint32_t frac_part = 0;
+ uint32_t dec_points = 0;
+ uint32_t dec_scaler = 0;
+ uint32_t dec_part = 0;
+
+ uint64_t tmp_long_int = 0;
+
+ char fmt[VL53L1_MAX_STRING_LENGTH];
+
+ SUPPRESS_UNUSED_WARNING(buf_size);
+
+ /* split into integer and fractional values */
+
+ sign_bit = signed_fp_value >> 31;
+
+ if (sign_bit > 0) {
+ fp_value = 0x80000000 -
+ (0x7FFFFFFF & (uint32_t)signed_fp_value);
+ } else
+ fp_value = (uint32_t)signed_fp_value;
+
+ int_part = fp_value >> frac_bits;
+ unity_fp_value = 0x01 << frac_bits;
+ frac_part = fp_value & (unity_fp_value-1);
+
+ /* Calculate decimal scale factor and required decimal points
+ * min number of displayed places is 2
+ */
+ dec_points = 2;
+ dec_scaler = 100;
+
+ while (dec_scaler < unity_fp_value) {
+ dec_points++;
+ dec_scaler *= 10;
+ }
+
+ /* Build format string */
+ if (sign_bit > 0)
+ sprintf(fmt, "-%%u.%%0%uu", dec_points);
+ else
+ sprintf(fmt, "%%u.%%0%uu", dec_points);
+
+ /* Convert fractional part into a decimal
+ * need 64-bit head room at this point
+ */
+ tmp_long_int = (uint64_t)frac_part * (uint64_t)dec_scaler;
+ tmp_long_int += (uint64_t)unity_fp_value/2;
+
+ tmp_long_int = do_division_u(tmp_long_int, (uint64_t)unity_fp_value);
+
+ dec_part = (uint32_t)tmp_long_int;
+
+ /* Generate string for fixed point number */
+ sprintf(
+ pbuffer,
+ fmt,
+ int_part,
+ dec_part);
+}
+
+
+void VL53L1_print_static_nvm_managed(
+ VL53L1_static_nvm_managed_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags)
+{
+ /**
+ * Prints out VL53L1_static_nvm_managed_t for debug
+ */
+
+ char fp_text[VL53L1_MAX_STRING_LENGTH];
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = 0x%02X\n",
+ pprefix,
+ "i2c_slave__device_address",
+ pdata->i2c_slave__device_address);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "ana_config__vhv_ref_sel_vddpix",
+ pdata->ana_config__vhv_ref_sel_vddpix);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "ana_config__vhv_ref_sel_vquench",
+ pdata->ana_config__vhv_ref_sel_vquench);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "ana_config__reg_avdd1v2_sel",
+ pdata->ana_config__reg_avdd1v2_sel);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "ana_config__fast_osc__trim",
+ pdata->ana_config__fast_osc__trim);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->osc_measured__fast_osc__frequency,
+ 12,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "osc_measured__fast_osc__frequency",
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "vhv_config__timeout_macrop_loop_bound",
+ pdata->vhv_config__timeout_macrop_loop_bound);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "vhv_config__count_thresh",
+ pdata->vhv_config__count_thresh);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "vhv_config__offset",
+ pdata->vhv_config__offset);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "vhv_config__init",
+ pdata->vhv_config__init);
+}
+
+
+void VL53L1_print_customer_nvm_managed(
+ VL53L1_customer_nvm_managed_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags)
+{
+ /*
+ * Prints out VL53L1_customer_nvm_managed_t for debug
+ */
+
+ char fp_text[VL53L1_MAX_STRING_LENGTH];
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_ref_0",
+ pdata->global_config__spad_enables_ref_0);
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_ref_1",
+ pdata->global_config__spad_enables_ref_1);
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_ref_2",
+ pdata->global_config__spad_enables_ref_2);
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_ref_3",
+ pdata->global_config__spad_enables_ref_3);
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_ref_4",
+ pdata->global_config__spad_enables_ref_4);
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_ref_5",
+ pdata->global_config__spad_enables_ref_5);
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__ref_en_start_select",
+ pdata->global_config__ref_en_start_select);
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "ref_spad_man__num_requested_ref_spads",
+ pdata->ref_spad_man__num_requested_ref_spads);
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "ref_spad_man__ref_location",
+ pdata->ref_spad_man__ref_location);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->algo__crosstalk_compensation_plane_offset_kcps,
+ 9,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "algo__crosstalk_compensation_plane_offset_kcps",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->algo__crosstalk_compensation_x_plane_gradient_kcps,
+ 11,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "algo__crosstalk_compensation_x_plane_gradient_kcps",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->algo__crosstalk_compensation_y_plane_gradient_kcps,
+ 11,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "algo__crosstalk_compensation_y_plane_gradient_kcps",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->ref_spad_char__total_rate_target_mcps,
+ 7,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "ref_spad_char__total_rate_target_mcps",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->algo__part_to_part_range_offset_mm,
+ 2,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "algo__part_to_part_range_offset_mm",
+ fp_text);
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %d\n",
+ pprefix,
+ "mm_config__inner_offset_mm",
+ pdata->mm_config__inner_offset_mm);
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %d\n",
+ pprefix,
+ "mm_config__outer_offset_mm",
+ pdata->mm_config__outer_offset_mm);
+}
+
+
+void VL53L1_print_nvm_copy_data(
+ VL53L1_nvm_copy_data_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags)
+{
+ /**
+ * Prints out VL53L1_nvm_copy_data_t for debug
+ */
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "identification__model_id",
+ pdata->identification__model_id);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "identification__module_type",
+ pdata->identification__module_type);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "identification__revision_id",
+ pdata->identification__revision_id);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "identification__module_id",
+ pdata->identification__module_id);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "ana_config__fast_osc__trim_max",
+ pdata->ana_config__fast_osc__trim_max);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "ana_config__fast_osc__freq_set",
+ pdata->ana_config__fast_osc__freq_set);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "ana_config__vcsel_trim",
+ pdata->ana_config__vcsel_trim);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "ana_config__vcsel_selion",
+ pdata->ana_config__vcsel_selion);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "ana_config__vcsel_selion_max",
+ pdata->ana_config__vcsel_selion_max);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "protected_laser_safety__lock_bit",
+ pdata->protected_laser_safety__lock_bit);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "laser_safety__key",
+ pdata->laser_safety__key);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "laser_safety__key_ro",
+ pdata->laser_safety__key_ro);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "laser_safety__clip",
+ pdata->laser_safety__clip);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "laser_safety__mult",
+ pdata->laser_safety__mult);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_0",
+ pdata->global_config__spad_enables_rtn_0);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_1",
+ pdata->global_config__spad_enables_rtn_1);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_2",
+ pdata->global_config__spad_enables_rtn_2);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_3",
+ pdata->global_config__spad_enables_rtn_3);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_4",
+ pdata->global_config__spad_enables_rtn_4);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_5",
+ pdata->global_config__spad_enables_rtn_5);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_6",
+ pdata->global_config__spad_enables_rtn_6);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_7",
+ pdata->global_config__spad_enables_rtn_7);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_8",
+ pdata->global_config__spad_enables_rtn_8);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_9",
+ pdata->global_config__spad_enables_rtn_9);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_10",
+ pdata->global_config__spad_enables_rtn_10);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_11",
+ pdata->global_config__spad_enables_rtn_11);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_12",
+ pdata->global_config__spad_enables_rtn_12);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_13",
+ pdata->global_config__spad_enables_rtn_13);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_14",
+ pdata->global_config__spad_enables_rtn_14);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_15",
+ pdata->global_config__spad_enables_rtn_15);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_16",
+ pdata->global_config__spad_enables_rtn_16);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_17",
+ pdata->global_config__spad_enables_rtn_17);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_18",
+ pdata->global_config__spad_enables_rtn_18);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_19",
+ pdata->global_config__spad_enables_rtn_19);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_20",
+ pdata->global_config__spad_enables_rtn_20);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_21",
+ pdata->global_config__spad_enables_rtn_21);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_22",
+ pdata->global_config__spad_enables_rtn_22);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_23",
+ pdata->global_config__spad_enables_rtn_23);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_24",
+ pdata->global_config__spad_enables_rtn_24);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_25",
+ pdata->global_config__spad_enables_rtn_25);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_26",
+ pdata->global_config__spad_enables_rtn_26);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_27",
+ pdata->global_config__spad_enables_rtn_27);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_28",
+ pdata->global_config__spad_enables_rtn_28);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_29",
+ pdata->global_config__spad_enables_rtn_29);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_30",
+ pdata->global_config__spad_enables_rtn_30);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_config__spad_enables_rtn_31",
+ pdata->global_config__spad_enables_rtn_31);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "roi_config__mode_roi_centre_spad",
+ pdata->roi_config__mode_roi_centre_spad);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = 0x%02X\n",
+ pprefix,
+ "roi_config__mode_roi_xy_size",
+ pdata->roi_config__mode_roi_xy_size);
+}
+
+
+void VL53L1_print_range_data(
+ VL53L1_range_data_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags)
+{
+ /*
+ * Prints out the range data structure for debug
+ */
+
+ char fp_text[VL53L1_MAX_STRING_LENGTH];
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "range_id",
+ pdata->range_id);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "time_stamp",
+ pdata->time_stamp);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->width,
+ 4, VL53L1_MAX_STRING_LENGTH, fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "width",
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "woi",
+ pdata->woi);
+
+ /* Fast Oscillator Frequency */
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->fast_osc_frequency,
+ 12, VL53L1_MAX_STRING_LENGTH, fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "fast_osc_frequency",
+ fp_text);
+
+ /* Zero Distance Phase */
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->zero_distance_phase,
+ 11, VL53L1_MAX_STRING_LENGTH, fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "zero_distance_phase",
+ fp_text);
+
+ /* Actual effective SPAD count */
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->actual_effective_spads,
+ 8, VL53L1_MAX_STRING_LENGTH, fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "actual_effective_spad",
+ fp_text);
+
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "total_periods_elapsed",
+ pdata->total_periods_elapsed);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "peak_duration_us",
+ pdata->peak_duration_us);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "woi_duration_us",
+ pdata->woi_duration_us);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %d\n",
+ pprefix,
+ "ambient_window_events",
+ pdata->ambient_window_events);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %d\n",
+ pprefix,
+ "ranging_total_events",
+ pdata->ranging_total_events);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %d\n",
+ pprefix,
+ "signal_total_events",
+ pdata->signal_total_events);
+
+ /* Rates */
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->peak_signal_count_rate_mcps,
+ 7, VL53L1_MAX_STRING_LENGTH, fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "peak_signal_count_rate_mcps",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->avg_signal_count_rate_mcps,
+ 7, VL53L1_MAX_STRING_LENGTH, fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "avg_signal_count_rate_mcps",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->ambient_count_rate_mcps,
+ 7, VL53L1_MAX_STRING_LENGTH, fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "ambient_count_rate_mcps",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->total_rate_per_spad_mcps,
+ 13, VL53L1_MAX_STRING_LENGTH, fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "total_rate_per_spad_mcps",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->peak_rate_per_spad_kcps,
+ 11, VL53L1_MAX_STRING_LENGTH, fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "peak_rate_per_spad_kcps",
+ fp_text);
+
+ /* Sigma */
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->sigma_mm,
+ 2, VL53L1_MAX_STRING_LENGTH, fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "sigma_mm",
+ fp_text);
+
+ /* Phase */
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->median_phase,
+ 11, VL53L1_MAX_STRING_LENGTH, fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "median_phase",
+ fp_text);
+
+ /* Offset Corrected Range */
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %d\n",
+ pprefix,
+ "median_range_mm",
+ pdata->median_range_mm);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "range_status",
+ pdata->range_status);
+}
+
+
+void VL53L1_print_range_results(
+ VL53L1_range_results_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags)
+{
+ /*
+ * Prints out the range results data structure for debug
+ */
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "cfg_device_state",
+ pdata->cfg_device_state);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "rd_device_state",
+ pdata->rd_device_state);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "stream_count",
+ pdata->stream_count);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "device_status",
+ pdata->device_status);
+
+}
+
+void VL53L1_print_offset_range_results(
+ VL53L1_offset_range_results_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags)
+{
+ /*
+ * Prints out the offset range results data structure for debug
+ */
+
+ char pre_text[VL53L1_MAX_STRING_LENGTH];
+ char *ppre_text = &(pre_text[0]);
+
+ uint8_t i = 0;
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "cal_distance_mm",
+ pdata->cal_distance_mm);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "cal_status",
+ pdata->cal_status);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "cal_report",
+ pdata->cal_report);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "max_results",
+ pdata->max_results);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "active_results",
+ pdata->active_results);
+
+ for (i = 0 ; i < pdata->active_results ; i++) {
+ sprintf(ppre_text, "%sdata[%u].", pprefix, i);
+ VL53L1_print_offset_range_data(
+ &(pdata->data[i]),
+ ppre_text, trace_flags);
+ }
+}
+
+void VL53L1_print_offset_range_data(
+ VL53L1_offset_range_data_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags)
+{
+ /*
+ * Prints out the xtalk range (ROI) data structure for debug
+ */
+
+ char fp_text[VL53L1_MAX_STRING_LENGTH];
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "preset_mode",
+ pdata->preset_mode);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "dss_config__roi_mode_control",
+ pdata->dss_config__roi_mode_control);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->dss_config__manual_effective_spads_select,
+ 8,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "dss_config__manual_effective_spads_select",
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "no_of_samples",
+ pdata->no_of_samples);
+
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->effective_spads,
+ 8,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "effective_spads",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->peak_rate_mcps,
+ 7,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "peak_rate_mcps",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->sigma_mm,
+ 2,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "sigma_mm",
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %d\n",
+ pprefix,
+ "median_range_mm",
+ pdata->median_range_mm);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %d\n",
+ pprefix,
+ "range_mm_offset",
+ pdata->range_mm_offset);
+}
+
+void VL53L1_print_additional_offset_cal_data(
+ VL53L1_additional_offset_cal_data_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags)
+{
+ /*
+ * Prints out the xtalk range (ROI) data structure for debug
+ */
+
+ char fp_text[VL53L1_MAX_STRING_LENGTH];
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->result__mm_inner_actual_effective_spads,
+ 8,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "result__mm_inner_actual_effective_spads",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->result__mm_outer_actual_effective_spads,
+ 8,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "result__mm_outer_actual_effective_spads",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->result__mm_inner_peak_signal_count_rtn_mcps,
+ 7,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "result__mm_inner_peak_signal_count_rtn_mcps",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->result__mm_outer_peak_signal_count_rtn_mcps,
+ 7,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "result__mm_outer_peak_signal_count_rtn_mcps",
+ fp_text);
+}
+
+
+void VL53L1_print_cal_peak_rate_map(
+ VL53L1_cal_peak_rate_map_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags)
+{
+ /*
+ * Prints out peak rate map structure for debug
+ */
+
+ char fp_text[VL53L1_MAX_STRING_LENGTH];
+ char pre_text[VL53L1_MAX_STRING_LENGTH];
+ char *ppre_text = &(pre_text[0]);
+
+ uint8_t i = 0;
+ uint8_t x = 0;
+ uint8_t y = 0;
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->cal_distance_mm,
+ 2,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "cal_distance_mm",
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "max_samples",
+ pdata->max_samples);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "width",
+ pdata->width);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "height",
+ pdata->height);
+
+ i = 0;
+ for (y = 0 ; y < pdata->height ; y++) {
+ for (x = 0 ; x < pdata->width ; x++) {
+
+ sprintf(ppre_text, "%speak_rate_mcps[%u]", pprefix, i);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->peak_rate_mcps[i],
+ 7,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s = %s\n",
+ ppre_text,
+ fp_text);
+
+ i++;
+ }
+ }
+}
+
+void VL53L1_print_additional_data(
+ VL53L1_additional_data_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags)
+{
+
+ /*
+ * Prints out the Additional data structure for debug
+ */
+
+ char fp_text[VL53L1_MAX_STRING_LENGTH];
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "preset_mode",
+ pdata->preset_mode);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "measurement_mode",
+ pdata->measurement_mode);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "phasecal_config_timeout_us",
+ pdata->phasecal_config_timeout_us);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "mm_config_timeout_us",
+ pdata->mm_config_timeout_us);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "range_config_timeout_us",
+ pdata->range_config_timeout_us);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "inter_measurement_period_ms",
+ pdata->inter_measurement_period_ms);
+
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->dss_config__target_total_rate_mcps,
+ 7,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "dss_config__target_total_rate_mcps",
+ fp_text);
+
+}
+
+
+void VL53L1_print_gain_calibration_data(
+ VL53L1_gain_calibration_data_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags)
+{
+ /*
+ * Prints out the LL Driver state data for debug
+ */
+
+ char fp_text[VL53L1_MAX_STRING_LENGTH];
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->standard_ranging_gain_factor,
+ 11,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "standard_ranging_gain_factor",
+ fp_text);
+
+}
+
+
+void VL53L1_print_xtalk_config(
+ VL53L1_xtalk_config_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags)
+{
+ /*
+ * Prints out the xtalk config data structure for debug
+ */
+
+ char fp_text[VL53L1_MAX_STRING_LENGTH];
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->algo__crosstalk_compensation_plane_offset_kcps,
+ 9,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "algo__crosstalk_compensation_plane_offset_kcps",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->algo__crosstalk_compensation_x_plane_gradient_kcps,
+ 11,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "algo__crosstalk_compensation_x_plane_gradient_kcps",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->algo__crosstalk_compensation_y_plane_gradient_kcps,
+ 11,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "algo__crosstalk_compensation_y_plane_gradient_kcps",
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "global_crosstalk_compensation_enable",
+ pdata->global_crosstalk_compensation_enable);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->lite_mode_crosstalk_margin_kcps,
+ 9,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "lite_mode_crosstalk_margin_kcps",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->crosstalk_range_ignore_threshold_mult,
+ 5,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "crosstalk_range_ignore_threshold_mult",
+ fp_text);
+
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->crosstalk_range_ignore_threshold_rate_mcps,
+ 13,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "crosstalk_range_ignore_threshold_rate_mcps",
+ fp_text);
+
+}
+
+
+
+void VL53L1_print_optical_centre(
+ VL53L1_optical_centre_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags)
+{
+
+ /* Prints out the optical centre data structure for debug
+ */
+
+ char fp_text[VL53L1_MAX_STRING_LENGTH];
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->x_centre,
+ 4,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "x_centre",
+ fp_text);
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pdata->y_centre,
+ 4,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %s\n",
+ pprefix,
+ "y_centre",
+ fp_text);
+}
+
+
+void VL53L1_print_user_zone(
+ VL53L1_user_zone_t *pdata,
+ char *pprefix,
+ uint32_t trace_flags)
+{
+
+ /* Prints out the zone (ROI) data structure for debug
+ */
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "x_centre",
+ pdata->x_centre);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "y_centre",
+ pdata->y_centre);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "width",
+ pdata->width);
+
+ trace_print(VL53L1_TRACE_LEVEL_INFO,
+ "%s%s = %u\n",
+ pprefix,
+ "height",
+ pdata->height);
+}
+
+
+void VL53L1_print_spad_rate_data(
+ VL53L1_spad_rate_data_t *pspad_rates,
+ char *pprefix,
+ uint32_t trace_flags)
+{
+
+ /**
+ * Print per SPAD rates generated by SSC
+ */
+
+ uint16_t spad_no = 0;
+ uint8_t row = 0;
+ uint8_t col = 0;
+
+ char fp_text[VL53L1_MAX_STRING_LENGTH];
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%8s,%4s,%4s, %s\n",
+ pprefix,
+ "spad_no",
+ "row",
+ "col",
+ "peak_rate_mcps");
+
+ for (spad_no = 0 ; spad_no < pspad_rates->no_of_values ; spad_no++) {
+
+ /* generate row / col location from SPAD number */
+ VL53L1_decode_row_col(
+ (uint8_t)spad_no,
+ &row,
+ &col);
+
+ /* Convert fixed point rate value to string */
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pspad_rates->rate_data[spad_no],
+ pspad_rates->fractional_bits,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ /* Print data */
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%8u,%4u,%4u, %s\n",
+ pprefix,
+ spad_no,
+ row,
+ col,
+ fp_text);
+ }
+}
+
+
+void VL53L1_print_spad_rate_map(
+ VL53L1_spad_rate_data_t *pspad_rates,
+ char *pprefix,
+ uint32_t trace_flags)
+{
+
+ /**
+ * Print per SPAD rates generated by SSC as a map
+ */
+
+ uint8_t spad_no = 0;
+ uint8_t row = 0;
+ uint8_t col = 0;
+
+ char fp_text[VL53L1_MAX_STRING_LENGTH];
+
+ /* Print column headers */
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%4s",
+ pprefix,
+ " ");
+
+ for (col = 0 ; col < VL53L1_SPAD_ARRAY_WIDTH ; col++)
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ ",%8u",
+ col);
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "\n");
+
+ /* Print rate data */
+
+ for (row = 0 ; row < VL53L1_SPAD_ARRAY_HEIGHT ; row++) {
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "%s%4u",
+ pprefix,
+ row);
+
+ for (col = 0 ; col < VL53L1_SPAD_ARRAY_HEIGHT ; col++) {
+
+ /* generate SPAD number from (row, col) location */
+
+ VL53L1_encode_row_col(
+ row,
+ col,
+ &spad_no);
+
+ /* Convert fixed point rate value to string */
+
+ VL53L1_signed_fixed_point_sprintf(
+ (int32_t)pspad_rates->rate_data[spad_no],
+ pspad_rates->fractional_bits,
+ VL53L1_MAX_STRING_LENGTH,
+ fp_text);
+
+ /* Print data */
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ ",%8s",
+ fp_text);
+ }
+
+ trace_print(
+ VL53L1_TRACE_LEVEL_INFO,
+ "\n");
+ }
+}
+
+
+#endif /* VL53L1_LOG_ENABLE */
+
diff --git a/src/lib/vl53l1/core/src/vl53l1_api_preset_modes.c b/src/lib/vl53l1/core/src/vl53l1_api_preset_modes.c
new file mode 100644
index 0000000000..09c7d6e8b6
--- /dev/null
+++ b/src/lib/vl53l1/core/src/vl53l1_api_preset_modes.c
@@ -0,0 +1,1373 @@
+/*******************************************************************************
+ Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ ******************************************************************************/
+
+/**
+ * @file vl53l1_api_preset_modes.c
+ *
+ * @brief EwokPlus25 API Preset Modes definitions
+ */
+
+#include "vl53l1_ll_def.h"
+#include "vl53l1_platform_log.h"
+#include "vl53l1_register_structs.h"
+#include "vl53l1_register_settings.h"
+#include "vl53l1_core.h"
+#include "vl53l1_api_preset_modes.h"
+#include "vl53l1_tuning_parm_defaults.h"
+
+
+#define LOG_FUNCTION_START(fmt, ...) \
+ _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_API, fmt, ##__VA_ARGS__)
+#define LOG_FUNCTION_END(status, ...) \
+ _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_API, status, ##__VA_ARGS__)
+#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
+ _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_API, status, fmt, ##__VA_ARGS__)
+
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_init_refspadchar_config_struct(
+ VL53L1_refspadchar_config_t *pdata)
+{
+ /*
+ * Initializes Ref SPAD Char data structures preset mode
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Reference SPAD Char Configuration
+ *
+ * vcsel_period = 0x0B - 24 clock VCSEL period
+ * timeout_us = 1000 - Set 1000us phase cal timeout
+ * target_count_rate_mcps = 0x0A00 - 9.7 -> 20.0 Mcps
+ * min_count_rate_limit_mcps = 0x0500 - 9.7 -> 10.0 Mcps
+ * max_count_rate_limit_mcps = 0x1400 - 9.7 -> 40.0 Mcps
+ */
+
+ pdata->device_test_mode =
+ VL53L1_TUNINGPARM_REFSPADCHAR_DEVICE_TEST_MODE_DEFAULT;
+ pdata->vcsel_period =
+ VL53L1_TUNINGPARM_REFSPADCHAR_VCSEL_PERIOD_DEFAULT;
+ pdata->timeout_us =
+ VL53L1_TUNINGPARM_REFSPADCHAR_PHASECAL_TIMEOUT_US_DEFAULT;
+ pdata->target_count_rate_mcps =
+ VL53L1_TUNINGPARM_REFSPADCHAR_TARGET_COUNT_RATE_MCPS_DEFAULT;
+ pdata->min_count_rate_limit_mcps =
+ VL53L1_TUNINGPARM_REFSPADCHAR_MIN_COUNTRATE_LIMIT_MCPS_DEFAULT;
+ pdata->max_count_rate_limit_mcps =
+ VL53L1_TUNINGPARM_REFSPADCHAR_MAX_COUNTRATE_LIMIT_MCPS_DEFAULT;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_init_ssc_config_struct(
+ VL53L1_ssc_config_t *pdata)
+{
+ /*
+ * Initializes SPAD Self Check (SSC) data structure
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* SPAD Select Check Configuration */
+
+ /* 0 - store RTN count rates
+ * 1 - store REF count rates
+ */
+ pdata->array_select = VL53L1_DEVICESSCARRAY_RTN;
+
+ /* VCSEL period register value 0x12 (18) -> 38 VCSEL clocks */
+ pdata->vcsel_period =
+ VL53L1_TUNINGPARM_SPADMAP_VCSEL_PERIOD_DEFAULT;
+
+ /* VCSEL pulse start */
+ pdata->vcsel_start =
+ VL53L1_TUNINGPARM_SPADMAP_VCSEL_START_DEFAULT;
+
+ /* VCSEL pulse width */
+ pdata->vcsel_width = 0x02;
+
+ /* SSC timeout [us] */
+ pdata->timeout_us = 36000;
+
+ /* SSC rate limit [Mcps]
+ * - 9.7 for VCSEL ON
+ * - 1.15 for VCSEL OFF
+ */
+ pdata->rate_limit_mcps =
+ VL53L1_TUNINGPARM_SPADMAP_RATE_LIMIT_MCPS_DEFAULT;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_init_xtalk_config_struct(
+ VL53L1_customer_nvm_managed_t *pnvm,
+ VL53L1_xtalk_config_t *pdata)
+{
+ /*
+ * Initializes Xtalk Config structure
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Xtalk default configuration
+ *
+ * algo__crosstalk_compensation_plane_offset_kcps
+ * = pdev->customer.algo__crosstalk_compensation_plane_offset_kcps
+ * algo__crosstalk_compensation_x_plane_gradient_kcps
+ * = pdev->customer.algo__crosstalk_compensation_x_plane_gradient_kcps
+ * algo__crosstalk_compensation_y_plane_gradient_kcps
+ * = pdev->customer.algo__crosstalk_compensation_y_plane_gradient_kcps
+ *
+ */
+
+ /* Store xtalk data into golden copy */
+
+ pdata->algo__crosstalk_compensation_plane_offset_kcps =
+ pnvm->algo__crosstalk_compensation_plane_offset_kcps;
+ pdata->algo__crosstalk_compensation_x_plane_gradient_kcps =
+ pnvm->algo__crosstalk_compensation_x_plane_gradient_kcps;
+ pdata->algo__crosstalk_compensation_y_plane_gradient_kcps =
+ pnvm->algo__crosstalk_compensation_y_plane_gradient_kcps;
+
+ /* Store NVM defaults for later use */
+
+ pdata->nvm_default__crosstalk_compensation_plane_offset_kcps =
+ (uint32_t)pnvm->algo__crosstalk_compensation_plane_offset_kcps;
+ pdata->nvm_default__crosstalk_compensation_x_plane_gradient_kcps =
+ pnvm->algo__crosstalk_compensation_x_plane_gradient_kcps;
+ pdata->nvm_default__crosstalk_compensation_y_plane_gradient_kcps =
+ pnvm->algo__crosstalk_compensation_y_plane_gradient_kcps;
+
+ pdata->lite_mode_crosstalk_margin_kcps =
+ VL53L1_TUNINGPARM_LITE_XTALK_MARGIN_KCPS_DEFAULT;
+
+ /* Default for Range Ignore Threshold Mult = 2.0 */
+
+ pdata->crosstalk_range_ignore_threshold_mult =
+ VL53L1_TUNINGPARM_LITE_RIT_MULT_DEFAULT;
+
+ if ((pdata->algo__crosstalk_compensation_plane_offset_kcps == 0x00)
+ && (pdata->algo__crosstalk_compensation_x_plane_gradient_kcps == 0x00)
+ && (pdata->algo__crosstalk_compensation_y_plane_gradient_kcps == 0x00))
+ pdata->global_crosstalk_compensation_enable = 0x00;
+ else
+ pdata->global_crosstalk_compensation_enable = 0x01;
+
+
+ if ((status == VL53L1_ERROR_NONE) &&
+ (pdata->global_crosstalk_compensation_enable == 0x01)) {
+ pdata->crosstalk_range_ignore_threshold_rate_mcps =
+ VL53L1_calc_range_ignore_threshold(
+ pdata->algo__crosstalk_compensation_plane_offset_kcps,
+ pdata->algo__crosstalk_compensation_x_plane_gradient_kcps,
+ pdata->algo__crosstalk_compensation_y_plane_gradient_kcps,
+ pdata->crosstalk_range_ignore_threshold_mult);
+ } else {
+ pdata->crosstalk_range_ignore_threshold_rate_mcps = 0;
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_init_offset_cal_config_struct(
+ VL53L1_offsetcal_config_t *pdata)
+{
+ /*
+ * Initializes Offset Calibration Config structure
+ * - for use with VL53L1_run_offset_calibration()
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Preset Timeout and DSS defaults */
+
+ pdata->dss_config__target_total_rate_mcps =
+ VL53L1_TUNINGPARM_OFFSET_CAL_DSS_RATE_MCPS_DEFAULT;
+ /* 20.0 Mcps */
+ pdata->phasecal_config_timeout_us =
+ VL53L1_TUNINGPARM_OFFSET_CAL_PHASECAL_TIMEOUT_US_DEFAULT;
+ /* 1000 us */
+ pdata->range_config_timeout_us =
+ VL53L1_TUNINGPARM_OFFSET_CAL_RANGE_TIMEOUT_US_DEFAULT;
+ /* 13000 us */
+ pdata->mm_config_timeout_us =
+ VL53L1_TUNINGPARM_OFFSET_CAL_MM_TIMEOUT_US_DEFAULT;
+ /* 13000 us - Added as part of Patch_AddedOffsetCalMMTuningParm_11791 */
+
+ /* Init number of averaged samples */
+
+ pdata->pre_num_of_samples =
+ VL53L1_TUNINGPARM_OFFSET_CAL_PRE_SAMPLES_DEFAULT;
+ pdata->mm1_num_of_samples =
+ VL53L1_TUNINGPARM_OFFSET_CAL_MM1_SAMPLES_DEFAULT;
+ pdata->mm2_num_of_samples =
+ VL53L1_TUNINGPARM_OFFSET_CAL_MM2_SAMPLES_DEFAULT;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+VL53L1_Error VL53L1_init_tuning_parm_storage_struct(
+ VL53L1_tuning_parm_storage_t *pdata)
+{
+ /*
+ * Initializes Tuning Param storage structure
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Default configuration
+ *
+ * - Custom overwrite possible from vl53l1_set_tuning_parms()
+ * - via tuning file input
+ */
+
+ pdata->tp_tuning_parm_version =
+ VL53L1_TUNINGPARM_VERSION_DEFAULT;
+ pdata->tp_tuning_parm_key_table_version =
+ VL53L1_TUNINGPARM_KEY_TABLE_VERSION_DEFAULT;
+ pdata->tp_tuning_parm_lld_version =
+ VL53L1_TUNINGPARM_LLD_VERSION_DEFAULT;
+ pdata->tp_init_phase_rtn_lite_long =
+ VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_LONG_RANGE_DEFAULT;
+ pdata->tp_init_phase_rtn_lite_med =
+ VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_MED_RANGE_DEFAULT;
+ pdata->tp_init_phase_rtn_lite_short =
+ VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_SHORT_RANGE_DEFAULT;
+ pdata->tp_init_phase_ref_lite_long =
+ VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_LONG_RANGE_DEFAULT;
+ pdata->tp_init_phase_ref_lite_med =
+ VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_MED_RANGE_DEFAULT;
+ pdata->tp_init_phase_ref_lite_short =
+ VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_SHORT_RANGE_DEFAULT;
+ pdata->tp_consistency_lite_phase_tolerance =
+ VL53L1_TUNINGPARM_CONSISTENCY_LITE_PHASE_TOLERANCE_DEFAULT;
+ pdata->tp_phasecal_target =
+ VL53L1_TUNINGPARM_PHASECAL_TARGET_DEFAULT;
+ pdata->tp_cal_repeat_rate =
+ VL53L1_TUNINGPARM_LITE_CAL_REPEAT_RATE_DEFAULT;
+ pdata->tp_lite_min_clip =
+ VL53L1_TUNINGPARM_LITE_MIN_CLIP_MM_DEFAULT;
+ pdata->tp_lite_long_sigma_thresh_mm =
+ VL53L1_TUNINGPARM_LITE_LONG_SIGMA_THRESH_MM_DEFAULT;
+ pdata->tp_lite_med_sigma_thresh_mm =
+ VL53L1_TUNINGPARM_LITE_MED_SIGMA_THRESH_MM_DEFAULT;
+ pdata->tp_lite_short_sigma_thresh_mm =
+ VL53L1_TUNINGPARM_LITE_SHORT_SIGMA_THRESH_MM_DEFAULT;
+ pdata->tp_lite_long_min_count_rate_rtn_mcps =
+ VL53L1_TUNINGPARM_LITE_LONG_MIN_COUNT_RATE_RTN_MCPS_DEFAULT;
+ pdata->tp_lite_med_min_count_rate_rtn_mcps =
+ VL53L1_TUNINGPARM_LITE_MED_MIN_COUNT_RATE_RTN_MCPS_DEFAULT;
+ pdata->tp_lite_short_min_count_rate_rtn_mcps =
+ VL53L1_TUNINGPARM_LITE_SHORT_MIN_COUNT_RATE_RTN_MCPS_DEFAULT;
+ pdata->tp_lite_sigma_est_pulse_width_ns =
+ VL53L1_TUNINGPARM_LITE_SIGMA_EST_PULSE_WIDTH_DEFAULT;
+ pdata->tp_lite_sigma_est_amb_width_ns =
+ VL53L1_TUNINGPARM_LITE_SIGMA_EST_AMB_WIDTH_NS_DEFAULT;
+ pdata->tp_lite_sigma_ref_mm =
+ VL53L1_TUNINGPARM_LITE_SIGMA_REF_MM_DEFAULT;
+ pdata->tp_lite_seed_cfg =
+ VL53L1_TUNINGPARM_LITE_SEED_CONFIG_DEFAULT;
+ pdata->tp_timed_seed_cfg =
+ VL53L1_TUNINGPARM_TIMED_SEED_CONFIG_DEFAULT;
+ pdata->tp_lite_quantifier =
+ VL53L1_TUNINGPARM_LITE_QUANTIFIER_DEFAULT;
+ pdata->tp_lite_first_order_select =
+ VL53L1_TUNINGPARM_LITE_FIRST_ORDER_SELECT_DEFAULT;
+
+ /* Preset Mode Configurations */
+ /* - New parms added as part of Patch_TuningParmPresetModeAddition_11839 */
+
+ pdata->tp_dss_target_lite_mcps =
+ VL53L1_TUNINGPARM_LITE_DSS_CONFIG_TARGET_TOTAL_RATE_MCPS_DEFAULT;
+ pdata->tp_dss_target_timed_mcps =
+ VL53L1_TUNINGPARM_TIMED_DSS_CONFIG_TARGET_TOTAL_RATE_MCPS_DEFAULT;
+ pdata->tp_phasecal_timeout_lite_us =
+ VL53L1_TUNINGPARM_LITE_PHASECAL_CONFIG_TIMEOUT_US;
+ pdata->tp_phasecal_timeout_timed_us =
+ VL53L1_TUNINGPARM_TIMED_PHASECAL_CONFIG_TIMEOUT_US_DEFAULT;
+ pdata->tp_mm_timeout_lite_us =
+ VL53L1_TUNINGPARM_LITE_MM_CONFIG_TIMEOUT_US_DEFAULT;
+ pdata->tp_mm_timeout_timed_us =
+ VL53L1_TUNINGPARM_TIMED_MM_CONFIG_TIMEOUT_US_DEFAULT;
+ pdata->tp_range_timeout_lite_us =
+ VL53L1_TUNINGPARM_LITE_RANGE_CONFIG_TIMEOUT_US_DEFAULT;
+ pdata->tp_range_timeout_timed_us =
+ VL53L1_TUNINGPARM_TIMED_RANGE_CONFIG_TIMEOUT_US_DEFAULT;
+
+ /* Added for Patch_LowPowerAutoMode */
+
+ pdata->tp_mm_timeout_lpa_us =
+ VL53L1_TUNINGPARM_LOWPOWERAUTO_MM_CONFIG_TIMEOUT_US_DEFAULT;
+ pdata->tp_range_timeout_lpa_us =
+ VL53L1_TUNINGPARM_LOWPOWERAUTO_RANGE_CONFIG_TIMEOUT_US_DEFAULT;
+
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_preset_mode_standard_ranging(
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms)
+{
+ /*
+ * Initializes static and dynamic data structures fordevice preset mode
+ * VL53L1_DEVICEPRESETMODE_STANDARD_RANGING
+ *
+ * - streaming
+ * - single sigma delta
+ * - back to back
+ *
+ * PLEASE NOTE THE SETTINGS BELOW AT PROVISIONAL AND WILL CHANGE!
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Static Configuration */
+
+ /* dss_config__target_total_rate_mcps = 20.0 Mcps 9.7 fp */
+ pstatic->dss_config__target_total_rate_mcps = 0x0A00;
+ pstatic->debug__ctrl = 0x00;
+ pstatic->test_mode__ctrl = 0x00;
+ pstatic->clk_gating__ctrl = 0x00;
+ pstatic->nvm_bist__ctrl = 0x00;
+ pstatic->nvm_bist__num_nvm_words = 0x00;
+ pstatic->nvm_bist__start_address = 0x00;
+ pstatic->host_if__status = 0x00;
+ pstatic->pad_i2c_hv__config = 0x00;
+ pstatic->pad_i2c_hv__extsup_config = 0x00;
+
+ /*
+ * 0 - gpio__extsup_hv
+ * 1 - gpio__vmodeint_hv
+ */
+ pstatic->gpio_hv_pad__ctrl = 0x00;
+
+ /*
+ * Set interrupt active low
+ *
+ * 3:0 - gpio__mux_select_hv
+ * 4 - gpio__mux_active_high_hv
+ */
+ pstatic->gpio_hv_mux__ctrl = \
+ VL53L1_DEVICEINTERRUPTPOLARITY_ACTIVE_LOW | \
+ VL53L1_DEVICEGPIOMODE_OUTPUT_RANGE_AND_ERROR_INTERRUPTS;
+
+ pstatic->gpio__tio_hv_status = 0x02;
+ pstatic->gpio__fio_hv_status = 0x00;
+ pstatic->ana_config__spad_sel_pswidth = 0x02;
+ pstatic->ana_config__vcsel_pulse_width_offset = 0x08;
+ pstatic->ana_config__fast_osc__config_ctrl = 0x00;
+
+ pstatic->sigma_estimator__effective_pulse_width_ns =
+ ptuning_parms->tp_lite_sigma_est_pulse_width_ns;
+ pstatic->sigma_estimator__effective_ambient_width_ns =
+ ptuning_parms->tp_lite_sigma_est_amb_width_ns;
+ pstatic->sigma_estimator__sigma_ref_mm =
+ ptuning_parms->tp_lite_sigma_ref_mm;
+ /* Minimum allowable value of 1 - 0 disables the feature */
+ pstatic->algo__crosstalk_compensation_valid_height_mm = 0x01;
+ pstatic->spare_host_config__static_config_spare_0 = 0x00;
+ pstatic->spare_host_config__static_config_spare_1 = 0x00;
+
+ pstatic->algo__range_ignore_threshold_mcps = 0x0000;
+
+ /* set RIT distance to 20 mm */
+ pstatic->algo__range_ignore_valid_height_mm = 0xff;
+ pstatic->algo__range_min_clip =
+ ptuning_parms->tp_lite_min_clip;
+ /*
+ * Phase consistency check limit - format 1.3 fp
+ * 0x02 -> 0.25
+ * 0x08 -> 1.00
+ */
+ pstatic->algo__consistency_check__tolerance =
+ ptuning_parms->tp_consistency_lite_phase_tolerance;
+ pstatic->spare_host_config__static_config_spare_2 = 0x00;
+ pstatic->sd_config__reset_stages_msb = 0x00;
+ pstatic->sd_config__reset_stages_lsb = 0x00;
+
+ pgeneral->gph_config__stream_count_update_value = 0x00;
+ pgeneral->global_config__stream_divider = 0x00;
+ pgeneral->system__interrupt_config_gpio =
+ VL53L1_INTERRUPT_CONFIG_NEW_SAMPLE_READY;
+ pgeneral->cal_config__vcsel_start = 0x0B;
+
+ /*
+ * Set VHV / Phase Cal repeat rate to 1 every
+ * 60 * 60 ranges (once every minute @ 60Hz)
+ * 0 - disables
+ * 12-bit value -> 4095 max
+ */
+ pgeneral->cal_config__repeat_rate =
+ ptuning_parms->tp_cal_repeat_rate;
+ pgeneral->global_config__vcsel_width = 0x02;
+ /* 13 macro periods gives a timeout of 1ms */
+ pgeneral->phasecal_config__timeout_macrop = 0x0D;
+ /* Phase cal target phase 2.0625 - 4.4 fp -> 0x21*/
+ pgeneral->phasecal_config__target =
+ ptuning_parms->tp_phasecal_target;
+ pgeneral->phasecal_config__override = 0x00;
+ pgeneral->dss_config__roi_mode_control =
+ VL53L1_DEVICEDSSMODE__TARGET_RATE;
+ /* format for threshold high and low is 9.7 fp */
+ pgeneral->system__thresh_rate_high = 0x0000;
+ pgeneral->system__thresh_rate_low = 0x0000;
+ /* The format for manual effective spads is 8.8 -> 0x8C00 = 140.00 */
+ pgeneral->dss_config__manual_effective_spads_select = 0x8C00;
+ pgeneral->dss_config__manual_block_select = 0x00;
+
+ /*
+ * Aperture attenuation value - format 0.8
+ *
+ * Nominal: 5x -> 0.200000 * 256 = 51 = 0x33
+ * Measured: 4.6x -> 0.217391 * 256 = 56 = 0x38
+ */
+ pgeneral->dss_config__aperture_attenuation = 0x38;
+ pgeneral->dss_config__max_spads_limit = 0xFF;
+ pgeneral->dss_config__min_spads_limit = 0x01;
+
+ /* Timing Configuration */
+
+ /* Default timing of 2ms */
+ ptiming->mm_config__timeout_macrop_a_hi = 0x00;
+ ptiming->mm_config__timeout_macrop_a_lo = 0x1a;
+ ptiming->mm_config__timeout_macrop_b_hi = 0x00;
+ ptiming->mm_config__timeout_macrop_b_lo = 0x20;
+ /* Setup for 30ms default */
+ ptiming->range_config__timeout_macrop_a_hi = 0x01;
+ ptiming->range_config__timeout_macrop_a_lo = 0xCC;
+ /* register value 11 gives a 24 VCSEL period */
+ ptiming->range_config__vcsel_period_a = 0x0B;
+ /* Setup for 30ms default */
+ ptiming->range_config__timeout_macrop_b_hi = 0x01;
+ ptiming->range_config__timeout_macrop_b_lo = 0xF5;
+ /* register value 09 gives a 20 VCSEL period */
+ ptiming->range_config__vcsel_period_b = 0x09;
+ /*
+ * Sigma thresh register - format 14.2
+ *
+ * 0x003C -> 15.0 mm
+ * 0x0050 -> 20.0 mm
+ */
+ ptiming->range_config__sigma_thresh =
+ ptuning_parms->tp_lite_med_sigma_thresh_mm;
+ /*
+ * Rate Limit - format 9.7fp
+ * 0x0020 -> 0.250 Mcps
+ * 0x0080 -> 1.000 Mcps
+ */
+ ptiming->range_config__min_count_rate_rtn_limit_mcps =
+ ptuning_parms->tp_lite_med_min_count_rate_rtn_mcps;
+
+ /* Phase limit register formats = 5.3
+ * low = 0x08 -> 1.0
+ * high = 0x78 -> 15.0 -> 3.0m
+ */
+ ptiming->range_config__valid_phase_low = 0x08;
+ ptiming->range_config__valid_phase_high = 0x78;
+ ptiming->system__intermeasurement_period = 0x00000000;
+ ptiming->system__fractional_enable = 0x00;
+
+ /* Dynamic Configuration */
+
+ pdynamic->system__grouped_parameter_hold_0 = 0x01;
+
+ pdynamic->system__thresh_high = 0x0000;
+ pdynamic->system__thresh_low = 0x0000;
+ pdynamic->system__enable_xtalk_per_quadrant = 0x00;
+ pdynamic->system__seed_config =
+ ptuning_parms->tp_lite_seed_cfg;
+
+ /* Timing A */
+ pdynamic->sd_config__woi_sd0 = 0x0B;
+ /* Timing B */
+ pdynamic->sd_config__woi_sd1 = 0x09;
+
+ pdynamic->sd_config__initial_phase_sd0 =
+ ptuning_parms->tp_init_phase_rtn_lite_med;
+ pdynamic->sd_config__initial_phase_sd1 =
+ ptuning_parms->tp_init_phase_ref_lite_med;;
+
+ pdynamic->system__grouped_parameter_hold_1 = 0x01;
+
+ /*
+ * Quantifier settings
+ *
+ * sd_config__first_order_select
+ * bit 0 - return sigma delta
+ * bit 1 - reference sigma delta
+ *
+ * sd_config__first_order_select = 0x03 (1st order)
+ *
+ * sd_config__quantifier options
+ * 0
+ * 1 -> 64
+ * 2 -> 128
+ * 3 -> 256
+ *
+ * sd_config__first_order_select = 0x00 (2nd order)
+ *
+ * sd_config__quantifier options
+ * 0
+ * 1 -> 256
+ * 2 -> 1024
+ * 3 -> 4095
+ *
+ * Setting below 2nd order, Quantifier = 1024
+ */
+
+ pdynamic->sd_config__first_order_select =
+ ptuning_parms->tp_lite_first_order_select;
+ pdynamic->sd_config__quantifier =
+ ptuning_parms->tp_lite_quantifier;
+
+ /* Below defaults will be overwritten by zone_cfg
+ * Spad no = 199 (0xC7)
+ * Spad no = 63 (0x3F)
+ */
+ pdynamic->roi_config__user_roi_centre_spad = 0xC7;
+ /* 16x16 ROI */
+ pdynamic->roi_config__user_roi_requested_global_xy_size = 0xFF;
+
+
+ pdynamic->system__sequence_config = \
+ VL53L1_SEQUENCE_VHV_EN | \
+ VL53L1_SEQUENCE_PHASECAL_EN | \
+ VL53L1_SEQUENCE_DSS1_EN | \
+ VL53L1_SEQUENCE_DSS2_EN | \
+ VL53L1_SEQUENCE_MM2_EN | \
+ VL53L1_SEQUENCE_RANGE_EN;
+
+ pdynamic->system__grouped_parameter_hold = 0x02;
+
+ /* System control */
+
+
+ psystem->system__stream_count_ctrl = 0x00;
+ psystem->firmware__enable = 0x01;
+ psystem->system__interrupt_clear = \
+ VL53L1_CLEAR_RANGE_INT;
+
+ psystem->system__mode_start = \
+ VL53L1_DEVICESCHEDULERMODE_STREAMING | \
+ VL53L1_DEVICEREADOUTMODE_SINGLE_SD | \
+ VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_preset_mode_standard_ranging_short_range(
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms)
+{
+ /*
+ * Initializes static and dynamic data structures for
+ * device preset mode
+ *
+ * VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_SHORT_RANGE
+ * (up to 1.4 metres)
+ *
+ * PLEASE NOTE THE SETTINGS BELOW AT PROVISIONAL AND WILL CHANGE!
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Call standard ranging configuration followed by
+ * overrides for the short range configuration
+ */
+
+ status = VL53L1_preset_mode_standard_ranging(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+
+ /* now override standard ranging specific registers */
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ /* Timing Configuration
+ *
+ * vcsel_period_a = 7 -> 16 period
+ * vcsel_period_b = 5 -> 12 period
+ * sigma_thresh = 0x003C -> 14.2fp -> 15.0 mm
+ * min_count_rate_rtn_limit_mcps = 0x0080 -> 9.7fp -> 1.0 Mcps
+ * valid_phase_low = 0x08 -> 5.3fp -> 1.0
+ * valid_phase_high = 0x38 -> 5.3fp -> 7.0 -> 1.4m
+ */
+
+ ptiming->range_config__vcsel_period_a = 0x07;
+ ptiming->range_config__vcsel_period_b = 0x05;
+ ptiming->range_config__sigma_thresh =
+ ptuning_parms->tp_lite_short_sigma_thresh_mm;
+ ptiming->range_config__min_count_rate_rtn_limit_mcps =
+ ptuning_parms->tp_lite_short_min_count_rate_rtn_mcps;
+ ptiming->range_config__valid_phase_low = 0x08;
+ ptiming->range_config__valid_phase_high = 0x38;
+
+ /* Dynamic Configuration
+ * SD0 -> Timing A
+ * SD1 -> Timing B
+ */
+
+ pdynamic->sd_config__woi_sd0 = 0x07;
+ pdynamic->sd_config__woi_sd1 = 0x05;
+ pdynamic->sd_config__initial_phase_sd0 =
+ ptuning_parms->tp_init_phase_rtn_lite_short;
+ pdynamic->sd_config__initial_phase_sd1 =
+ ptuning_parms->tp_init_phase_ref_lite_short;
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_preset_mode_standard_ranging_long_range(
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms)
+{
+ /*
+ * Initializes static and dynamic data structures for
+ * device preset mode
+ *
+ * VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_LONG_RANGE
+ * (up to 4.8 metres)
+ *
+ * PLEASE NOTE THE SETTINGS BELOW AT PROVISIONAL AND WILL CHANGE!
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Call standard ranging configuration with
+ * overrides for long range configuration
+ */
+
+ status = VL53L1_preset_mode_standard_ranging(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+
+ /* now override standard ranging specific registers */
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ /* Timing Configuration
+ *
+ * vcsel_period_a = 15 -> 32 period
+ * vcsel_period_b = 13 -> 28 period
+ * sigma_thresh = 0x003C -> 14.2fp -> 15.0 mm
+ * min_count_rate_rtn_limit_mcps = 0x0080 -> 9.7fp -> 1.0 Mcps
+ * valid_phase_low = 0x08 -> 5.3fp -> 1.0
+ * valid_phase_high = 0xB8 -> 5.3fp -> 23.0 -> 4.6m
+ */
+
+ ptiming->range_config__vcsel_period_a = 0x0F;
+ ptiming->range_config__vcsel_period_b = 0x0D;
+ ptiming->range_config__sigma_thresh =
+ ptuning_parms->tp_lite_long_sigma_thresh_mm;
+ ptiming->range_config__min_count_rate_rtn_limit_mcps =
+ ptuning_parms->tp_lite_long_min_count_rate_rtn_mcps;
+ ptiming->range_config__valid_phase_low = 0x08;
+ ptiming->range_config__valid_phase_high = 0xB8;
+
+ /* Dynamic Configuration
+ * SD0 -> Timing A
+ * SD1 -> Timing B
+ */
+
+ pdynamic->sd_config__woi_sd0 = 0x0F;
+ pdynamic->sd_config__woi_sd1 = 0x0D;
+ pdynamic->sd_config__initial_phase_sd0 =
+ ptuning_parms->tp_init_phase_rtn_lite_long;
+ pdynamic->sd_config__initial_phase_sd1 =
+ ptuning_parms->tp_init_phase_ref_lite_long;
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_preset_mode_standard_ranging_mm1_cal(
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms)
+{
+ /*
+ * Initializes static and dynamic data structures for
+ * device preset mode
+ *
+ * VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM1_CAL
+ *
+ * PLEASE NOTE THE SETTINGS BELOW AT PROVISIONAL AND WILL CHANGE!
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Call standard ranging configuration with
+ * overrides for long range configuration
+ */
+
+ status = VL53L1_preset_mode_standard_ranging(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+
+ /* now override standard ranging specific registers */
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ pgeneral->dss_config__roi_mode_control =
+ VL53L1_DEVICEDSSMODE__REQUESTED_EFFFECTIVE_SPADS;
+
+ pdynamic->system__sequence_config = \
+ VL53L1_SEQUENCE_VHV_EN | \
+ VL53L1_SEQUENCE_PHASECAL_EN | \
+ VL53L1_SEQUENCE_DSS1_EN | \
+ VL53L1_SEQUENCE_DSS2_EN | \
+ VL53L1_SEQUENCE_MM1_EN;
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_preset_mode_standard_ranging_mm2_cal(
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms)
+{
+ /*
+ * Initializes static and dynamic data structures for
+ * device preset mode
+ *
+ * VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM2_CAL
+ *
+ * PLEASE NOTE THE SETTINGS BELOW AT PROVISIONAL AND WILL CHANGE!
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Call standard ranging configuration with
+ * overrides for long range configuration
+ */
+
+ status = VL53L1_preset_mode_standard_ranging(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+
+ /* now override standard ranging specific registers */
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ pgeneral->dss_config__roi_mode_control =
+ VL53L1_DEVICEDSSMODE__REQUESTED_EFFFECTIVE_SPADS;
+
+ pdynamic->system__sequence_config = \
+ VL53L1_SEQUENCE_VHV_EN | \
+ VL53L1_SEQUENCE_PHASECAL_EN | \
+ VL53L1_SEQUENCE_DSS1_EN | \
+ VL53L1_SEQUENCE_DSS2_EN | \
+ VL53L1_SEQUENCE_MM2_EN;
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_preset_mode_timed_ranging(
+
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms)
+{
+ /*
+ * Initializes static and dynamic data structures for
+ * device preset mode
+ *
+ * VL53L1_DEVICEPRESETMODE_TIMED_RANGING
+ *
+ * - pseudo-solo
+ * - single sigma delta
+ * - timed
+ *
+ * PLEASE NOTE THE SETTINGS BELOW AT PROVISIONAL AND WILL CHANGE!
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Call standard ranging configuration */
+
+ status = VL53L1_preset_mode_standard_ranging(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+
+ /* now override standard ranging specific registers */
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ /* Dynamic Configuration */
+
+ /* Disable GPH */
+ pdynamic->system__grouped_parameter_hold = 0x00;
+
+ /* Re-Configure timing budget default for 13ms */
+ ptiming->range_config__timeout_macrop_a_hi = 0x00;
+ ptiming->range_config__timeout_macrop_a_lo = 0xB1;
+ /* Setup for 13ms default */
+ ptiming->range_config__timeout_macrop_b_hi = 0x00;
+ ptiming->range_config__timeout_macrop_b_lo = 0xD4;
+
+ /* Timing Configuration */
+
+ ptiming->system__intermeasurement_period = 0x00000600;
+ pdynamic->system__seed_config =
+ ptuning_parms->tp_timed_seed_cfg;
+
+ /* System control */
+
+ /* Configure Timed/Psuedo-solo mode */
+ psystem->system__mode_start =
+ VL53L1_DEVICESCHEDULERMODE_PSEUDO_SOLO | \
+ VL53L1_DEVICEREADOUTMODE_SINGLE_SD | \
+ VL53L1_DEVICEMEASUREMENTMODE_TIMED;
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+VL53L1_Error VL53L1_preset_mode_timed_ranging_short_range(
+
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms)
+{
+ /*
+ * Initializes static and dynamic data structures for
+ * device preset mode
+ *
+ * VL53L1_DEVICEPRESETMODE_TIMED_RANGING_SHORT_RANGE
+ *
+ * - pseudo-solo
+ * - single sigma delta
+ * - timed
+ *
+ * PLEASE NOTE THE SETTINGS BELOW AT PROVISIONAL AND WILL CHANGE!
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Call standard ranging configuration */
+
+ status = VL53L1_preset_mode_standard_ranging_short_range(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+
+ /* now override standard ranging specific registers */
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ /* Dynamic Configuration */
+
+ /* Disable GPH */
+ pdynamic->system__grouped_parameter_hold = 0x00;
+
+
+ /* Timing Configuration */
+
+ /* Re-Configure timing budget default for 13ms */
+ ptiming->range_config__timeout_macrop_a_hi = 0x01;
+ ptiming->range_config__timeout_macrop_a_lo = 0x84;
+ /* Setup for 13ms default */
+ ptiming->range_config__timeout_macrop_b_hi = 0x01;
+ ptiming->range_config__timeout_macrop_b_lo = 0xB1;
+
+ ptiming->system__intermeasurement_period = 0x00000600;
+ pdynamic->system__seed_config =
+ ptuning_parms->tp_timed_seed_cfg;
+
+ /* System control */
+
+ /* Configure Timed/Psuedo-solo mode */
+ psystem->system__mode_start =
+ VL53L1_DEVICESCHEDULERMODE_PSEUDO_SOLO | \
+ VL53L1_DEVICEREADOUTMODE_SINGLE_SD | \
+ VL53L1_DEVICEMEASUREMENTMODE_TIMED;
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+VL53L1_Error VL53L1_preset_mode_timed_ranging_long_range(
+
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms)
+{
+ /*
+ * Initializes static and dynamic data structures for
+ * device preset mode
+ *
+ * VL53L1_DEVICEPRESETMODE_TIMED_RANGING_LONG_RANGE
+ *
+ * - pseudo-solo
+ * - single sigma delta
+ * - timed
+ *
+ * PLEASE NOTE THE SETTINGS BELOW AT PROVISIONAL AND WILL CHANGE!
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Call standard ranging configuration */
+
+ status = VL53L1_preset_mode_standard_ranging_long_range(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+
+ /* now override standard ranging specific registers */
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ /* Dynamic Configuration */
+
+ /* Disable GPH */
+ pdynamic->system__grouped_parameter_hold = 0x00;
+
+
+ /* Timing Configuration */
+
+ /* Re-Configure timing budget default for 13ms */
+ ptiming->range_config__timeout_macrop_a_hi = 0x00;
+ ptiming->range_config__timeout_macrop_a_lo = 0x97;
+ /* Setup for 13ms default */
+ ptiming->range_config__timeout_macrop_b_hi = 0x00;
+ ptiming->range_config__timeout_macrop_b_lo = 0xB1;
+
+ ptiming->system__intermeasurement_period = 0x00000600;
+ pdynamic->system__seed_config =
+ ptuning_parms->tp_timed_seed_cfg;
+
+ /* System control */
+
+ /* Configure Timed/Psuedo-solo mode */
+ psystem->system__mode_start =
+ VL53L1_DEVICESCHEDULERMODE_PSEUDO_SOLO | \
+ VL53L1_DEVICEREADOUTMODE_SINGLE_SD | \
+ VL53L1_DEVICEMEASUREMENTMODE_TIMED;
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+/* Start Patch_LowPowerAutoMode */
+VL53L1_Error VL53L1_preset_mode_low_power_auto_ranging(
+
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms,
+ VL53L1_low_power_auto_data_t *plpadata)
+{
+ /*
+ * Initializes static and dynamic data structures for
+ * device preset mode
+ *
+ * VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_MEDIUM_RANGE
+ *
+ * - pseudo-solo
+ * - single sigma delta
+ * - timed
+ * - special low power auto mode for Presence application
+ *
+ * PLEASE NOTE THE SETTINGS BELOW ARE PROVISIONAL AND WILL CHANGE!
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Call standard ranging configuration */
+
+ status = VL53L1_preset_mode_timed_ranging(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+
+ /* now setup the low power auto mode */
+
+ if (status == VL53L1_ERROR_NONE) {
+ status = VL53L1_config_low_power_auto_mode(
+ pgeneral,
+ pdynamic,
+ plpadata
+ );
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+VL53L1_Error VL53L1_preset_mode_low_power_auto_short_ranging(
+
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms,
+ VL53L1_low_power_auto_data_t *plpadata)
+{
+ /*
+ * Initializes static and dynamic data structures for
+ * device preset mode
+ *
+ * VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_SHORT_RANGE
+ *
+ * - pseudo-solo
+ * - single sigma delta
+ * - timed
+ * - special low power auto mode for Presence application
+ *
+ * PLEASE NOTE THE SETTINGS BELOW ARE PROVISIONAL AND WILL CHANGE!
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Call standard ranging configuration */
+
+ status = VL53L1_preset_mode_timed_ranging_short_range(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+
+ /* now setup the low power auto mode */
+
+ if (status == VL53L1_ERROR_NONE) {
+ status = VL53L1_config_low_power_auto_mode(
+ pgeneral,
+ pdynamic,
+ plpadata
+ );
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+VL53L1_Error VL53L1_preset_mode_low_power_auto_long_ranging(
+
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms,
+ VL53L1_low_power_auto_data_t *plpadata)
+{
+ /*
+ * Initializes static and dynamic data structures for
+ * device preset mode
+ *
+ * VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_LONG_RANGE
+ *
+ * - pseudo-solo
+ * - single sigma delta
+ * - timed
+ * - special low power auto mode for Presence application
+ *
+ * PLEASE NOTE THE SETTINGS BELOW ARE PROVISIONAL AND WILL CHANGE!
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Call standard ranging configuration */
+
+ status = VL53L1_preset_mode_timed_ranging_long_range(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+
+ /* now setup the low power auto mode */
+
+ if (status == VL53L1_ERROR_NONE) {
+ status = VL53L1_config_low_power_auto_mode(
+ pgeneral,
+ pdynamic,
+ plpadata
+ );
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+/* End Patch_LowPowerAutoMode */
+
+VL53L1_Error VL53L1_preset_mode_singleshot_ranging(
+
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms)
+{
+ /*
+ * Initializes static and dynamic data structures for device preset mode
+ * VL53L1_DEVICEPRESETMODE_TIMED_RANGING
+ *
+ * - pseudo-solo
+ * - single sigma delta
+ * - timed
+ *
+ * PLEASE NOTE THE SETTINGS BELOW AT PROVISIONAL AND WILL CHANGE!
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Call standard ranging configuration */
+
+ status = VL53L1_preset_mode_standard_ranging(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+
+ /* now override standard ranging specific registers */
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ /* Dynamic Configuration */
+
+ /* Disable GPH */
+ pdynamic->system__grouped_parameter_hold = 0x00;
+
+ /* Timing Configuration */
+
+ /* Re-Configure timing budget default for 13ms */
+ ptiming->range_config__timeout_macrop_a_hi = 0x00;
+ ptiming->range_config__timeout_macrop_a_lo = 0xB1;
+ /* Setup for 13ms default */
+ ptiming->range_config__timeout_macrop_b_hi = 0x00;
+ ptiming->range_config__timeout_macrop_b_lo = 0xD4;
+
+ pdynamic->system__seed_config =
+ ptuning_parms->tp_timed_seed_cfg;
+
+ /* System control */
+
+ /* Configure Timed/Psuedo-solo mode */
+ psystem->system__mode_start = \
+ VL53L1_DEVICESCHEDULERMODE_PSEUDO_SOLO | \
+ VL53L1_DEVICEREADOUTMODE_SINGLE_SD | \
+ VL53L1_DEVICEMEASUREMENTMODE_SINGLESHOT;
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_preset_mode_olt(
+ VL53L1_static_config_t *pstatic,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_system_control_t *psystem,
+ VL53L1_tuning_parm_storage_t *ptuning_parms)
+{
+ /**
+ * Initializes static and dynamic data structures for device preset mode
+ * VL53L1_DEVICEPRESETMODE_OLT
+ *
+ * PLEASE NOTE THE SETTINGS BELOW AT PROVISIONAL AND WILL CHANGE!
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* Call standard ranging configuration */
+
+ status = VL53L1_preset_mode_standard_ranging(
+ pstatic,
+ pgeneral,
+ ptiming,
+ pdynamic,
+ psystem,
+ ptuning_parms);
+
+ /* now override OLT specific registers */
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ /* Disables requirement for host handshake */
+ psystem->system__stream_count_ctrl = 0x01;
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
diff --git a/src/lib/vl53l1/core/src/vl53l1_api_strings.c b/src/lib/vl53l1/core/src/vl53l1_api_strings.c
new file mode 100644
index 0000000000..6871826461
--- /dev/null
+++ b/src/lib/vl53l1/core/src/vl53l1_api_strings.c
@@ -0,0 +1,267 @@
+/*
+* Copyright (c) 2017, STMicroelectronics - All Rights Reserved
+*
+* This file is part of VL53L1 Core and is dual licensed, either
+* 'STMicroelectronics Proprietary license'
+* or 'BSD 3-clause "New" or "Revised" License' , at your option.
+*
+********************************************************************************
+*
+* 'STMicroelectronics Proprietary license'
+*
+********************************************************************************
+*
+* License terms: STMicroelectronics Proprietary in accordance with licensing
+* terms at www.st.com/sla0044
+*
+* STMicroelectronics confidential
+* Reproduction and Communication of this document is strictly prohibited unless
+* specifically authorized in writing by STMicroelectronics.
+*
+*
+********************************************************************************
+*
+* Alternatively, VL53L1 Core may be distributed under the terms of
+* 'BSD 3-clause "New" or "Revised" License', in which case the following
+* provisions apply instead of the ones
+* mentioned above :
+*
+********************************************************************************
+*
+* License terms: BSD 3-clause "New" or "Revised" License.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions are met:
+*
+* 1. Redistributions of source code must retain the above copyright notice, this
+* list of conditions and the following disclaimer.
+*
+* 2. Redistributions in binary form must reproduce the above copyright notice,
+* this list of conditions and the following disclaimer in the documentation
+* and/or other materials provided with the distribution.
+*
+* 3. Neither the name of the copyright holder nor the names of its contributors
+* may be used to endorse or promote products derived from this software
+* without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*
+********************************************************************************
+*
+*/
+
+/**
+ * @file vl53l1_api_strings.c
+ * @brief VL53L1 API functions for decoding error codes to a text string
+ */
+
+#include "vl53l1_api_core.h"
+#include "vl53l1_api_strings.h"
+#include "vl53l1_error_codes.h"
+#include "vl53l1_error_strings.h"
+
+#define LOG_FUNCTION_START(fmt, ...) \
+ _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_API, fmt, ##__VA_ARGS__)
+#define LOG_FUNCTION_END(status, ...) \
+ _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_API, status, ##__VA_ARGS__)
+#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
+ _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_API, status, fmt, \
+ ##__VA_ARGS__)
+
+
+VL53L1_Error VL53L1_get_range_status_string(
+ uint8_t RangeStatus,
+ char *pRangeStatusString)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+#ifdef VL53L1_USE_EMPTY_STRING
+ VL53L1_COPYSTRING(pRangeStatusString, "");
+#else
+ switch (RangeStatus) {
+ case 0:
+ VL53L1_COPYSTRING(pRangeStatusString,
+ VL53L1_STRING_RANGESTATUS_RANGEVALID);
+ break;
+ case 1:
+ VL53L1_COPYSTRING(pRangeStatusString,
+ VL53L1_STRING_RANGESTATUS_SIGMA);
+ break;
+ case 2:
+ VL53L1_COPYSTRING(pRangeStatusString,
+ VL53L1_STRING_RANGESTATUS_SIGNAL);
+ break;
+ case 3:
+ VL53L1_COPYSTRING(pRangeStatusString,
+ VL53L1_STRING_RANGESTATUS_MINRANGE);
+ break;
+ case 4:
+ VL53L1_COPYSTRING(pRangeStatusString,
+ VL53L1_STRING_RANGESTATUS_PHASE);
+ break;
+ case 5:
+ VL53L1_COPYSTRING(pRangeStatusString,
+ VL53L1_STRING_RANGESTATUS_HW);
+ break;
+
+ default: /**/
+ VL53L1_COPYSTRING(pRangeStatusString,
+ VL53L1_STRING_RANGESTATUS_NONE);
+ }
+#endif
+
+ LOG_FUNCTION_END(status);
+ return status;
+}
+
+
+VL53L1_Error VL53L1_get_pal_state_string(
+ VL53L1_State PalStateCode,
+ char *pPalStateString)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+#ifdef VL53L1_USE_EMPTY_STRING
+ VL53L1_COPYSTRING(pPalStateString, "");
+#else
+ switch (PalStateCode) {
+ case VL53L1_STATE_POWERDOWN:
+ VL53L1_COPYSTRING(pPalStateString,
+ VL53L1_STRING_STATE_POWERDOWN);
+ break;
+ case VL53L1_STATE_WAIT_STATICINIT:
+ VL53L1_COPYSTRING(pPalStateString,
+ VL53L1_STRING_STATE_WAIT_STATICINIT);
+ break;
+ case VL53L1_STATE_STANDBY:
+ VL53L1_COPYSTRING(pPalStateString,
+ VL53L1_STRING_STATE_STANDBY);
+ break;
+ case VL53L1_STATE_IDLE:
+ VL53L1_COPYSTRING(pPalStateString,
+ VL53L1_STRING_STATE_IDLE);
+ break;
+ case VL53L1_STATE_RUNNING:
+ VL53L1_COPYSTRING(pPalStateString,
+ VL53L1_STRING_STATE_RUNNING);
+ break;
+ case VL53L1_STATE_RESET:
+ VL53L1_COPYSTRING(pPalStateString,
+ VL53L1_STRING_STATE_RESET);
+ break;
+ case VL53L1_STATE_UNKNOWN:
+ VL53L1_COPYSTRING(pPalStateString,
+ VL53L1_STRING_STATE_UNKNOWN);
+ break;
+ case VL53L1_STATE_ERROR:
+ VL53L1_COPYSTRING(pPalStateString,
+ VL53L1_STRING_STATE_ERROR);
+ break;
+
+ default:
+ VL53L1_COPYSTRING(pPalStateString,
+ VL53L1_STRING_STATE_UNKNOWN);
+ }
+#endif
+
+ LOG_FUNCTION_END(status);
+ return status;
+}
+
+VL53L1_Error VL53L1_get_sequence_steps_info(
+ VL53L1_SequenceStepId SequenceStepId,
+ char *pSequenceStepsString)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+#ifdef VL53L1_USE_EMPTY_STRING
+ VL53L1_COPYSTRING(pSequenceStepsString, "");
+#else
+ switch (SequenceStepId) {
+ case VL53L1_SEQUENCESTEP_VHV:
+ VL53L1_COPYSTRING(pSequenceStepsString,
+ VL53L1_STRING_SEQUENCESTEP_VHV);
+ break;
+ case VL53L1_SEQUENCESTEP_PHASECAL:
+ VL53L1_COPYSTRING(pSequenceStepsString,
+ VL53L1_STRING_SEQUENCESTEP_PHASECAL);
+ break;
+ case VL53L1_SEQUENCESTEP_REFPHASE:
+ VL53L1_COPYSTRING(pSequenceStepsString,
+ VL53L1_STRING_SEQUENCESTEP_DSS1);
+ break;
+ case VL53L1_SEQUENCESTEP_DSS1:
+ VL53L1_COPYSTRING(pSequenceStepsString,
+ VL53L1_STRING_SEQUENCESTEP_DSS1);
+ break;
+ case VL53L1_SEQUENCESTEP_DSS2:
+ VL53L1_COPYSTRING(pSequenceStepsString,
+ VL53L1_STRING_SEQUENCESTEP_DSS2);
+ break;
+ case VL53L1_SEQUENCESTEP_MM1:
+ VL53L1_COPYSTRING(pSequenceStepsString,
+ VL53L1_STRING_SEQUENCESTEP_MM1);
+ break;
+ case VL53L1_SEQUENCESTEP_MM2:
+ VL53L1_COPYSTRING(pSequenceStepsString,
+ VL53L1_STRING_SEQUENCESTEP_MM2);
+ break;
+ case VL53L1_SEQUENCESTEP_RANGE:
+ VL53L1_COPYSTRING(pSequenceStepsString,
+ VL53L1_STRING_SEQUENCESTEP_RANGE);
+ break;
+ default:
+ Status = VL53L1_ERROR_INVALID_PARAMS;
+ }
+#endif
+
+ LOG_FUNCTION_END(Status);
+
+ return Status;
+}
+
+VL53L1_Error VL53L1_get_limit_check_info(uint16_t LimitCheckId,
+ char *pLimitCheckString)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+#ifdef VL53L1_USE_EMPTY_STRING
+ VL53L1_COPYSTRING(pLimitCheckString, "");
+#else
+ switch (LimitCheckId) {
+ case VL53L1_CHECKENABLE_SIGMA_FINAL_RANGE:
+ VL53L1_COPYSTRING(pLimitCheckString,
+ VL53L1_STRING_CHECKENABLE_SIGMA_FINAL_RANGE);
+ break;
+ case VL53L1_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE:
+ VL53L1_COPYSTRING(pLimitCheckString,
+ VL53L1_STRING_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE);
+ break;
+ default:
+ VL53L1_COPYSTRING(pLimitCheckString,
+ VL53L1_STRING_UNKNOW_ERROR_CODE);
+ }
+#endif
+
+ LOG_FUNCTION_END(Status);
+ return Status;
+}
+
diff --git a/src/lib/vl53l1/core/src/vl53l1_core.c b/src/lib/vl53l1/core/src/vl53l1_core.c
new file mode 100644
index 0000000000..3424d5c30b
--- /dev/null
+++ b/src/lib/vl53l1/core/src/vl53l1_core.c
@@ -0,0 +1,2319 @@
+/*******************************************************************************
+ Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ ******************************************************************************/
+
+/**
+ * @file vl53l1_core.c
+ *
+ * @brief EwokPlus25 core function definition
+ */
+
+#include "vl53l1_ll_def.h"
+#include "vl53l1_ll_device.h"
+#include "vl53l1_register_map.h"
+#include "vl53l1_register_funcs.h"
+#include "vl53l1_register_settings.h"
+#include "vl53l1_api_preset_modes.h"
+#include "vl53l1_core.h"
+
+#include "../../../../drivers/interface/vl53l1x.h"
+#include "vl53l1_tuning_parm_defaults.h"
+
+#ifdef VL53L1_LOGGING
+#include "vl53l1_api_debug.h"
+#include "vl53l1_debug.h"
+#include "vl53l1_register_debug.h"
+#endif
+
+#define LOG_FUNCTION_START(fmt, ...) \
+ _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_CORE, fmt, ##__VA_ARGS__)
+#define LOG_FUNCTION_END(status, ...) \
+ _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_CORE, status, ##__VA_ARGS__)
+#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
+ _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_CORE, \
+ status, fmt, ##__VA_ARGS__)
+
+#define trace_print(level, ...) \
+ _LOG_TRACE_PRINT(VL53L1_TRACE_MODULE_CORE, \
+ level, VL53L1_TRACE_FUNCTION_NONE, ##__VA_ARGS__)
+
+
+void VL53L1_init_version(
+ VL53L1_DEV Dev)
+{
+ /**
+ * Initialise version structure
+ */
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ pdev->version.ll_major = VL53L1_LL_API_IMPLEMENTATION_VER_MAJOR;
+ pdev->version.ll_minor = VL53L1_LL_API_IMPLEMENTATION_VER_MINOR;
+ pdev->version.ll_build = VL53L1_LL_API_IMPLEMENTATION_VER_SUB;
+ pdev->version.ll_revision = VL53L1_LL_API_IMPLEMENTATION_VER_REVISION;
+}
+
+
+void VL53L1_init_ll_driver_state(
+ VL53L1_DEV Dev,
+ VL53L1_DeviceState device_state)
+{
+ /**
+ * Initialise LL Driver state variables
+ */
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+ VL53L1_ll_driver_state_t *pstate = &(pdev->ll_state);
+
+ pstate->cfg_device_state = device_state;
+ pstate->cfg_stream_count = 0;
+ pstate->cfg_gph_id = VL53L1_GROUPEDPARAMETERHOLD_ID_MASK;
+ pstate->cfg_timing_status = 0;
+
+ pstate->rd_device_state = device_state;
+ pstate->rd_stream_count = 0;
+ pstate->rd_gph_id = VL53L1_GROUPEDPARAMETERHOLD_ID_MASK;
+ pstate->rd_timing_status = 0;
+
+}
+
+
+VL53L1_Error VL53L1_update_ll_driver_rd_state(
+ VL53L1_DEV Dev)
+{
+ /**
+ * State machine for read device state
+ *
+ * VL53L1_DEVICESTATE_SW_STANDBY
+ * VL53L1_DEVICESTATE_RANGING_WAIT_GPH_SYNC
+ * VL53L1_DEVICESTATE_RANGING_GATHER_DATA
+ * VL53L1_DEVICESTATE_RANGING_OUTPUT_DATA
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+ VL53L1_ll_driver_state_t *pstate = &(pdev->ll_state);
+
+ /* if top bits of mode start reset are zero then in standby state */
+
+ LOG_FUNCTION_START("");
+
+#ifdef VL53L1_LOGGING
+ VL53L1_print_ll_driver_state(pstate);
+#endif
+
+ if ((pdev->sys_ctrl.system__mode_start &
+ VL53L1_DEVICEMEASUREMENTMODE_MODE_MASK) == 0x00) {
+
+ pstate->rd_device_state = VL53L1_DEVICESTATE_SW_STANDBY;
+ pstate->rd_stream_count = 0;
+ pstate->rd_gph_id = VL53L1_GROUPEDPARAMETERHOLD_ID_MASK;
+ pstate->rd_timing_status = 0;
+
+ } else {
+
+ /*
+ * implement read stream count
+ */
+
+ if (pstate->rd_stream_count == 0xFF) {
+ pstate->rd_stream_count = 0x80;
+ } else {
+ pstate->rd_stream_count++;
+ }
+
+
+ /*
+ * Toggle grouped parameter hold ID
+ */
+
+ pstate->rd_gph_id ^= VL53L1_GROUPEDPARAMETERHOLD_ID_MASK;
+
+ /* Ok now ranging */
+
+ switch (pstate->rd_device_state) {
+
+ case VL53L1_DEVICESTATE_SW_STANDBY:
+
+ if ((pdev->dyn_cfg.system__grouped_parameter_hold &
+ VL53L1_GROUPEDPARAMETERHOLD_ID_MASK) > 0) {
+ pstate->rd_device_state =
+ VL53L1_DEVICESTATE_RANGING_WAIT_GPH_SYNC;
+ } else {
+ pstate->rd_device_state =
+ VL53L1_DEVICESTATE_RANGING_OUTPUT_DATA;
+ }
+
+ pstate->rd_stream_count = 0;
+ pstate->rd_timing_status = 0;
+
+ break;
+
+ case VL53L1_DEVICESTATE_RANGING_WAIT_GPH_SYNC:
+
+ pstate->rd_stream_count = 0;
+ pstate->rd_device_state =
+ VL53L1_DEVICESTATE_RANGING_OUTPUT_DATA;
+
+ break;
+
+ case VL53L1_DEVICESTATE_RANGING_GATHER_DATA:
+
+ pstate->rd_device_state =
+ VL53L1_DEVICESTATE_RANGING_OUTPUT_DATA;
+
+ break;
+
+ case VL53L1_DEVICESTATE_RANGING_OUTPUT_DATA:
+
+ pstate->rd_timing_status ^= 0x01;
+
+ pstate->rd_device_state =
+ VL53L1_DEVICESTATE_RANGING_OUTPUT_DATA;
+
+ break;
+
+ default:
+
+ pstate->rd_device_state =
+ VL53L1_DEVICESTATE_SW_STANDBY;
+ pstate->rd_stream_count = 0;
+ pstate->rd_gph_id = VL53L1_GROUPEDPARAMETERHOLD_ID_MASK;
+ pstate->rd_timing_status = 0;
+
+ break;
+ }
+ }
+
+#ifdef VL53L1_LOGGING
+ VL53L1_print_ll_driver_state(pstate);
+#endif
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_check_ll_driver_rd_state(
+ VL53L1_DEV Dev)
+{
+ /*
+ * Checks if the LL Driver Read state and expected stream count
+ * matches the state and stream count received from the device
+ *
+ * Check is only use in back to back mode
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ VL53L1_ll_driver_state_t *pstate = &(pdev->ll_state);
+ VL53L1_system_results_t *psys_results = &(pdev->sys_results);
+
+ uint8_t device_range_status = 0;
+ uint8_t device_stream_count = 0;
+ uint8_t device_gph_id = 0;
+
+ LOG_FUNCTION_START("");
+
+#ifdef VL53L1_LOGGING
+ VL53L1_print_ll_driver_state(pstate);
+#endif
+
+ device_range_status =
+ psys_results->result__range_status &
+ VL53L1_RANGE_STATUS__RANGE_STATUS_MASK;
+
+ device_stream_count = psys_results->result__stream_count;
+
+ /* load the correct GPH ID */
+ device_gph_id = (psys_results->result__interrupt_status &
+ VL53L1_INTERRUPT_STATUS__GPH_ID_INT_STATUS_MASK) >> 4;
+
+ /* only apply checks in back to back mode */
+
+ if ((pdev->sys_ctrl.system__mode_start &
+ VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK) ==
+ VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK) {
+
+ /* if read state is wait for GPH sync interrupt then check the
+ * device returns a GPH range status value otherwise check that
+ * the stream count matches
+ *
+ * In theory the stream count should zero for the GPH interrupt
+ * but that is not the case after at abort ....
+ */
+
+ if (pstate->rd_device_state ==
+ VL53L1_DEVICESTATE_RANGING_WAIT_GPH_SYNC) {
+
+ if (device_range_status !=
+ VL53L1_DEVICEERROR_GPHSTREAMCOUNT0READY) {
+ status = VL53L1_ERROR_GPH_SYNC_CHECK_FAIL;
+ }
+ } else {
+ if (pstate->rd_stream_count != device_stream_count) {
+ status = VL53L1_ERROR_STREAM_COUNT_CHECK_FAIL;
+ }
+
+ /*
+ * Check Read state GPH ID
+ */
+
+ if (pstate->rd_gph_id != device_gph_id) {
+ status = VL53L1_ERROR_GPH_ID_CHECK_FAIL;
+#ifdef VL53L1_LOGGING
+ trace_print(VL53L1_TRACE_LEVEL_ALL,
+ " RDSTATECHECK: Check failed: rd_gph_id: %d, device_gph_id: %d\n",
+ pstate->rd_gph_id,
+ device_gph_id);
+#endif
+ } else {
+#ifdef VL53L1_LOGGING
+ trace_print(VL53L1_TRACE_LEVEL_ALL,
+ " RDSTATECHECK: Check passed: rd_gph_id: %d, device_gph_id: %d\n",
+ pstate->rd_gph_id,
+ device_gph_id);
+#endif
+ }
+
+ } /* else (not in WAIT_GPH_SYNC) */
+
+ } /* if back to back */
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_update_ll_driver_cfg_state(
+ VL53L1_DEV Dev)
+{
+ /**
+ * State machine for configuration device state
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev =
+ VL53L1DevStructGetLLDriverHandle(Dev);
+
+ VL53L1_ll_driver_state_t *pstate = &(pdev->ll_state);
+
+ LOG_FUNCTION_START("");
+
+#ifdef VL53L1_LOGGING
+ VL53L1_print_ll_driver_state(pstate);
+#endif
+
+ /* if top bits of mode start reset are zero then in standby state */
+
+ if ((pdev->sys_ctrl.system__mode_start &
+ VL53L1_DEVICEMEASUREMENTMODE_MODE_MASK) == 0x00) {
+
+ pstate->cfg_device_state = VL53L1_DEVICESTATE_SW_STANDBY;
+ pstate->cfg_stream_count = 0;
+ pstate->cfg_gph_id = VL53L1_GROUPEDPARAMETERHOLD_ID_MASK;
+ pstate->cfg_timing_status = 0;
+
+ } else {
+
+ /*
+ * implement configuration stream count
+ */
+
+ if (pstate->cfg_stream_count == 0xFF) {
+ pstate->cfg_stream_count = 0x80;
+ } else {
+ pstate->cfg_stream_count++;
+ }
+
+ /*
+ * Toggle grouped parameter hold ID
+ */
+
+ pstate->cfg_gph_id ^= VL53L1_GROUPEDPARAMETERHOLD_ID_MASK;
+
+ /*
+ * Implement configuration state machine
+ */
+
+ switch (pstate->cfg_device_state) {
+
+ case VL53L1_DEVICESTATE_SW_STANDBY:
+
+ pstate->cfg_timing_status ^= 0x01;
+ pstate->cfg_stream_count = 1;
+
+ pstate->cfg_device_state = VL53L1_DEVICESTATE_RANGING_DSS_AUTO;
+ break;
+
+ case VL53L1_DEVICESTATE_RANGING_DSS_AUTO:
+
+ pstate->cfg_timing_status ^= 0x01;
+
+ break;
+
+ default:
+
+ pstate->cfg_device_state = VL53L1_DEVICESTATE_SW_STANDBY;
+ pstate->cfg_stream_count = 0;
+ pstate->cfg_gph_id = VL53L1_GROUPEDPARAMETERHOLD_ID_MASK;
+ pstate->cfg_timing_status = 0;
+
+ break;
+ }
+ }
+
+#ifdef VL53L1_LOGGING
+ VL53L1_print_ll_driver_state(pstate);
+#endif
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+void VL53L1_copy_rtn_good_spads_to_buffer(
+ VL53L1_nvm_copy_data_t *pdata,
+ uint8_t *pbuffer)
+{
+ /*
+ * Convenience function to copy return SPAD enables to buffer
+ */
+
+ *(pbuffer + 0) = pdata->global_config__spad_enables_rtn_0;
+ *(pbuffer + 1) = pdata->global_config__spad_enables_rtn_1;
+ *(pbuffer + 2) = pdata->global_config__spad_enables_rtn_2;
+ *(pbuffer + 3) = pdata->global_config__spad_enables_rtn_3;
+ *(pbuffer + 4) = pdata->global_config__spad_enables_rtn_4;
+ *(pbuffer + 5) = pdata->global_config__spad_enables_rtn_5;
+ *(pbuffer + 6) = pdata->global_config__spad_enables_rtn_6;
+ *(pbuffer + 7) = pdata->global_config__spad_enables_rtn_7;
+ *(pbuffer + 8) = pdata->global_config__spad_enables_rtn_8;
+ *(pbuffer + 9) = pdata->global_config__spad_enables_rtn_9;
+ *(pbuffer + 10) = pdata->global_config__spad_enables_rtn_10;
+ *(pbuffer + 11) = pdata->global_config__spad_enables_rtn_11;
+ *(pbuffer + 12) = pdata->global_config__spad_enables_rtn_12;
+ *(pbuffer + 13) = pdata->global_config__spad_enables_rtn_13;
+ *(pbuffer + 14) = pdata->global_config__spad_enables_rtn_14;
+ *(pbuffer + 15) = pdata->global_config__spad_enables_rtn_15;
+ *(pbuffer + 16) = pdata->global_config__spad_enables_rtn_16;
+ *(pbuffer + 17) = pdata->global_config__spad_enables_rtn_17;
+ *(pbuffer + 18) = pdata->global_config__spad_enables_rtn_18;
+ *(pbuffer + 19) = pdata->global_config__spad_enables_rtn_19;
+ *(pbuffer + 20) = pdata->global_config__spad_enables_rtn_20;
+ *(pbuffer + 21) = pdata->global_config__spad_enables_rtn_21;
+ *(pbuffer + 22) = pdata->global_config__spad_enables_rtn_22;
+ *(pbuffer + 23) = pdata->global_config__spad_enables_rtn_23;
+ *(pbuffer + 24) = pdata->global_config__spad_enables_rtn_24;
+ *(pbuffer + 25) = pdata->global_config__spad_enables_rtn_25;
+ *(pbuffer + 26) = pdata->global_config__spad_enables_rtn_26;
+ *(pbuffer + 27) = pdata->global_config__spad_enables_rtn_27;
+ *(pbuffer + 28) = pdata->global_config__spad_enables_rtn_28;
+ *(pbuffer + 29) = pdata->global_config__spad_enables_rtn_29;
+ *(pbuffer + 30) = pdata->global_config__spad_enables_rtn_30;
+ *(pbuffer + 31) = pdata->global_config__spad_enables_rtn_31;
+}
+
+
+void VL53L1_init_system_results(
+ VL53L1_system_results_t *pdata)
+{
+ /*
+ * Initialises the system results to all 0xFF just like the
+ * device firmware does a the start of a range
+ */
+
+ pdata->result__interrupt_status = 0xFF;
+ pdata->result__range_status = 0xFF;
+ pdata->result__report_status = 0xFF;
+ pdata->result__stream_count = 0xFF;
+
+ pdata->result__dss_actual_effective_spads_sd0 = 0xFFFF;
+ pdata->result__peak_signal_count_rate_mcps_sd0 = 0xFFFF;
+ pdata->result__ambient_count_rate_mcps_sd0 = 0xFFFF;
+ pdata->result__sigma_sd0 = 0xFFFF;
+ pdata->result__phase_sd0 = 0xFFFF;
+ pdata->result__final_crosstalk_corrected_range_mm_sd0 = 0xFFFF;
+ pdata->result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0 =
+ 0xFFFF;
+ pdata->result__mm_inner_actual_effective_spads_sd0 = 0xFFFF;
+ pdata->result__mm_outer_actual_effective_spads_sd0 = 0xFFFF;
+ pdata->result__avg_signal_count_rate_mcps_sd0 = 0xFFFF;
+
+ pdata->result__dss_actual_effective_spads_sd1 = 0xFFFF;
+ pdata->result__peak_signal_count_rate_mcps_sd1 = 0xFFFF;
+ pdata->result__ambient_count_rate_mcps_sd1 = 0xFFFF;
+ pdata->result__sigma_sd1 = 0xFFFF;
+ pdata->result__phase_sd1 = 0xFFFF;
+ pdata->result__final_crosstalk_corrected_range_mm_sd1 = 0xFFFF;
+ pdata->result__spare_0_sd1 = 0xFFFF;
+ pdata->result__spare_1_sd1 = 0xFFFF;
+ pdata->result__spare_2_sd1 = 0xFFFF;
+ pdata->result__spare_3_sd1 = 0xFF;
+
+}
+
+
+void VL53L1_i2c_encode_uint16_t(
+ uint16_t ip_value,
+ uint16_t count,
+ uint8_t *pbuffer)
+{
+ /*
+ * Encodes a uint16_t register value into an I2C write buffer
+ * MS byte first order (as per I2C register map.
+ */
+
+ uint16_t i = 0;
+ uint16_t data = 0;
+
+ data = ip_value;
+
+ for (i = 0; i < count ; i++) {
+ pbuffer[count-i-1] = (uint8_t)(data & 0x00FF);
+ data = data >> 8;
+ }
+}
+
+uint16_t VL53L1_i2c_decode_uint16_t(
+ uint16_t count,
+ uint8_t *pbuffer)
+{
+ /*
+ * Decodes a uint16_t from the input I2C read buffer
+ * (MS byte first order)
+ */
+
+ uint16_t value = 0x00;
+
+ while (count-- > 0) {
+ value = (value << 8) | (uint16_t)*pbuffer++;
+ }
+
+ return value;
+}
+
+
+void VL53L1_i2c_encode_int16_t(
+ int16_t ip_value,
+ uint16_t count,
+ uint8_t *pbuffer)
+{
+ /*
+ * Encodes a int16_t register value into an I2C write buffer
+ * MS byte first order (as per I2C register map.
+ */
+
+ uint16_t i = 0;
+ int16_t data = 0;
+
+ data = ip_value;
+
+ for (i = 0; i < count ; i++) {
+ pbuffer[count-i-1] = (uint8_t)(data & 0x00FF);
+ data = data >> 8;
+ }
+}
+
+int16_t VL53L1_i2c_decode_int16_t(
+ uint16_t count,
+ uint8_t *pbuffer)
+{
+ /*
+ * Decodes a int16_t from the input I2C read buffer
+ * (MS byte first order)
+ */
+
+ int16_t value = 0x00;
+
+ /* implement sign extension */
+ if (*pbuffer >= 0x80) {
+ value = 0xFFFF;
+ }
+
+ while (count-- > 0) {
+ value = (value << 8) | (int16_t)*pbuffer++;
+ }
+
+ return value;
+}
+
+void VL53L1_i2c_encode_uint32_t(
+ uint32_t ip_value,
+ uint16_t count,
+ uint8_t *pbuffer)
+{
+ /*
+ * Encodes a uint32_t register value into an I2C write buffer
+ * MS byte first order (as per I2C register map.
+ */
+
+ uint16_t i = 0;
+ uint32_t data = 0;
+
+ data = ip_value;
+
+ for (i = 0; i < count ; i++) {
+ pbuffer[count-i-1] = (uint8_t)(data & 0x00FF);
+ data = data >> 8;
+ }
+}
+
+uint32_t VL53L1_i2c_decode_uint32_t(
+ uint16_t count,
+ uint8_t *pbuffer)
+{
+ /*
+ * Decodes a uint32_t from the input I2C read buffer
+ * (MS byte first order)
+ */
+
+ uint32_t value = 0x00;
+
+ while (count-- > 0) {
+ value = (value << 8) | (uint32_t)*pbuffer++;
+ }
+
+ return value;
+}
+
+
+uint32_t VL53L1_i2c_decode_with_mask(
+ uint16_t count,
+ uint8_t *pbuffer,
+ uint32_t bit_mask,
+ uint32_t down_shift,
+ uint32_t offset)
+{
+ /*
+ * Decodes an integer from the input I2C read buffer
+ * (MS byte first order)
+ */
+
+ uint32_t value = 0x00;
+
+ /* extract from buffer */
+ while (count-- > 0) {
+ value = (value << 8) | (uint32_t)*pbuffer++;
+ }
+
+ /* Apply bit mask and down shift */
+ value = value & bit_mask;
+ if (down_shift > 0) {
+ value = value >> down_shift;
+ }
+
+ /* add offset */
+ value = value + offset;
+
+ return value;
+}
+
+
+void VL53L1_i2c_encode_int32_t(
+ int32_t ip_value,
+ uint16_t count,
+ uint8_t *pbuffer)
+{
+ /*
+ * Encodes a int32_t register value into an I2C write buffer
+ * MS byte first order (as per I2C register map.
+ */
+
+ uint16_t i = 0;
+ int32_t data = 0;
+
+ data = ip_value;
+
+ for (i = 0; i < count ; i++) {
+ pbuffer[count-i-1] = (uint8_t)(data & 0x00FF);
+ data = data >> 8;
+ }
+}
+
+int32_t VL53L1_i2c_decode_int32_t(
+ uint16_t count,
+ uint8_t *pbuffer)
+{
+ /*
+ * Decodes a int32_t from the input I2C read buffer
+ * (MS byte first order)
+ */
+
+ int32_t value = 0x00;
+
+ /* implement sign extension */
+ if (*pbuffer >= 0x80) {
+ value = 0xFFFFFFFF;
+ }
+
+ while (count-- > 0) {
+ value = (value << 8) | (int32_t)*pbuffer++;
+ }
+
+ return value;
+}
+
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_start_test(
+ VL53L1_DEV Dev,
+ uint8_t test_mode__ctrl)
+{
+ /*
+ * Triggers the start of a test mode
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) { /*lint !e774 always true*/
+ status = VL53L1_WrByte(
+ Dev,
+ VL53L1_TEST_MODE__CTRL,
+ test_mode__ctrl);
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_set_firmware_enable_register(
+ VL53L1_DEV Dev,
+ uint8_t value)
+{
+ /*
+ * Set FIRMWARE__ENABLE register
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ pdev->sys_ctrl.firmware__enable = value;
+
+ status = VL53L1_WrByte(
+ Dev,
+ VL53L1_FIRMWARE__ENABLE,
+ pdev->sys_ctrl.firmware__enable);
+
+ return status;
+}
+
+VL53L1_Error VL53L1_enable_firmware(
+ VL53L1_DEV Dev)
+{
+ /*
+ * Enable firmware
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ status = VL53L1_set_firmware_enable_register(Dev, 0x01);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_disable_firmware(
+ VL53L1_DEV Dev)
+{
+ /*
+ * Disable firmware
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ status = VL53L1_set_firmware_enable_register(Dev, 0x00);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_powerforce_register(
+ VL53L1_DEV Dev,
+ uint8_t value)
+{
+ /*
+ * Set power force register
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ pdev->sys_ctrl.power_management__go1_power_force = value;
+
+ status = VL53L1_WrByte(
+ Dev,
+ VL53L1_POWER_MANAGEMENT__GO1_POWER_FORCE,
+ pdev->sys_ctrl.power_management__go1_power_force);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_enable_powerforce(
+ VL53L1_DEV Dev)
+{
+ /*
+ * Enable power force
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ status = VL53L1_set_powerforce_register(Dev, 0x01);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_disable_powerforce(
+ VL53L1_DEV Dev)
+{
+ /*
+ * Disable power force
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ status = VL53L1_set_powerforce_register(Dev, 0x00);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_clear_interrupt(
+ VL53L1_DEV Dev)
+{
+ /*
+ * Clear Ranging interrupt by writing to
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ pdev->sys_ctrl.system__interrupt_clear = VL53L1_CLEAR_RANGE_INT;
+
+ status = VL53L1_WrByte(
+ Dev,
+ VL53L1_SYSTEM__INTERRUPT_CLEAR,
+ pdev->sys_ctrl.system__interrupt_clear);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_force_shadow_stream_count_to_zero(
+ VL53L1_DEV Dev)
+{
+ /*
+ * Forces shadow stream count to zero
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ if (status == VL53L1_ERROR_NONE) { /*lint !e774 always true*/
+ status = VL53L1_disable_firmware(Dev);
+ }
+
+ if (status == VL53L1_ERROR_NONE) {
+ status = VL53L1_WrByte(
+ Dev,
+ VL53L1_SHADOW_RESULT__STREAM_COUNT,
+ 0x00);
+ }
+
+ if (status == VL53L1_ERROR_NONE) {
+ status = VL53L1_enable_firmware(Dev);
+ }
+
+ return status;
+}
+#endif
+
+uint32_t VL53L1_calc_macro_period_us(
+ uint16_t fast_osc_frequency,
+ uint8_t vcsel_period)
+{
+ /* Calculates macro period in [us] from the input fast oscillator
+ * frequency and VCSEL period
+ *
+ * Macro period fixed point format = unsigned 12.12
+ * Maximum supported macro period = 4095.9999 us
+ */
+
+ uint32_t pll_period_us = 0;
+ uint8_t vcsel_period_pclks = 0;
+ uint32_t macro_period_us = 0;
+
+ LOG_FUNCTION_START("");
+
+ /* Calculate PLL period in [us] from the fast_osc_frequency
+ * Fast osc frequency fixed point format = unsigned 4.12
+ */
+
+ pll_period_us = VL53L1_calc_pll_period_us(fast_osc_frequency);
+
+ /* VCSEL period
+ * - the real VCSEL period in PLL clocks = 2*(VCSEL_PERIOD+1)
+ */
+
+ vcsel_period_pclks = VL53L1_decode_vcsel_period(vcsel_period);
+
+ /* Macro period
+ * - PLL period [us] = 0.24 format
+ * - for 1.0 MHz fast oscillator freq
+ * - max PLL period = 1/64 (6-bits)
+ * - i.e only the lower 18-bits of PLL Period value are used
+ * - Macro period [vclks] = 2304 (12-bits)
+ *
+ * Max bits (24 - 6) + 12 = 30-bits usage
+ *
+ * Downshift by 6 before multiplying by the VCSEL Period
+ */
+
+ macro_period_us =
+ (uint32_t)VL53L1_MACRO_PERIOD_VCSEL_PERIODS *
+ pll_period_us;
+ macro_period_us = macro_period_us >> 6;
+
+ macro_period_us = macro_period_us * (uint32_t)vcsel_period_pclks;
+ macro_period_us = macro_period_us >> 6;
+
+#ifdef VL53L1_LOGGING
+ trace_print(VL53L1_TRACE_LEVEL_DEBUG,
+ " %-48s : %10u\n", "pll_period_us",
+ pll_period_us);
+ trace_print(VL53L1_TRACE_LEVEL_DEBUG,
+ " %-48s : %10u\n", "vcsel_period_pclks",
+ vcsel_period_pclks);
+ trace_print(VL53L1_TRACE_LEVEL_DEBUG,
+ " %-48s : %10u\n", "macro_period_us",
+ macro_period_us);
+#endif
+
+ LOG_FUNCTION_END(0);
+
+ return macro_period_us;
+}
+
+
+uint16_t VL53L1_calc_range_ignore_threshold(
+ uint32_t central_rate,
+ int16_t x_gradient,
+ int16_t y_gradient,
+ uint8_t rate_mult)
+{
+ /* Calculates Range Ignore Threshold rate per spad
+ * in Mcps - 3.13 format
+ *
+ * Calculates worst case xtalk rate per spad in array corner
+ * based on input central xtalk and x and y gradients
+ *
+ * Worst case rate = central rate + (8*(magnitude(xgrad)) +
+ * (8*(magnitude(ygrad)))
+ *
+ * Range ignore threshold rate is then multiplied by user input
+ * rate_mult (in 3.5 fractional format)
+ *
+ */
+
+ int32_t range_ignore_thresh_int = 0;
+ uint16_t range_ignore_thresh_kcps = 0;
+ int32_t central_rate_int = 0;
+ int16_t x_gradient_int = 0;
+ int16_t y_gradient_int = 0;
+
+ LOG_FUNCTION_START("");
+
+ /* Shift central_rate to .13 fractional for simple addition */
+
+ central_rate_int = ((int32_t)central_rate * (1 << 4)) / (1000);
+
+ if (x_gradient < 0) {
+ x_gradient_int = x_gradient * -1;
+ }
+
+ if (y_gradient < 0) {
+ y_gradient_int = y_gradient * -1;
+ }
+
+ /* Calculate full rate per spad - worst case from measured xtalk */
+ /* Generated here from .11 fractional kcps */
+ /* Additional factor of 4 applied to bring fractional precision to .13 */
+
+ range_ignore_thresh_int = (8 * x_gradient_int * 4) + (8 * y_gradient_int * 4);
+
+ /* Convert Kcps to Mcps */
+
+ range_ignore_thresh_int = range_ignore_thresh_int / 1000;
+
+ /* Combine with Central Rate - Mcps .13 format*/
+
+ range_ignore_thresh_int = range_ignore_thresh_int + central_rate_int;
+
+ /* Mult by user input */
+
+ range_ignore_thresh_int = (int32_t)rate_mult * range_ignore_thresh_int;
+
+ range_ignore_thresh_int = (range_ignore_thresh_int + (1<<4)) / (1<<5);
+
+ /* Finally clip and output in correct format */
+
+ if (range_ignore_thresh_int > 0xFFFF) {
+ range_ignore_thresh_kcps = 0xFFFF;
+ } else {
+ range_ignore_thresh_kcps = (uint16_t)range_ignore_thresh_int;
+ }
+
+#ifdef VL53L1_LOGGING
+ trace_print(VL53L1_TRACE_LEVEL_DEBUG,
+ " %-48s : %10u\n", "range_ignore_thresh_kcps",
+ range_ignore_thresh_kcps);
+#endif
+
+ LOG_FUNCTION_END(0);
+
+ return range_ignore_thresh_kcps;
+}
+
+
+uint32_t VL53L1_calc_timeout_mclks(
+ uint32_t timeout_us,
+ uint32_t macro_period_us)
+{
+ /* Calculates the timeout value in macro periods based on the input
+ * timeout period in milliseconds and the macro period in [us]
+ *
+ * Max timeout supported is 1000000 us (1 sec) -> 20-bits
+ * Max timeout in 20.12 format = 32-bits
+ *
+ * Macro period [us] = 12.12 format
+ */
+
+ uint32_t timeout_mclks = 0;
+
+ LOG_FUNCTION_START("");
+
+ timeout_mclks =
+ ((timeout_us << 12) + (macro_period_us>>1)) /
+ macro_period_us;
+
+ LOG_FUNCTION_END(0);
+
+ return timeout_mclks;
+}
+
+
+uint16_t VL53L1_calc_encoded_timeout(
+ uint32_t timeout_us,
+ uint32_t macro_period_us)
+{
+ /* Calculates the encoded timeout register value based on the input
+ * timeout period in milliseconds and the macro period in [us]
+ *
+ * Max timeout supported is 1000000 us (1 sec) -> 20-bits
+ * Max timeout in 20.12 format = 32-bits
+ *
+ * Macro period [us] = 12.12 format
+ */
+
+ uint32_t timeout_mclks = 0;
+ uint16_t timeout_encoded = 0;
+
+ LOG_FUNCTION_START("");
+
+ timeout_mclks =
+ VL53L1_calc_timeout_mclks(timeout_us, macro_period_us);
+
+ timeout_encoded =
+ VL53L1_encode_timeout(timeout_mclks);
+
+#ifdef VL53L1_LOGGING
+ trace_print(VL53L1_TRACE_LEVEL_DEBUG,
+ " %-48s : %10u (0x%04X)\n", "timeout_mclks",
+ timeout_mclks, timeout_mclks);
+ trace_print(VL53L1_TRACE_LEVEL_DEBUG,
+ " %-48s : %10u (0x%04X)\n", "timeout_encoded",
+ timeout_encoded, timeout_encoded);
+#endif
+
+ LOG_FUNCTION_END(0);
+
+ return timeout_encoded;
+}
+
+
+uint32_t VL53L1_calc_timeout_us(
+ uint32_t timeout_mclks,
+ uint32_t macro_period_us)
+{
+ /* Calculates the timeout in [us] based on the input
+ * encoded timeout and the macro period in [us]
+ *
+ * Max timeout supported is 1000000 us (1 sec) -> 20-bits
+ * Max timeout in 20.12 format = 32-bits
+ *
+ * Macro period [us] = 12.12 format
+ */
+
+ uint32_t timeout_us = 0;
+ uint64_t tmp = 0;
+
+ LOG_FUNCTION_START("");
+
+ tmp = (uint64_t)timeout_mclks * (uint64_t)macro_period_us;
+ tmp += 0x00800;
+ tmp = tmp >> 12;
+
+ timeout_us = (uint32_t)tmp;
+
+#ifdef VL53L1_LOGGING
+ trace_print(VL53L1_TRACE_LEVEL_DEBUG,
+ " %-48s : %10u (0x%04X)\n", "timeout_mclks",
+ timeout_mclks, timeout_mclks);
+
+ trace_print(VL53L1_TRACE_LEVEL_DEBUG,
+ " %-48s : %10u us\n", "timeout_us",
+ timeout_us, timeout_us);
+#endif
+
+ LOG_FUNCTION_END(0);
+
+ return timeout_us;
+}
+
+uint32_t VL53L1_calc_crosstalk_plane_offset_with_margin(
+ uint32_t plane_offset_kcps,
+ int16_t margin_offset_kcps)
+{
+ uint32_t plane_offset_with_margin = 0;
+ int32_t plane_offset_kcps_temp = 0;
+
+ LOG_FUNCTION_START("");
+
+ plane_offset_kcps_temp =
+ (int32_t)plane_offset_kcps +
+ (int32_t)margin_offset_kcps;
+
+ if (plane_offset_kcps_temp < 0) {
+ plane_offset_kcps_temp = 0;
+ } else {
+ if (plane_offset_kcps_temp > 0x3FFFF) {
+ plane_offset_kcps_temp = 0x3FFFF;
+ }
+ }
+
+ plane_offset_with_margin = (uint32_t) plane_offset_kcps_temp;
+
+ LOG_FUNCTION_END(0);
+
+ return plane_offset_with_margin;
+
+}
+
+uint32_t VL53L1_calc_decoded_timeout_us(
+ uint16_t timeout_encoded,
+ uint32_t macro_period_us)
+{
+ /* Calculates the timeout in [us] based on the input
+ * encoded timeout and the macro period in [us]
+ *
+ * Max timeout supported is 1000000 us (1 sec) -> 20-bits
+ * Max timeout in 20.12 format = 32-bits
+ *
+ * Macro period [us] = 12.12 format
+ */
+
+ uint32_t timeout_mclks = 0;
+ uint32_t timeout_us = 0;
+
+ LOG_FUNCTION_START("");
+
+ timeout_mclks =
+ VL53L1_decode_timeout(timeout_encoded);
+
+ timeout_us =
+ VL53L1_calc_timeout_us(timeout_mclks, macro_period_us);
+
+ LOG_FUNCTION_END(0);
+
+ return timeout_us;
+}
+
+
+uint16_t VL53L1_encode_timeout(uint32_t timeout_mclks)
+{
+ /*
+ * Encode timeout in macro periods in (LSByte * 2^MSByte) + 1 format
+ */
+
+ uint16_t encoded_timeout = 0;
+ uint32_t ls_byte = 0;
+ uint16_t ms_byte = 0;
+
+ if (timeout_mclks > 0) {
+ ls_byte = timeout_mclks - 1;
+
+ while ((ls_byte & 0xFFFFFF00) > 0) {
+ ls_byte = ls_byte >> 1;
+ ms_byte++;
+ }
+
+ encoded_timeout = (ms_byte << 8)
+ + (uint16_t) (ls_byte & 0x000000FF);
+ }
+
+ return encoded_timeout;
+}
+
+
+uint32_t VL53L1_decode_timeout(uint16_t encoded_timeout)
+{
+ /*
+ * Decode 16-bit timeout register value
+ * format (LSByte * 2^MSByte) + 1
+ */
+
+ uint32_t timeout_macro_clks = 0;
+
+ timeout_macro_clks = ((uint32_t) (encoded_timeout & 0x00FF)
+ << (uint32_t) ((encoded_timeout & 0xFF00) >> 8)) + 1;
+
+ return timeout_macro_clks;
+}
+
+
+VL53L1_Error VL53L1_calc_timeout_register_values(
+ uint32_t phasecal_config_timeout_us,
+ uint32_t mm_config_timeout_us,
+ uint32_t range_config_timeout_us,
+ uint16_t fast_osc_frequency,
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_timing_config_t *ptiming)
+{
+ /*
+ * Converts the input MM and range timeouts in [us]
+ * into the appropriate register values
+ *
+ * Must also be run after the VCSEL period settings are changed
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ uint32_t macro_period_us = 0;
+ uint32_t timeout_mclks = 0;
+ uint16_t timeout_encoded = 0;
+
+ LOG_FUNCTION_START("");
+
+ if (fast_osc_frequency == 0) {
+ status = VL53L1_ERROR_DIVISION_BY_ZERO;
+ } else {
+ /* Update Macro Period for Range A VCSEL Period */
+ macro_period_us =
+ VL53L1_calc_macro_period_us(
+ fast_osc_frequency,
+ ptiming->range_config__vcsel_period_a);
+
+ /* Update Phase timeout - uses Timing A */
+ timeout_mclks =
+ VL53L1_calc_timeout_mclks(
+ phasecal_config_timeout_us,
+ macro_period_us);
+
+ /* clip as the phase cal timeout register is only 8-bits */
+ if (timeout_mclks > 0xFF)
+ timeout_mclks = 0xFF;
+
+ pgeneral->phasecal_config__timeout_macrop =
+ (uint8_t)timeout_mclks;
+
+ /* Update MM Timing A timeout */
+ timeout_encoded =
+ VL53L1_calc_encoded_timeout(
+ mm_config_timeout_us,
+ macro_period_us);
+
+ ptiming->mm_config__timeout_macrop_a_hi =
+ (uint8_t)((timeout_encoded & 0xFF00) >> 8);
+ ptiming->mm_config__timeout_macrop_a_lo =
+ (uint8_t) (timeout_encoded & 0x00FF);
+
+ /* Update Range Timing A timeout */
+ timeout_encoded =
+ VL53L1_calc_encoded_timeout(
+ range_config_timeout_us,
+ macro_period_us);
+
+ ptiming->range_config__timeout_macrop_a_hi =
+ (uint8_t)((timeout_encoded & 0xFF00) >> 8);
+ ptiming->range_config__timeout_macrop_a_lo =
+ (uint8_t) (timeout_encoded & 0x00FF);
+
+ /* Update Macro Period for Range B VCSEL Period */
+ macro_period_us =
+ VL53L1_calc_macro_period_us(
+ fast_osc_frequency,
+ ptiming->range_config__vcsel_period_b);
+
+ /* Update MM Timing B timeout */
+ timeout_encoded =
+ VL53L1_calc_encoded_timeout(
+ mm_config_timeout_us,
+ macro_period_us);
+
+ ptiming->mm_config__timeout_macrop_b_hi =
+ (uint8_t)((timeout_encoded & 0xFF00) >> 8);
+ ptiming->mm_config__timeout_macrop_b_lo =
+ (uint8_t) (timeout_encoded & 0x00FF);
+
+ /* Update Range Timing B timeout */
+ timeout_encoded = VL53L1_calc_encoded_timeout(
+ range_config_timeout_us,
+ macro_period_us);
+
+ ptiming->range_config__timeout_macrop_b_hi =
+ (uint8_t)((timeout_encoded & 0xFF00) >> 8);
+ ptiming->range_config__timeout_macrop_b_lo =
+ (uint8_t) (timeout_encoded & 0x00FF);
+ }
+
+ LOG_FUNCTION_END(0);
+
+ return status;
+
+}
+
+
+uint8_t VL53L1_encode_vcsel_period(uint8_t vcsel_period_pclks)
+{
+ /*
+ * Converts the encoded VCSEL period register value into
+ * the real period in PLL clocks
+ */
+
+ uint8_t vcsel_period_reg = 0;
+
+ vcsel_period_reg = (vcsel_period_pclks >> 1) - 1;
+
+ return vcsel_period_reg;
+}
+
+
+uint32_t VL53L1_decode_unsigned_integer(
+ uint8_t *pbuffer,
+ uint8_t no_of_bytes)
+{
+ /*
+ * Decodes a integer number from the buffer
+ */
+
+ uint8_t i = 0;
+ uint32_t decoded_value = 0;
+
+ for (i = 0 ; i < no_of_bytes ; i++) {
+ decoded_value = (decoded_value << 8) + (uint32_t)pbuffer[i];
+ }
+
+ return decoded_value;
+}
+
+
+void VL53L1_encode_unsigned_integer(
+ uint32_t ip_value,
+ uint8_t no_of_bytes,
+ uint8_t *pbuffer)
+{
+ /*
+ * Encodes an integer number into the buffer
+ */
+
+ uint8_t i = 0;
+ uint32_t data = 0;
+
+ data = ip_value;
+ for (i = 0; i < no_of_bytes ; i++) {
+ pbuffer[no_of_bytes-i-1] = data & 0x00FF;
+ data = data >> 8;
+ }
+}
+
+
+void VL53L1_spad_number_to_byte_bit_index(
+ uint8_t spad_number,
+ uint8_t *pbyte_index,
+ uint8_t *pbit_index,
+ uint8_t *pbit_mask)
+{
+
+ /**
+ * Converts the input SPAD number into the SPAD Enable byte index, bit index and bit mask
+ *
+ * byte_index = (spad_no >> 3)
+ * bit_index = spad_no & 0x07
+ * bit_mask = 0x01 << bit_index
+ */
+
+ *pbyte_index = spad_number >> 3;
+ *pbit_index = spad_number & 0x07;
+ *pbit_mask = 0x01 << *pbit_index;
+
+}
+
+
+void VL53L1_encode_row_col(
+ uint8_t row,
+ uint8_t col,
+ uint8_t *pspad_number)
+{
+ /**
+ * Encodes the input array(row,col) location as SPAD number.
+ */
+
+ if (row > 7) {
+ *pspad_number = 128 + (col << 3) + (15-row);
+ } else {
+ *pspad_number = ((15-col) << 3) + row;
+ }
+}
+
+
+void VL53L1_decode_zone_size(
+ uint8_t encoded_xy_size,
+ uint8_t *pwidth,
+ uint8_t *pheight)
+{
+
+ /* extract x and y sizes
+ *
+ * Important: the sense of the device width and height is swapped
+ * versus the API sense
+ *
+ * MS Nibble = height
+ * LS Nibble = width
+ */
+
+ *pheight = encoded_xy_size >> 4;
+ *pwidth = encoded_xy_size & 0x0F;
+
+}
+
+
+void VL53L1_encode_zone_size(
+ uint8_t width,
+ uint8_t height,
+ uint8_t *pencoded_xy_size)
+{
+ /* merge x and y sizes
+ *
+ * Important: the sense of the device width and height is swapped
+ * versus the API sense
+ *
+ * MS Nibble = height
+ * LS Nibble = width
+ */
+
+ *pencoded_xy_size = (height << 4) + width;
+
+}
+
+
+void VL53L1_decode_zone_limits(
+ uint8_t encoded_xy_centre,
+ uint8_t encoded_xy_size,
+ int16_t *px_ll,
+ int16_t *py_ll,
+ int16_t *px_ur,
+ int16_t *py_ur)
+{
+
+ /*
+ * compute zone lower left and upper right limits
+ *
+ * centre (8,8) width = 16, height = 16 -> (0,0) -> (15,15)
+ * centre (8,8) width = 14, height = 16 -> (1,0) -> (14,15)
+ */
+
+ uint8_t x_centre = 0;
+ uint8_t y_centre = 0;
+ uint8_t width = 0;
+ uint8_t height = 0;
+
+ /* decode zone centre and size information */
+
+ VL53L1_decode_row_col(
+ encoded_xy_centre,
+ &y_centre,
+ &x_centre);
+
+ VL53L1_decode_zone_size(
+ encoded_xy_size,
+ &width,
+ &height);
+
+ /* compute bounds and clip */
+
+ *px_ll = (int16_t)x_centre - ((int16_t)width + 1) / 2;
+ if (*px_ll < 0)
+ *px_ll = 0;
+
+ *px_ur = *px_ll + (int16_t)width;
+ if (*px_ur > (VL53L1_SPAD_ARRAY_WIDTH-1))
+ *px_ur = VL53L1_SPAD_ARRAY_WIDTH-1;
+
+ *py_ll = (int16_t)y_centre - ((int16_t)height + 1) / 2;
+ if (*py_ll < 0)
+ *py_ll = 0;
+
+ *py_ur = *py_ll + (int16_t)height;
+ if (*py_ur > (VL53L1_SPAD_ARRAY_HEIGHT-1))
+ *py_ur = VL53L1_SPAD_ARRAY_HEIGHT-1;
+}
+
+
+uint8_t VL53L1_is_aperture_location(
+ uint8_t row,
+ uint8_t col)
+{
+ /*
+ * Returns > 0 if input (row,col) location is an aperture
+ */
+
+ uint8_t is_aperture = 0;
+ uint8_t mod_row = row % 4;
+ uint8_t mod_col = col % 4;
+
+ if (mod_row == 0 && mod_col == 2)
+ is_aperture = 1;
+
+ if (mod_row == 2 && mod_col == 0)
+ is_aperture = 1;
+
+ return is_aperture;
+}
+
+
+void VL53L1_calc_mm_effective_spads(
+ uint8_t encoded_mm_roi_centre,
+ uint8_t encoded_mm_roi_size,
+ uint8_t encoded_zone_centre,
+ uint8_t encoded_zone_size,
+ uint8_t *pgood_spads,
+ uint16_t aperture_attenuation,
+ uint16_t *pmm_inner_effective_spads,
+ uint16_t *pmm_outer_effective_spads)
+{
+
+ /* Calculates the effective SPAD counts for the MM inner and outer
+ * regions based on the input MM ROI, Zone info and return good
+ * SPAD map
+ */
+
+ int16_t x = 0;
+ int16_t y = 0;
+
+ int16_t mm_x_ll = 0;
+ int16_t mm_y_ll = 0;
+ int16_t mm_x_ur = 0;
+ int16_t mm_y_ur = 0;
+
+ int16_t zone_x_ll = 0;
+ int16_t zone_y_ll = 0;
+ int16_t zone_x_ur = 0;
+ int16_t zone_y_ur = 0;
+
+ uint8_t spad_number = 0;
+ uint8_t byte_index = 0;
+ uint8_t bit_index = 0;
+ uint8_t bit_mask = 0;
+
+ uint8_t is_aperture = 0;
+ uint16_t spad_attenuation = 0;
+
+ /* decode the MM ROI and Zone limits */
+
+ VL53L1_decode_zone_limits(
+ encoded_mm_roi_centre,
+ encoded_mm_roi_size,
+ &mm_x_ll,
+ &mm_y_ll,
+ &mm_x_ur,
+ &mm_y_ur);
+
+ VL53L1_decode_zone_limits(
+ encoded_zone_centre,
+ encoded_zone_size,
+ &zone_x_ll,
+ &zone_y_ll,
+ &zone_x_ur,
+ &zone_y_ur);
+
+ /*
+ * Loop though all SPAD within the zone. Check if it is
+ * a good SPAD then add the transmission value to either
+ * the inner or outer effective SPAD count dependent if
+ * the SPAD lies within the MM ROI.
+ */
+
+ *pmm_inner_effective_spads = 0;
+ *pmm_outer_effective_spads = 0;
+
+ for (y = zone_y_ll ; y <= zone_y_ur ; y++) {
+ for (x = zone_x_ll ; x <= zone_x_ur ; x++) {
+
+ /* Convert location into SPAD number */
+
+ VL53L1_encode_row_col(
+ (uint8_t)y,
+ (uint8_t)x,
+ &spad_number);
+
+ /* Convert spad number into byte and bit index
+ * this is required to look up the appropriate
+ * SPAD enable bit with the 32-byte good SPAD
+ * enable buffer
+ */
+
+ VL53L1_spad_number_to_byte_bit_index(
+ spad_number,
+ &byte_index,
+ &bit_index,
+ &bit_mask);
+
+ /* If spad is good then add it */
+
+ if ((pgood_spads[byte_index] & bit_mask) > 0) {
+ /* determine if apertured SPAD or not */
+
+ is_aperture = VL53L1_is_aperture_location(
+ (uint8_t)y,
+ (uint8_t)x);
+
+ if (is_aperture > 0)
+ spad_attenuation = aperture_attenuation;
+ else
+ spad_attenuation = 0x0100;
+
+ /*
+ * if inside MM roi add to inner effective SPAD count
+ * otherwise add to outer effective SPAD Count
+ */
+
+ if (x >= mm_x_ll && x <= mm_x_ur &&
+ y >= mm_y_ll && y <= mm_y_ur)
+ *pmm_inner_effective_spads +=
+ spad_attenuation;
+ else
+ *pmm_outer_effective_spads +=
+ spad_attenuation;
+ }
+ }
+ }
+}
+
+
+/*
+ * Encodes VL53L1_GPIO_interrupt_config_t structure to FW register format
+ */
+
+uint8_t VL53L1_encode_GPIO_interrupt_config(
+ VL53L1_GPIO_interrupt_config_t *pintconf)
+{
+ uint8_t system__interrupt_config;
+
+ system__interrupt_config = pintconf->intr_mode_distance;
+ system__interrupt_config |= ((pintconf->intr_mode_rate) << 2);
+ system__interrupt_config |= ((pintconf->intr_new_measure_ready) << 5);
+ system__interrupt_config |= ((pintconf->intr_no_target) << 6);
+ system__interrupt_config |= ((pintconf->intr_combined_mode) << 7);
+
+ return system__interrupt_config;
+}
+
+/*
+ * Decodes FW register to VL53L1_GPIO_interrupt_config_t structure
+ */
+
+VL53L1_GPIO_interrupt_config_t VL53L1_decode_GPIO_interrupt_config(
+ uint8_t system__interrupt_config)
+{
+ VL53L1_GPIO_interrupt_config_t intconf;
+
+ intconf.intr_mode_distance = system__interrupt_config & 0x03;
+ intconf.intr_mode_rate = (system__interrupt_config >> 2) & 0x03;
+ intconf.intr_new_measure_ready = (system__interrupt_config >> 5) & 0x01;
+ intconf.intr_no_target = (system__interrupt_config >> 6) & 0x01;
+ intconf.intr_combined_mode = (system__interrupt_config >> 7) & 0x01;
+
+ /* set some default values */
+ intconf.threshold_rate_low = 0;
+ intconf.threshold_rate_high = 0;
+ intconf.threshold_distance_low = 0;
+ intconf.threshold_distance_high = 0;
+
+ return intconf;
+}
+
+/*
+ * Set GPIO distance threshold
+ */
+
+VL53L1_Error VL53L1_set_GPIO_distance_threshold(
+ VL53L1_DEV Dev,
+ uint16_t threshold_high,
+ uint16_t threshold_low)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ pdev->dyn_cfg.system__thresh_high = threshold_high;
+ pdev->dyn_cfg.system__thresh_low = threshold_low;
+
+ LOG_FUNCTION_END(status);
+ return status;
+}
+
+/*
+ * Set GPIO rate threshold
+ */
+
+VL53L1_Error VL53L1_set_GPIO_rate_threshold(
+ VL53L1_DEV Dev,
+ uint16_t threshold_high,
+ uint16_t threshold_low)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ pdev->gen_cfg.system__thresh_rate_high = threshold_high;
+ pdev->gen_cfg.system__thresh_rate_low = threshold_low;
+
+ LOG_FUNCTION_END(status);
+ return status;
+}
+
+/*
+ * Set GPIO thresholds from structure
+ */
+
+VL53L1_Error VL53L1_set_GPIO_thresholds_from_struct(
+ VL53L1_DEV Dev,
+ VL53L1_GPIO_interrupt_config_t *pintconf)
+{
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ status = VL53L1_set_GPIO_distance_threshold(
+ Dev,
+ pintconf->threshold_distance_high,
+ pintconf->threshold_distance_low);
+
+ if (status == VL53L1_ERROR_NONE) {
+ status =
+ VL53L1_set_GPIO_rate_threshold(
+ Dev,
+ pintconf->threshold_rate_high,
+ pintconf->threshold_rate_low);
+ }
+
+ LOG_FUNCTION_END(status);
+ return status;
+}
+
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_set_ref_spad_char_config(
+ VL53L1_DEV Dev,
+ uint8_t vcsel_period_a,
+ uint32_t phasecal_timeout_us,
+ uint16_t total_rate_target_mcps,
+ uint16_t max_count_rate_rtn_limit_mcps,
+ uint16_t min_count_rate_rtn_limit_mcps,
+ uint16_t fast_osc_frequency)
+{
+ /*
+ * Initialises the VCSEL period A and phasecal timeout registers
+ * for the Reference SPAD Characterisation test
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint8_t buffer[2];
+
+ uint32_t macro_period_us = 0;
+ uint32_t timeout_mclks = 0;
+
+ LOG_FUNCTION_START("");
+
+ /*
+ * Update Macro Period for Range A VCSEL Period
+ */
+ macro_period_us =
+ VL53L1_calc_macro_period_us(
+ fast_osc_frequency,
+ vcsel_period_a);
+
+ /*
+ * Calculate PhaseCal timeout and clip to max of 255 macro periods
+ */
+
+ timeout_mclks = phasecal_timeout_us << 12;
+ timeout_mclks = timeout_mclks + (macro_period_us>>1);
+ timeout_mclks = timeout_mclks / macro_period_us;
+
+ if (timeout_mclks > 0xFF)
+ pdev->gen_cfg.phasecal_config__timeout_macrop = 0xFF;
+ else
+ pdev->gen_cfg.phasecal_config__timeout_macrop =
+ (uint8_t)timeout_mclks;
+
+ pdev->tim_cfg.range_config__vcsel_period_a = vcsel_period_a;
+
+ /*
+ * Update device settings
+ */
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status =
+ VL53L1_WrByte(
+ Dev,
+ VL53L1_PHASECAL_CONFIG__TIMEOUT_MACROP,
+ pdev->gen_cfg.phasecal_config__timeout_macrop);
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_WrByte(
+ Dev,
+ VL53L1_RANGE_CONFIG__VCSEL_PERIOD_A,
+ pdev->tim_cfg.range_config__vcsel_period_a);
+
+ /*
+ * Copy vcsel register value to the WOI registers to ensure that
+ * it is correctly set for the specified VCSEL period
+ */
+
+ buffer[0] = pdev->tim_cfg.range_config__vcsel_period_a;
+ buffer[1] = pdev->tim_cfg.range_config__vcsel_period_a;
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_WriteMulti(
+ Dev,
+ VL53L1_SD_CONFIG__WOI_SD0,
+ buffer,
+ 2); /* It should be be replaced with a define */
+
+ /*
+ * Set min, target and max rate limits
+ */
+
+ pdev->customer.ref_spad_char__total_rate_target_mcps =
+ total_rate_target_mcps;
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_WrWord(
+ Dev,
+ VL53L1_REF_SPAD_CHAR__TOTAL_RATE_TARGET_MCPS,
+ total_rate_target_mcps); /* 9.7 format */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_WrWord(
+ Dev,
+ VL53L1_RANGE_CONFIG__SIGMA_THRESH,
+ max_count_rate_rtn_limit_mcps);
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_WrWord(
+ Dev,
+ VL53L1_RANGE_CONFIG__MIN_COUNT_RATE_RTN_LIMIT_MCPS,
+ min_count_rate_rtn_limit_mcps);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_ssc_config(
+ VL53L1_DEV Dev,
+ VL53L1_ssc_config_t *pssc_cfg,
+ uint16_t fast_osc_frequency)
+{
+ /**
+ * Builds and sends a single I2C multiple byte transaction to
+ * initialize the device for SSC.
+ *
+ * The function also sets the WOI registers based on the input
+ * vcsel period register value.
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t buffer[5];
+
+ uint32_t macro_period_us = 0;
+ uint16_t timeout_encoded = 0;
+
+ LOG_FUNCTION_START("");
+
+ /*
+ * Update Macro Period for Range A VCSEL Period
+ */
+ macro_period_us =
+ VL53L1_calc_macro_period_us(
+ fast_osc_frequency,
+ pssc_cfg->vcsel_period);
+
+ /*
+ * Update MM Timing A timeout
+ */
+ timeout_encoded =
+ VL53L1_calc_encoded_timeout(
+ pssc_cfg->timeout_us,
+ macro_period_us);
+
+ /* update VCSEL timings */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_WrByte(
+ Dev,
+ VL53L1_CAL_CONFIG__VCSEL_START,
+ pssc_cfg->vcsel_start);
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_WrByte(
+ Dev,
+ VL53L1_GLOBAL_CONFIG__VCSEL_WIDTH,
+ pssc_cfg->vcsel_width);
+
+ /* build buffer for timeouts, period and rate limit */
+
+ buffer[0] = (uint8_t)((timeout_encoded & 0x0000FF00) >> 8);
+ buffer[1] = (uint8_t) (timeout_encoded & 0x000000FF);
+ buffer[2] = pssc_cfg->vcsel_period;
+ buffer[3] = (uint8_t)((pssc_cfg->rate_limit_mcps & 0x0000FF00) >> 8);
+ buffer[4] = (uint8_t) (pssc_cfg->rate_limit_mcps & 0x000000FF);
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_WriteMulti(
+ Dev,
+ VL53L1_RANGE_CONFIG__TIMEOUT_MACROP_B_HI,
+ buffer,
+ 5);
+
+ /*
+ * Copy vcsel register value to the WOI registers to ensure that
+ * it is correctly set for the specified VCSEL period
+ */
+
+ buffer[0] = pssc_cfg->vcsel_period;
+ buffer[1] = pssc_cfg->vcsel_period;
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_WriteMulti(
+ Dev,
+ VL53L1_SD_CONFIG__WOI_SD0,
+ buffer,
+ 2);
+
+ /*
+ * Write zero to NVM_BIST_CTRL to send RTN CountRate to Patch RAM
+ * or 1 to write REF CountRate to Patch RAM
+ */
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_WrByte(
+ Dev,
+ VL53L1_NVM_BIST__CTRL,
+ pssc_cfg->array_select);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifndef VL53L1_NOCALIB
+VL53L1_Error VL53L1_get_spad_rate_data(
+ VL53L1_DEV Dev,
+ VL53L1_spad_rate_data_t *pspad_rates)
+{
+
+ /**
+ * Gets the SSC rate map output
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ int i = 0;
+
+ uint8_t data[512];
+ uint8_t *pdata = &data[0];
+
+ LOG_FUNCTION_START("");
+
+ /* Disable Firmware to Read Patch Ram */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_disable_firmware(Dev);
+
+ /*
+ * Read Return SPADs Rates from patch RAM.
+ * Note : platform layer splits the I2C comms into smaller chunks
+ */
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_ReadMulti(
+ Dev,
+ VL53L1_PRIVATE__PATCH_BASE_ADDR_RSLV,
+ pdata,
+ 512);
+
+ /* now convert into 16-bit number */
+ pdata = &data[0];
+ for (i = 0 ; i < VL53L1_NO_OF_SPAD_ENABLES ; i++) {
+ pspad_rates->rate_data[i] =
+ (uint16_t)VL53L1_decode_unsigned_integer(pdata, 2);
+ pdata += 2;
+ }
+
+ /* Initialise structure info */
+
+ pspad_rates->buffer_size = VL53L1_NO_OF_SPAD_ENABLES;
+ pspad_rates->no_of_values = VL53L1_NO_OF_SPAD_ENABLES;
+ pspad_rates->fractional_bits = 15;
+
+ /* Re-enable Firmware */
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+/* Start Patch_LowPowerAutoMode */
+
+VL53L1_Error VL53L1_low_power_auto_data_init(
+ VL53L1_DEV Dev
+ )
+{
+
+ /*
+ * Initializes internal data structures for low power auto mode
+ */
+
+ /* don't really use this here */
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ pdev->low_power_auto_data.vhv_loop_bound =
+ VL53L1_TUNINGPARM_LOWPOWERAUTO_VHV_LOOP_BOUND_DEFAULT;
+ pdev->low_power_auto_data.is_low_power_auto_mode = 0;
+ pdev->low_power_auto_data.low_power_auto_range_count = 0;
+ pdev->low_power_auto_data.saved_interrupt_config = 0;
+ pdev->low_power_auto_data.saved_vhv_init = 0;
+ pdev->low_power_auto_data.saved_vhv_timeout = 0;
+ pdev->low_power_auto_data.first_run_phasecal_result = 0;
+ pdev->low_power_auto_data.dss__total_rate_per_spad_mcps = 0;
+ pdev->low_power_auto_data.dss__required_spads = 0;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+VL53L1_Error VL53L1_low_power_auto_data_stop_range(
+ VL53L1_DEV Dev
+ )
+{
+
+ /*
+ * Range has been paused but may continue later
+ */
+
+ /* don't really use this here */
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ /* doing this ensures stop_range followed by a get_device_results does
+ * not mess up the counters */
+
+ pdev->low_power_auto_data.low_power_auto_range_count = 0xFF;
+
+ pdev->low_power_auto_data.first_run_phasecal_result = 0;
+ pdev->low_power_auto_data.dss__total_rate_per_spad_mcps = 0;
+ pdev->low_power_auto_data.dss__required_spads = 0;
+
+ /* restore vhv configs */
+ if (pdev->low_power_auto_data.saved_vhv_init != 0)
+ pdev->stat_nvm.vhv_config__init =
+ pdev->low_power_auto_data.saved_vhv_init;
+ if (pdev->low_power_auto_data.saved_vhv_timeout != 0)
+ pdev->stat_nvm.vhv_config__timeout_macrop_loop_bound =
+ pdev->low_power_auto_data.saved_vhv_timeout;
+
+ /* remove phasecal override */
+ pdev->gen_cfg.phasecal_config__override = 0x00;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+VL53L1_Error VL53L1_config_low_power_auto_mode(
+ VL53L1_general_config_t *pgeneral,
+ VL53L1_dynamic_config_t *pdynamic,
+ VL53L1_low_power_auto_data_t *plpadata
+ )
+{
+
+ /*
+ * Initializes configs for when low power auto presets are selected
+ */
+
+ /* don't really use this here */
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* set low power auto mode */
+ plpadata->is_low_power_auto_mode = 1;
+
+ /* set low power range count to 0 */
+ plpadata->low_power_auto_range_count = 0;
+
+ /* Turn off MM1/MM2 and DSS2 */
+ pdynamic->system__sequence_config = \
+ VL53L1_SEQUENCE_VHV_EN | \
+ VL53L1_SEQUENCE_PHASECAL_EN | \
+ VL53L1_SEQUENCE_DSS1_EN | \
+ /* VL53L1_SEQUENCE_DSS2_EN | \*/
+ /* VL53L1_SEQUENCE_MM1_EN | \*/
+ /* VL53L1_SEQUENCE_MM2_EN | \*/
+ VL53L1_SEQUENCE_RANGE_EN;
+
+ /* Set DSS to manual/expected SPADs */
+ pgeneral->dss_config__manual_effective_spads_select = 200 << 8;
+ pgeneral->dss_config__roi_mode_control =
+ VL53L1_DEVICEDSSMODE__REQUESTED_EFFFECTIVE_SPADS;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+VL53L1_Error VL53L1_low_power_auto_setup_manual_calibration(
+ VL53L1_DEV Dev)
+{
+
+ /*
+ * Setup ranges after the first one in low power auto mode by turning
+ * off FW calibration steps and programming static values
+ */
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ /* don't really use this here */
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* save original vhv configs */
+ pdev->low_power_auto_data.saved_vhv_init =
+ pdev->stat_nvm.vhv_config__init;
+ pdev->low_power_auto_data.saved_vhv_timeout =
+ pdev->stat_nvm.vhv_config__timeout_macrop_loop_bound;
+
+ /* disable VHV init */
+ pdev->stat_nvm.vhv_config__init &= 0x7F;
+ /* set loop bound to tuning param */
+ pdev->stat_nvm.vhv_config__timeout_macrop_loop_bound =
+ (pdev->stat_nvm.vhv_config__timeout_macrop_loop_bound & 0x03) +
+ (pdev->low_power_auto_data.vhv_loop_bound << 2);
+ /* override phasecal */
+ pdev->gen_cfg.phasecal_config__override = 0x01;
+ pdev->low_power_auto_data.first_run_phasecal_result =
+ pdev->dbg_results.phasecal_result__vcsel_start;
+ pdev->gen_cfg.cal_config__vcsel_start =
+ pdev->low_power_auto_data.first_run_phasecal_result;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+VL53L1_Error VL53L1_low_power_auto_update_DSS(
+ VL53L1_DEV Dev)
+{
+
+ /*
+ * Do a DSS calculation and update manual config
+ */
+
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ /* don't really use this here */
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ uint32_t utemp32a;
+
+ LOG_FUNCTION_START("");
+
+ /* Calc total rate per spad */
+
+ /* 9.7 format */
+ utemp32a = pdev->sys_results.result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0 +
+ pdev->sys_results.result__ambient_count_rate_mcps_sd0;
+
+ /* clip to 16 bits */
+ if (utemp32a > 0xFFFF)
+ utemp32a = 0xFFFF;
+
+ /* shift up to take advantage of 32 bits */
+ /* 9.23 format */
+ utemp32a = utemp32a << 16;
+
+ /* check SPAD count */
+ if (pdev->sys_results.result__dss_actual_effective_spads_sd0 == 0)
+ status = VL53L1_ERROR_DIVISION_BY_ZERO;
+ else {
+ /* format 17.15 */
+ utemp32a = utemp32a /
+ pdev->sys_results.result__dss_actual_effective_spads_sd0;
+ /* save intermediate result */
+ pdev->low_power_auto_data.dss__total_rate_per_spad_mcps =
+ utemp32a;
+
+ /* get the target rate and shift up by 16
+ * format 9.23 */
+ utemp32a = pdev->stat_cfg.dss_config__target_total_rate_mcps <<
+ 16;
+
+ /* check for divide by zero */
+ if (pdev->low_power_auto_data.dss__total_rate_per_spad_mcps == 0)
+ status = VL53L1_ERROR_DIVISION_BY_ZERO;
+ else {
+ /* divide by rate per spad
+ * format 24.8 */
+ utemp32a = utemp32a /
+ pdev->low_power_auto_data.dss__total_rate_per_spad_mcps;
+
+ /* clip to 16 bit */
+ if (utemp32a > 0xFFFF)
+ utemp32a = 0xFFFF;
+
+ /* save result in low power auto data */
+ pdev->low_power_auto_data.dss__required_spads =
+ (uint16_t)utemp32a;
+
+ /* override DSS config */
+ pdev->gen_cfg.dss_config__manual_effective_spads_select =
+ pdev->low_power_auto_data.dss__required_spads;
+ pdev->gen_cfg.dss_config__roi_mode_control =
+ VL53L1_DEVICEDSSMODE__REQUESTED_EFFFECTIVE_SPADS;
+ }
+
+ }
+
+ if (status == VL53L1_ERROR_DIVISION_BY_ZERO) {
+ /* We want to gracefully set a spad target, not just exit with
+ * an error */
+
+ /* set target to mid point */
+ pdev->low_power_auto_data.dss__required_spads = 0x8000;
+
+ /* override DSS config */
+ pdev->gen_cfg.dss_config__manual_effective_spads_select =
+ pdev->low_power_auto_data.dss__required_spads;
+ pdev->gen_cfg.dss_config__roi_mode_control =
+ VL53L1_DEVICEDSSMODE__REQUESTED_EFFFECTIVE_SPADS;
+
+ /* reset error */
+ status = VL53L1_ERROR_NONE;
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+/* End Patch_LowPowerAutoMode */
diff --git a/src/lib/vl53l1/core/src/vl53l1_core_support.c b/src/lib/vl53l1/core/src/vl53l1_core_support.c
new file mode 100644
index 0000000000..e88916e67d
--- /dev/null
+++ b/src/lib/vl53l1/core/src/vl53l1_core_support.c
@@ -0,0 +1,411 @@
+/*******************************************************************************
+ Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ ******************************************************************************/
+
+/**
+ * @file vl53l1_core_support.c
+ *
+ * @brief EwokPlus25 core function definition
+ */
+
+#include "vl53l1_ll_def.h"
+#include "vl53l1_ll_device.h"
+#include "vl53l1_platform_log.h"
+#include "vl53l1_core_support.h"
+#include "vl53l1_platform_user_data.h"
+#include "vl53l1_platform_user_defines.h"
+
+#ifdef VL53L1_LOGGING
+#include "vl53l1_debug.h"
+#include "vl53l1_register_debug.h"
+#endif
+
+#define LOG_FUNCTION_START(fmt, ...) \
+ _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_CORE, fmt, ##__VA_ARGS__)
+#define LOG_FUNCTION_END(status, ...) \
+ _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_CORE, status, ##__VA_ARGS__)
+#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
+ _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_CORE, \
+ status, fmt, ##__VA_ARGS__)
+
+#define trace_print(level, ...) \
+ _LOG_TRACE_PRINT(VL53L1_TRACE_MODULE_CORE, \
+ level, VL53L1_TRACE_FUNCTION_NONE, ##__VA_ARGS__)
+
+
+uint32_t VL53L1_calc_pll_period_us(
+ uint16_t fast_osc_frequency)
+{
+ /* Calculates PLL frequency using NVM fast_osc_frequency
+ * Fast osc frequency fixed point format = unsigned 4.12
+ *
+ * PLL period fixed point format = unsigned 0.24
+ * Min input fast osc frequency = 1 MHz
+ * PLL Multiplier = 64 (fixed)
+ * Min PLL freq = 64.0MHz
+ * -> max PLL period = 1/ 64
+ * -> only the 18 LS bits are used
+ *
+ * 2^30 = (2^24) (1.0us) * 4096 (2^12) / 64 (PLL Multiplier)
+ */
+
+ uint32_t pll_period_us = 0;
+
+ LOG_FUNCTION_START("");
+
+ pll_period_us = (0x01 << 30) / fast_osc_frequency;
+
+#ifdef VL53L1_LOGGING
+ trace_print(VL53L1_TRACE_LEVEL_DEBUG,
+ " %-48s : %10u\n", "pll_period_us",
+ pll_period_us);
+#endif
+
+ LOG_FUNCTION_END(0);
+
+ return pll_period_us;
+}
+
+
+#ifdef PAL_EXTENDED
+uint32_t VL53L1_duration_maths(
+ uint32_t pll_period_us,
+ uint32_t vcsel_parm_pclks,
+ uint32_t window_vclks,
+ uint32_t elapsed_mclks)
+{
+ /*
+ * Generates the ranging duration in us
+ *
+ * duration_us = elapsed_mclks * vcsel_perm_pclks *
+ * window_vclks * pll_period_us
+ *
+ * returned value in [us] with no fraction bits
+ */
+
+ uint64_t tmp_long_int = 0;
+ uint32_t duration_us = 0;
+
+ /* PLL period us = 0.24 18 LS bits used
+ * window_vclks = 12.0 (2304 max)
+ * output 30b (6.24)
+ */
+ duration_us = window_vclks * pll_period_us;
+
+ /* down shift by 12
+ * output 18b (6.12)
+ */
+ duration_us = duration_us >> 12;
+
+ /* Save first part of the calc (#1) */
+ tmp_long_int = (uint64_t)duration_us;
+
+ /* Multiply elapsed macro periods (22-bit)
+ * by VCSEL parameter 6.4 (max 63.9999)
+ * output 32b (28.4)
+ */
+ duration_us = elapsed_mclks * vcsel_parm_pclks;
+
+ /* down shift by 4 to remove fractional bits (#2)
+ * output 28b (28.0)
+ */
+ duration_us = duration_us >> 4;
+
+ /* Multiply #1 18b (6.12) by #2 28b (28.0)
+ * output 46b (34.12)
+ */
+ tmp_long_int = tmp_long_int * (uint64_t)duration_us;
+
+ /* Remove fractional part
+ * output 34b (34.0)
+ */
+ tmp_long_int = tmp_long_int >> 12;
+
+ /* Clip to 32-bits */
+ if (tmp_long_int > 0xFFFFFFFF) {
+ tmp_long_int = 0xFFFFFFFF;
+ }
+
+ duration_us = (uint32_t)tmp_long_int;
+
+ return duration_us;
+}
+
+
+uint32_t VL53L1_isqrt(uint32_t num)
+{
+
+ /*
+ * Implements an integer square root
+ *
+ * From: http://en.wikipedia.org/wiki/Methods_of_computing_square_roots
+ */
+
+ uint32_t res = 0;
+ uint32_t bit = 1 << 30; /* The second-to-top bit is set: 1 << 14 for 16-bits, 1 << 30 for 32 bits */
+
+ /* "bit" starts at the highest power of four <= the argument. */
+ while (bit > num) {
+ bit >>= 2;
+ }
+
+ while (bit != 0) {
+ if (num >= res + bit) {
+ num -= res + bit;
+ res = (res >> 1) + bit;
+ } else {
+ res >>= 1;
+ }
+ bit >>= 2;
+ }
+
+ return res;
+}
+
+
+uint16_t VL53L1_rate_maths(
+ int32_t events,
+ uint32_t time_us)
+{
+ /*
+ * Converts events into count rate
+ *
+ * Max events = 512 Mcps * 1sec
+ * = 512,000,000 events
+ * = 29b
+ *
+ * If events > 2^24 use 3-bit fractional bits is used internally
+ * otherwise 7-bit fractional bits are used
+ */
+
+ uint32_t tmp_int = 0;
+ uint32_t frac_bits = 7;
+ uint16_t rate_mcps = 0; /* 9.7 format */
+
+ /*
+ * Clip input event range
+ */
+
+ if (events > VL53L1_SPAD_TOTAL_COUNT_MAX) {
+ tmp_int = VL53L1_SPAD_TOTAL_COUNT_MAX;
+ } else if (events > 0) {
+ tmp_int = (uint32_t)events;
+ }
+
+ /*
+ * if events > VL53L1_SPAD_TOTAL_COUNT_RES_THRES use 3 rather
+ * than 7 fractional bits internal to function
+ */
+
+ if (events > VL53L1_SPAD_TOTAL_COUNT_RES_THRES) {
+ frac_bits = 3;
+ } else {
+ frac_bits = 7;
+ }
+
+ /*
+ * Create 3 or 7 fractional bits
+ * output 32b (29.3 or 25.7)
+ * Divide by range duration in [us] - no fractional bits
+ */
+ if (time_us > 0) {
+ tmp_int = ((tmp_int << frac_bits) + (time_us / 2)) / time_us;
+ }
+
+ /*
+ * Re align if reduced resolution
+ */
+ if (events > VL53L1_SPAD_TOTAL_COUNT_RES_THRES) {
+ tmp_int = tmp_int << 4;
+ }
+
+ /*
+ * Firmware internal count is 17.7 (24b) but it this
+ * case clip to 16-bit value for reporting
+ */
+
+ if (tmp_int > 0xFFFF) {
+ tmp_int = 0xFFFF;
+ }
+
+ rate_mcps = (uint16_t)tmp_int;
+
+ return rate_mcps;
+}
+
+uint16_t VL53L1_rate_per_spad_maths(
+ uint32_t frac_bits,
+ uint32_t peak_count_rate,
+ uint16_t num_spads,
+ uint32_t max_output_value)
+{
+
+ uint32_t tmp_int = 0;
+
+ /* rate_per_spad Format varies with prog frac_bits */
+ uint16_t rate_per_spad = 0;
+
+ /* Calculate rate per spad with variable fractional bits */
+
+ /* Frac_bits should be programmed as final frac_bits - 7 as
+ * the pk_rate contains an inherent 7 bit resolution
+ */
+
+ if (num_spads > 0) {
+ tmp_int = (peak_count_rate << 8) << frac_bits;
+ tmp_int = (tmp_int + ((uint32_t)num_spads / 2)) / (uint32_t)num_spads;
+ } else {
+ tmp_int = ((peak_count_rate) << frac_bits);
+ }
+
+ /* Clip in case of overwrap - special code */
+
+ if (tmp_int > max_output_value) {
+ tmp_int = max_output_value;
+ }
+
+ rate_per_spad = (uint16_t)tmp_int;
+
+ return rate_per_spad;
+}
+
+int32_t VL53L1_range_maths(
+ uint16_t fast_osc_frequency,
+ uint16_t phase,
+ uint16_t zero_distance_phase,
+ uint8_t fractional_bits,
+ int32_t gain_factor,
+ int32_t range_offset_mm)
+{
+ /*
+ * Converts phase information into distance in [mm]
+ */
+
+ uint32_t pll_period_us = 0; /* 0.24 format */
+ int64_t tmp_long_int = 0;
+ int32_t range_mm = 0;
+
+ /* Calculate PLL period in [ps] */
+
+ pll_period_us = VL53L1_calc_pll_period_us(fast_osc_frequency);
+
+ /* Raw range in [mm]
+ *
+ * calculate the phase difference between return and reference phases
+ *
+ * phases 16b (5.11)
+ * output 17b including sign bit
+ */
+
+ tmp_long_int = (int64_t)phase - (int64_t)zero_distance_phase;
+
+ /*
+ * multiply by the PLL period
+ *
+ * PLL period 24bit (0.24) but only 18 LS bits used
+ *
+ * Output 35b (0.35) (17b + 18b)
+ */
+
+ tmp_long_int = tmp_long_int * (int64_t)pll_period_us;
+
+ /*
+ * Down shift by 9 - Output 26b (0.26)
+ */
+
+ tmp_long_int = tmp_long_int / (0x01 << 9);
+
+ /*
+ * multiply by speed of light in air divided by 8
+ * Factor of 8 includes 2 for the round trip and 4 scaling
+ *
+ * VL53L1_SPEED_OF_LIGHT_IN_AIR_DIV_8 = 16b (16.2)
+ *
+ * Output 42b (18.24) (16b + 26b)
+ */
+
+ tmp_long_int = tmp_long_int * VL53L1_SPEED_OF_LIGHT_IN_AIR_DIV_8;
+
+ /*
+ * Down shift by 22 - Output 20b (18.2)
+ */
+
+ tmp_long_int = tmp_long_int / (0x01 << 22);
+
+ /* Add range offset */
+ range_mm = (int32_t)tmp_long_int + range_offset_mm;
+
+ /* apply correction gain */
+ range_mm *= gain_factor;
+ range_mm += 0x0400;
+ range_mm /= 0x0800;
+
+ /* Remove fractional bits */
+ if (fractional_bits == 0)
+ range_mm = range_mm / (0x01 << 2);
+ else if (fractional_bits == 1)
+ range_mm = range_mm / (0x01 << 1);
+
+ return range_mm;
+}
+#endif
+
+uint8_t VL53L1_decode_vcsel_period(uint8_t vcsel_period_reg)
+{
+ /*
+ * Converts the encoded VCSEL period register value into
+ * the real period in PLL clocks
+ */
+
+ uint8_t vcsel_period_pclks = 0;
+
+ vcsel_period_pclks = (vcsel_period_reg + 1) << 1;
+
+ return vcsel_period_pclks;
+}
+
+
+void VL53L1_decode_row_col(
+ uint8_t spad_number,
+ uint8_t *prow,
+ uint8_t *pcol)
+{
+
+ /**
+ * Decodes the array (row,col) location from
+ * the input SPAD number
+ */
+
+ if (spad_number > 127) {
+ *prow = 8 + ((255-spad_number) & 0x07);
+ *pcol = (spad_number-128) >> 3;
+ } else {
+ *prow = spad_number & 0x07;
+ *pcol = (127-spad_number) >> 3;
+ }
+}
+
diff --git a/src/lib/vl53l1/core/src/vl53l1_error_strings.c b/src/lib/vl53l1/core/src/vl53l1_error_strings.c
new file mode 100644
index 0000000000..0954c97a23
--- /dev/null
+++ b/src/lib/vl53l1/core/src/vl53l1_error_strings.c
@@ -0,0 +1,270 @@
+/*******************************************************************************
+ Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ ******************************************************************************/
+
+/**
+ * @file vl53l1_error_strings.c
+ * @brief VL53L1 API functions for decoding error codes to a text string
+ */
+
+#include "vl53l1_error_codes.h"
+#include "vl53l1_error_strings.h"
+#include "vl53l1_platform_log.h"
+#include "vl53l1_ll_def.h"
+
+#define LOG_FUNCTION_START(fmt, ...) \
+ _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_API, fmt, ##__VA_ARGS__)
+#define LOG_FUNCTION_END(status, ...) \
+ _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_API, status, ##__VA_ARGS__)
+#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
+ _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_API, \
+ status, fmt, ##__VA_ARGS__)
+
+
+#ifndef VL53L1_DEBUG
+ #define VL53L1_USE_EMPTY_STRING
+#endif
+
+VL53L1_Error VL53L1_get_pal_error_string(
+ VL53L1_Error PalErrorCode,
+ char *pPalErrorString)
+{
+ VL53L1_Error Status = VL53L1_ERROR_NONE;
+
+#ifdef VL53L1_USE_EMPTY_STRING
+ SUPPRESS_UNUSED_WARNING(PalErrorCode);
+#endif
+
+ LOG_FUNCTION_START("");
+
+#ifdef VL53L1_USE_EMPTY_STRING
+ VL53L1_COPYSTRING(pPalErrorString, "");
+#else
+
+ switch (PalErrorCode) {
+ case VL53L1_ERROR_NONE:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_NONE);
+ break;
+ case VL53L1_ERROR_CALIBRATION_WARNING:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_CALIBRATION_WARNING);
+ break;
+ case VL53L1_ERROR_MIN_CLIPPED:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_MIN_CLIPPED);
+ break;
+ case VL53L1_ERROR_UNDEFINED:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_UNDEFINED);
+ break;
+ case VL53L1_ERROR_INVALID_PARAMS:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_INVALID_PARAMS);
+ break;
+ case VL53L1_ERROR_NOT_SUPPORTED:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_NOT_SUPPORTED);
+ break;
+ case VL53L1_ERROR_RANGE_ERROR:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_RANGE_ERROR);
+ break;
+ case VL53L1_ERROR_TIME_OUT:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_TIME_OUT);
+ break;
+ case VL53L1_ERROR_MODE_NOT_SUPPORTED:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_MODE_NOT_SUPPORTED);
+ break;
+ case VL53L1_ERROR_BUFFER_TOO_SMALL:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_BUFFER_TOO_SMALL);
+ break;
+ case VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_COMMS_BUFFER_TOO_SMALL);
+ break;
+ case VL53L1_ERROR_GPIO_NOT_EXISTING:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_GPIO_NOT_EXISTING);
+ break;
+ case VL53L1_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED);
+ break;
+ case VL53L1_ERROR_CONTROL_INTERFACE:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_CONTROL_INTERFACE);
+ break;
+ case VL53L1_ERROR_INVALID_COMMAND:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_INVALID_COMMAND);
+ break;
+ case VL53L1_ERROR_DIVISION_BY_ZERO:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_DIVISION_BY_ZERO);
+ break;
+ case VL53L1_ERROR_REF_SPAD_INIT:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_REF_SPAD_INIT);
+ break;
+ case VL53L1_ERROR_GPH_SYNC_CHECK_FAIL:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_GPH_SYNC_CHECK_FAIL);
+ break;
+ case VL53L1_ERROR_STREAM_COUNT_CHECK_FAIL:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_STREAM_COUNT_CHECK_FAIL);
+ break;
+ case VL53L1_ERROR_GPH_ID_CHECK_FAIL:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_GPH_ID_CHECK_FAIL);
+ break;
+ case VL53L1_ERROR_ZONE_STREAM_COUNT_CHECK_FAIL:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_ZONE_STREAM_COUNT_CHECK_FAIL);
+ break;
+ case VL53L1_ERROR_ZONE_GPH_ID_CHECK_FAIL:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_ZONE_GPH_ID_CHECK_FAIL);
+ break;
+
+ case VL53L1_ERROR_XTALK_EXTRACTION_NO_SAMPLE_FAIL:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_XTALK_EXTRACTION_NO_SAMPLES_FAIL);
+ break;
+ case VL53L1_ERROR_XTALK_EXTRACTION_SIGMA_LIMIT_FAIL:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_XTALK_EXTRACTION_SIGMA_LIMIT_FAIL);
+ break;
+
+ case VL53L1_ERROR_OFFSET_CAL_NO_SAMPLE_FAIL:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_OFFSET_CAL_NO_SAMPLE_FAIL);
+ break;
+ case VL53L1_ERROR_OFFSET_CAL_NO_SPADS_ENABLED_FAIL:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_OFFSET_CAL_NO_SPADS_ENABLED_FAIL);
+ break;
+ case VL53L1_ERROR_ZONE_CAL_NO_SAMPLE_FAIL:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_ZONE_CAL_NO_SAMPLE_FAIL);
+ break;
+
+ case VL53L1_WARNING_OFFSET_CAL_MISSING_SAMPLES:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_WARNING_OFFSET_CAL_MISSING_SAMPLES);
+ break;
+ case VL53L1_WARNING_OFFSET_CAL_SIGMA_TOO_HIGH:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_WARNING_OFFSET_CAL_SIGMA_TOO_HIGH);
+ break;
+ case VL53L1_WARNING_OFFSET_CAL_RATE_TOO_HIGH:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_WARNING_OFFSET_CAL_RATE_TOO_HIGH);
+ break;
+ case VL53L1_WARNING_OFFSET_CAL_SPAD_COUNT_TOO_LOW:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_WARNING_OFFSET_CAL_SPAD_COUNT_TOO_LOW);
+ break;
+
+ case VL53L1_WARNING_ZONE_CAL_MISSING_SAMPLES:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_WARNING_ZONE_CAL_MISSING_SAMPLES);
+ break;
+ case VL53L1_WARNING_ZONE_CAL_SIGMA_TOO_HIGH:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_WARNING_ZONE_CAL_SIGMA_TOO_HIGH);
+ break;
+ case VL53L1_WARNING_ZONE_CAL_RATE_TOO_HIGH:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_WARNING_ZONE_CAL_RATE_TOO_HIGH);
+ break;
+
+ case VL53L1_WARNING_REF_SPAD_CHAR_NOT_ENOUGH_SPADS:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_WARNING_REF_SPAD_CHAR_NOT_ENOUGH_SPADS);
+ break;
+ case VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_HIGH:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_WARNING_REF_SPAD_CHAR_RATE_TOO_HIGH);
+ break;
+ case VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_LOW:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_WARNING_REF_SPAD_CHAR_RATE_TOO_LOW);
+ break;
+
+ case VL53L1_WARNING_XTALK_MISSING_SAMPLES:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_WARNING_XTALK_MISSING_SAMPLES);
+ break;
+ case VL53L1_WARNING_XTALK_NO_SAMPLES_FOR_GRADIENT:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_WARNING_XTALK_NO_SAMPLES_FOR_GRADIENT);
+ break;
+ case VL53L1_WARNING_XTALK_SIGMA_LIMIT_FOR_GRADIENT:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_WARNING_XTALK_SIGMA_LIMIT_FOR_GRADIENT);
+ break;
+
+ case VL53L1_ERROR_DEVICE_FIRMWARE_TOO_OLD:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_DEVICE_FIRMWARE_TOO_OLD);
+ break;
+ case VL53L1_ERROR_DEVICE_FIRMWARE_TOO_NEW:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_DEVICE_FIRMWARE_TOO_NEW);
+ break;
+ case VL53L1_ERROR_UNIT_TEST_FAIL:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_UNIT_TEST_FAIL);
+ break;
+ case VL53L1_ERROR_FILE_READ_FAIL:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_FILE_READ_FAIL);
+ break;
+ case VL53L1_ERROR_FILE_WRITE_FAIL:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_FILE_WRITE_FAIL);
+ break;
+ case VL53L1_ERROR_NOT_IMPLEMENTED:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_ERROR_NOT_IMPLEMENTED);
+ break;
+ default:
+ VL53L1_COPYSTRING(pPalErrorString,
+ VL53L1_STRING_UNKNOW_ERROR_CODE);
+ }
+
+#endif
+
+ LOG_FUNCTION_END(Status);
+
+ return Status;
+}
diff --git a/src/lib/vl53l1/core/src/vl53l1_register_funcs.c b/src/lib/vl53l1/core/src/vl53l1_register_funcs.c
new file mode 100644
index 0000000000..25218fa082
--- /dev/null
+++ b/src/lib/vl53l1/core/src/vl53l1_register_funcs.c
@@ -0,0 +1,4459 @@
+/*******************************************************************************
+Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+******************************************************************************/
+
+/**
+ * @file vl53l1_register_funcs.c
+ * @brief VL53L1 Register Function definitions
+ */
+
+#include "vl53l1_ll_def.h"
+#include "vl53l1_platform_log.h"
+#include "vl53l1_core.h"
+#include "vl53l1_register_map.h"
+#include "vl53l1_register_structs.h"
+#include "vl53l1_register_funcs.h"
+
+#include "../../../../drivers/interface/vl53l1x.h"
+
+#define LOG_FUNCTION_START(fmt, ...) \
+ _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_REGISTERS, fmt, ##__VA_ARGS__)
+#define LOG_FUNCTION_END(status, ...) \
+ _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_REGISTERS, status, ##__VA_ARGS__)
+#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
+ _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_REGISTERS, status, fmt, ##__VA_ARGS__)
+
+
+VL53L1_Error VL53L1_i2c_encode_static_nvm_managed(
+ VL53L1_static_nvm_managed_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_static_nvm_managed_t into a I2C write buffer
+ * Buffer must be at least 11 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_STATIC_NVM_MANAGED_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ *(pbuffer + 0) =
+ pdata->i2c_slave__device_address & 0x7F;
+ *(pbuffer + 1) =
+ pdata->ana_config__vhv_ref_sel_vddpix & 0xF;
+ *(pbuffer + 2) =
+ pdata->ana_config__vhv_ref_sel_vquench & 0x7F;
+ *(pbuffer + 3) =
+ pdata->ana_config__reg_avdd1v2_sel & 0x3;
+ *(pbuffer + 4) =
+ pdata->ana_config__fast_osc__trim & 0x7F;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->osc_measured__fast_osc__frequency,
+ 2,
+ pbuffer + 5);
+ *(pbuffer + 7) =
+ pdata->vhv_config__timeout_macrop_loop_bound;
+ *(pbuffer + 8) =
+ pdata->vhv_config__count_thresh;
+ *(pbuffer + 9) =
+ pdata->vhv_config__offset & 0x3F;
+ *(pbuffer + 10) =
+ pdata->vhv_config__init;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_decode_static_nvm_managed(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_static_nvm_managed_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_static_nvm_managed_t from the input I2C read buffer
+ * Buffer must be at least 11 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_STATIC_NVM_MANAGED_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->i2c_slave__device_address =
+ (*(pbuffer + 0)) & 0x7F;
+ pdata->ana_config__vhv_ref_sel_vddpix =
+ (*(pbuffer + 1)) & 0xF;
+ pdata->ana_config__vhv_ref_sel_vquench =
+ (*(pbuffer + 2)) & 0x7F;
+ pdata->ana_config__reg_avdd1v2_sel =
+ (*(pbuffer + 3)) & 0x3;
+ pdata->ana_config__fast_osc__trim =
+ (*(pbuffer + 4)) & 0x7F;
+ pdata->osc_measured__fast_osc__frequency =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 5));
+ pdata->vhv_config__timeout_macrop_loop_bound =
+ (*(pbuffer + 7));
+ pdata->vhv_config__count_thresh =
+ (*(pbuffer + 8));
+ pdata->vhv_config__offset =
+ (*(pbuffer + 9)) & 0x3F;
+ pdata->vhv_config__init =
+ (*(pbuffer + 10));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_static_nvm_managed(
+ VL53L1_DEV Dev,
+ VL53L1_static_nvm_managed_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_static_nvm_managed_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_STATIC_NVM_MANAGED_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_static_nvm_managed(
+ pdata,
+ VL53L1_STATIC_NVM_MANAGED_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_I2C_SLAVE__DEVICE_ADDRESS,
+ comms_buffer,
+ VL53L1_STATIC_NVM_MANAGED_I2C_SIZE_BYTES);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_get_static_nvm_managed(
+ VL53L1_DEV Dev,
+ VL53L1_static_nvm_managed_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_static_nvm_managed_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_STATIC_NVM_MANAGED_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_I2C_SLAVE__DEVICE_ADDRESS,
+ comms_buffer,
+ VL53L1_STATIC_NVM_MANAGED_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_static_nvm_managed(
+ VL53L1_STATIC_NVM_MANAGED_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_encode_customer_nvm_managed(
+ VL53L1_customer_nvm_managed_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_customer_nvm_managed_t into a I2C write buffer
+ * Buffer must be at least 23 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_CUSTOMER_NVM_MANAGED_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ *(pbuffer + 0) =
+ pdata->global_config__spad_enables_ref_0;
+ *(pbuffer + 1) =
+ pdata->global_config__spad_enables_ref_1;
+ *(pbuffer + 2) =
+ pdata->global_config__spad_enables_ref_2;
+ *(pbuffer + 3) =
+ pdata->global_config__spad_enables_ref_3;
+ *(pbuffer + 4) =
+ pdata->global_config__spad_enables_ref_4;
+ *(pbuffer + 5) =
+ pdata->global_config__spad_enables_ref_5 & 0xF;
+ *(pbuffer + 6) =
+ pdata->global_config__ref_en_start_select;
+ *(pbuffer + 7) =
+ pdata->ref_spad_man__num_requested_ref_spads & 0x3F;
+ *(pbuffer + 8) =
+ pdata->ref_spad_man__ref_location & 0x3;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->algo__crosstalk_compensation_plane_offset_kcps,
+ 2,
+ pbuffer + 9);
+ VL53L1_i2c_encode_int16_t(
+ pdata->algo__crosstalk_compensation_x_plane_gradient_kcps,
+ 2,
+ pbuffer + 11);
+ VL53L1_i2c_encode_int16_t(
+ pdata->algo__crosstalk_compensation_y_plane_gradient_kcps,
+ 2,
+ pbuffer + 13);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->ref_spad_char__total_rate_target_mcps,
+ 2,
+ pbuffer + 15);
+ VL53L1_i2c_encode_int16_t(
+ pdata->algo__part_to_part_range_offset_mm & 0x1FFF,
+ 2,
+ pbuffer + 17);
+ VL53L1_i2c_encode_int16_t(
+ pdata->mm_config__inner_offset_mm,
+ 2,
+ pbuffer + 19);
+ VL53L1_i2c_encode_int16_t(
+ pdata->mm_config__outer_offset_mm,
+ 2,
+ pbuffer + 21);
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_decode_customer_nvm_managed(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_customer_nvm_managed_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_customer_nvm_managed_t from the input I2C read buffer
+ * Buffer must be at least 23 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_CUSTOMER_NVM_MANAGED_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->global_config__spad_enables_ref_0 =
+ (*(pbuffer + 0));
+ pdata->global_config__spad_enables_ref_1 =
+ (*(pbuffer + 1));
+ pdata->global_config__spad_enables_ref_2 =
+ (*(pbuffer + 2));
+ pdata->global_config__spad_enables_ref_3 =
+ (*(pbuffer + 3));
+ pdata->global_config__spad_enables_ref_4 =
+ (*(pbuffer + 4));
+ pdata->global_config__spad_enables_ref_5 =
+ (*(pbuffer + 5)) & 0xF;
+ pdata->global_config__ref_en_start_select =
+ (*(pbuffer + 6));
+ pdata->ref_spad_man__num_requested_ref_spads =
+ (*(pbuffer + 7)) & 0x3F;
+ pdata->ref_spad_man__ref_location =
+ (*(pbuffer + 8)) & 0x3;
+ pdata->algo__crosstalk_compensation_plane_offset_kcps =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 9));
+ pdata->algo__crosstalk_compensation_x_plane_gradient_kcps =
+ (VL53L1_i2c_decode_int16_t(2, pbuffer + 11));
+ pdata->algo__crosstalk_compensation_y_plane_gradient_kcps =
+ (VL53L1_i2c_decode_int16_t(2, pbuffer + 13));
+ pdata->ref_spad_char__total_rate_target_mcps =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 15));
+ pdata->algo__part_to_part_range_offset_mm =
+ (VL53L1_i2c_decode_int16_t(2, pbuffer + 17)) & 0x1FFF;
+ pdata->mm_config__inner_offset_mm =
+ (VL53L1_i2c_decode_int16_t(2, pbuffer + 19));
+ pdata->mm_config__outer_offset_mm =
+ (VL53L1_i2c_decode_int16_t(2, pbuffer + 21));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_customer_nvm_managed(
+ VL53L1_DEV Dev,
+ VL53L1_customer_nvm_managed_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_customer_nvm_managed_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_CUSTOMER_NVM_MANAGED_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_customer_nvm_managed(
+ pdata,
+ VL53L1_CUSTOMER_NVM_MANAGED_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_REF_0,
+ comms_buffer,
+ VL53L1_CUSTOMER_NVM_MANAGED_I2C_SIZE_BYTES);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_get_customer_nvm_managed(
+ VL53L1_DEV Dev,
+ VL53L1_customer_nvm_managed_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_customer_nvm_managed_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_CUSTOMER_NVM_MANAGED_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_REF_0,
+ comms_buffer,
+ VL53L1_CUSTOMER_NVM_MANAGED_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_customer_nvm_managed(
+ VL53L1_CUSTOMER_NVM_MANAGED_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_encode_static_config(
+ VL53L1_static_config_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_static_config_t into a I2C write buffer
+ * Buffer must be at least 32 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_STATIC_CONFIG_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ VL53L1_i2c_encode_uint16_t(
+ pdata->dss_config__target_total_rate_mcps,
+ 2,
+ pbuffer + 0);
+ *(pbuffer + 2) =
+ pdata->debug__ctrl & 0x1;
+ *(pbuffer + 3) =
+ pdata->test_mode__ctrl & 0xF;
+ *(pbuffer + 4) =
+ pdata->clk_gating__ctrl & 0xF;
+ *(pbuffer + 5) =
+ pdata->nvm_bist__ctrl & 0x1F;
+ *(pbuffer + 6) =
+ pdata->nvm_bist__num_nvm_words & 0x7F;
+ *(pbuffer + 7) =
+ pdata->nvm_bist__start_address & 0x7F;
+ *(pbuffer + 8) =
+ pdata->host_if__status & 0x1;
+ *(pbuffer + 9) =
+ pdata->pad_i2c_hv__config;
+ *(pbuffer + 10) =
+ pdata->pad_i2c_hv__extsup_config & 0x1;
+ *(pbuffer + 11) =
+ pdata->gpio_hv_pad__ctrl & 0x3;
+ *(pbuffer + 12) =
+ pdata->gpio_hv_mux__ctrl & 0x1F;
+ *(pbuffer + 13) =
+ pdata->gpio__tio_hv_status & 0x3;
+ *(pbuffer + 14) =
+ pdata->gpio__fio_hv_status & 0x3;
+ *(pbuffer + 15) =
+ pdata->ana_config__spad_sel_pswidth & 0x7;
+ *(pbuffer + 16) =
+ pdata->ana_config__vcsel_pulse_width_offset & 0x1F;
+ *(pbuffer + 17) =
+ pdata->ana_config__fast_osc__config_ctrl & 0x1;
+ *(pbuffer + 18) =
+ pdata->sigma_estimator__effective_pulse_width_ns;
+ *(pbuffer + 19) =
+ pdata->sigma_estimator__effective_ambient_width_ns;
+ *(pbuffer + 20) =
+ pdata->sigma_estimator__sigma_ref_mm;
+ *(pbuffer + 21) =
+ pdata->algo__crosstalk_compensation_valid_height_mm;
+ *(pbuffer + 22) =
+ pdata->spare_host_config__static_config_spare_0;
+ *(pbuffer + 23) =
+ pdata->spare_host_config__static_config_spare_1;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->algo__range_ignore_threshold_mcps,
+ 2,
+ pbuffer + 24);
+ *(pbuffer + 26) =
+ pdata->algo__range_ignore_valid_height_mm;
+ *(pbuffer + 27) =
+ pdata->algo__range_min_clip;
+ *(pbuffer + 28) =
+ pdata->algo__consistency_check__tolerance & 0xF;
+ *(pbuffer + 29) =
+ pdata->spare_host_config__static_config_spare_2;
+ *(pbuffer + 30) =
+ pdata->sd_config__reset_stages_msb & 0xF;
+ *(pbuffer + 31) =
+ pdata->sd_config__reset_stages_lsb;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_decode_static_config(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_static_config_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_static_config_t from the input I2C read buffer
+ * Buffer must be at least 32 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_STATIC_CONFIG_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->dss_config__target_total_rate_mcps =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 0));
+ pdata->debug__ctrl =
+ (*(pbuffer + 2)) & 0x1;
+ pdata->test_mode__ctrl =
+ (*(pbuffer + 3)) & 0xF;
+ pdata->clk_gating__ctrl =
+ (*(pbuffer + 4)) & 0xF;
+ pdata->nvm_bist__ctrl =
+ (*(pbuffer + 5)) & 0x1F;
+ pdata->nvm_bist__num_nvm_words =
+ (*(pbuffer + 6)) & 0x7F;
+ pdata->nvm_bist__start_address =
+ (*(pbuffer + 7)) & 0x7F;
+ pdata->host_if__status =
+ (*(pbuffer + 8)) & 0x1;
+ pdata->pad_i2c_hv__config =
+ (*(pbuffer + 9));
+ pdata->pad_i2c_hv__extsup_config =
+ (*(pbuffer + 10)) & 0x1;
+ pdata->gpio_hv_pad__ctrl =
+ (*(pbuffer + 11)) & 0x3;
+ pdata->gpio_hv_mux__ctrl =
+ (*(pbuffer + 12)) & 0x1F;
+ pdata->gpio__tio_hv_status =
+ (*(pbuffer + 13)) & 0x3;
+ pdata->gpio__fio_hv_status =
+ (*(pbuffer + 14)) & 0x3;
+ pdata->ana_config__spad_sel_pswidth =
+ (*(pbuffer + 15)) & 0x7;
+ pdata->ana_config__vcsel_pulse_width_offset =
+ (*(pbuffer + 16)) & 0x1F;
+ pdata->ana_config__fast_osc__config_ctrl =
+ (*(pbuffer + 17)) & 0x1;
+ pdata->sigma_estimator__effective_pulse_width_ns =
+ (*(pbuffer + 18));
+ pdata->sigma_estimator__effective_ambient_width_ns =
+ (*(pbuffer + 19));
+ pdata->sigma_estimator__sigma_ref_mm =
+ (*(pbuffer + 20));
+ pdata->algo__crosstalk_compensation_valid_height_mm =
+ (*(pbuffer + 21));
+ pdata->spare_host_config__static_config_spare_0 =
+ (*(pbuffer + 22));
+ pdata->spare_host_config__static_config_spare_1 =
+ (*(pbuffer + 23));
+ pdata->algo__range_ignore_threshold_mcps =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 24));
+ pdata->algo__range_ignore_valid_height_mm =
+ (*(pbuffer + 26));
+ pdata->algo__range_min_clip =
+ (*(pbuffer + 27));
+ pdata->algo__consistency_check__tolerance =
+ (*(pbuffer + 28)) & 0xF;
+ pdata->spare_host_config__static_config_spare_2 =
+ (*(pbuffer + 29));
+ pdata->sd_config__reset_stages_msb =
+ (*(pbuffer + 30)) & 0xF;
+ pdata->sd_config__reset_stages_lsb =
+ (*(pbuffer + 31));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_static_config(
+ VL53L1_DEV Dev,
+ VL53L1_static_config_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_static_config_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_STATIC_CONFIG_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_static_config(
+ pdata,
+ VL53L1_STATIC_CONFIG_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_DSS_CONFIG__TARGET_TOTAL_RATE_MCPS,
+ comms_buffer,
+ VL53L1_STATIC_CONFIG_I2C_SIZE_BYTES);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_get_static_config(
+ VL53L1_DEV Dev,
+ VL53L1_static_config_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_static_config_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_STATIC_CONFIG_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_DSS_CONFIG__TARGET_TOTAL_RATE_MCPS,
+ comms_buffer,
+ VL53L1_STATIC_CONFIG_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_static_config(
+ VL53L1_STATIC_CONFIG_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_i2c_encode_general_config(
+ VL53L1_general_config_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_general_config_t into a I2C write buffer
+ * Buffer must be at least 22 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_GENERAL_CONFIG_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ *(pbuffer + 0) =
+ pdata->gph_config__stream_count_update_value;
+ *(pbuffer + 1) =
+ pdata->global_config__stream_divider;
+ *(pbuffer + 2) =
+ pdata->system__interrupt_config_gpio;
+ *(pbuffer + 3) =
+ pdata->cal_config__vcsel_start & 0x7F;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->cal_config__repeat_rate & 0xFFF,
+ 2,
+ pbuffer + 4);
+ *(pbuffer + 6) =
+ pdata->global_config__vcsel_width & 0x7F;
+ *(pbuffer + 7) =
+ pdata->phasecal_config__timeout_macrop;
+ *(pbuffer + 8) =
+ pdata->phasecal_config__target;
+ *(pbuffer + 9) =
+ pdata->phasecal_config__override & 0x1;
+ *(pbuffer + 11) =
+ pdata->dss_config__roi_mode_control & 0x7;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->system__thresh_rate_high,
+ 2,
+ pbuffer + 12);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->system__thresh_rate_low,
+ 2,
+ pbuffer + 14);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->dss_config__manual_effective_spads_select,
+ 2,
+ pbuffer + 16);
+ *(pbuffer + 18) =
+ pdata->dss_config__manual_block_select;
+ *(pbuffer + 19) =
+ pdata->dss_config__aperture_attenuation;
+ *(pbuffer + 20) =
+ pdata->dss_config__max_spads_limit;
+ *(pbuffer + 21) =
+ pdata->dss_config__min_spads_limit;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_decode_general_config(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_general_config_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_general_config_t from the input I2C read buffer
+ * Buffer must be at least 22 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_GENERAL_CONFIG_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->gph_config__stream_count_update_value =
+ (*(pbuffer + 0));
+ pdata->global_config__stream_divider =
+ (*(pbuffer + 1));
+ pdata->system__interrupt_config_gpio =
+ (*(pbuffer + 2));
+ pdata->cal_config__vcsel_start =
+ (*(pbuffer + 3)) & 0x7F;
+ pdata->cal_config__repeat_rate =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 4)) & 0xFFF;
+ pdata->global_config__vcsel_width =
+ (*(pbuffer + 6)) & 0x7F;
+ pdata->phasecal_config__timeout_macrop =
+ (*(pbuffer + 7));
+ pdata->phasecal_config__target =
+ (*(pbuffer + 8));
+ pdata->phasecal_config__override =
+ (*(pbuffer + 9)) & 0x1;
+ pdata->dss_config__roi_mode_control =
+ (*(pbuffer + 11)) & 0x7;
+ pdata->system__thresh_rate_high =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 12));
+ pdata->system__thresh_rate_low =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 14));
+ pdata->dss_config__manual_effective_spads_select =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 16));
+ pdata->dss_config__manual_block_select =
+ (*(pbuffer + 18));
+ pdata->dss_config__aperture_attenuation =
+ (*(pbuffer + 19));
+ pdata->dss_config__max_spads_limit =
+ (*(pbuffer + 20));
+ pdata->dss_config__min_spads_limit =
+ (*(pbuffer + 21));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_general_config(
+ VL53L1_DEV Dev,
+ VL53L1_general_config_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_general_config_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_GENERAL_CONFIG_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_general_config(
+ pdata,
+ VL53L1_GENERAL_CONFIG_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_GPH_CONFIG__STREAM_COUNT_UPDATE_VALUE,
+ comms_buffer,
+ VL53L1_GENERAL_CONFIG_I2C_SIZE_BYTES);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_get_general_config(
+ VL53L1_DEV Dev,
+ VL53L1_general_config_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_general_config_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_GENERAL_CONFIG_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_GPH_CONFIG__STREAM_COUNT_UPDATE_VALUE,
+ comms_buffer,
+ VL53L1_GENERAL_CONFIG_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_general_config(
+ VL53L1_GENERAL_CONFIG_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_i2c_encode_timing_config(
+ VL53L1_timing_config_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_timing_config_t into a I2C write buffer
+ * Buffer must be at least 23 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_TIMING_CONFIG_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ *(pbuffer + 0) =
+ pdata->mm_config__timeout_macrop_a_hi & 0xF;
+ *(pbuffer + 1) =
+ pdata->mm_config__timeout_macrop_a_lo;
+ *(pbuffer + 2) =
+ pdata->mm_config__timeout_macrop_b_hi & 0xF;
+ *(pbuffer + 3) =
+ pdata->mm_config__timeout_macrop_b_lo;
+ *(pbuffer + 4) =
+ pdata->range_config__timeout_macrop_a_hi & 0xF;
+ *(pbuffer + 5) =
+ pdata->range_config__timeout_macrop_a_lo;
+ *(pbuffer + 6) =
+ pdata->range_config__vcsel_period_a & 0x3F;
+ *(pbuffer + 7) =
+ pdata->range_config__timeout_macrop_b_hi & 0xF;
+ *(pbuffer + 8) =
+ pdata->range_config__timeout_macrop_b_lo;
+ *(pbuffer + 9) =
+ pdata->range_config__vcsel_period_b & 0x3F;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->range_config__sigma_thresh,
+ 2,
+ pbuffer + 10);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->range_config__min_count_rate_rtn_limit_mcps,
+ 2,
+ pbuffer + 12);
+ *(pbuffer + 14) =
+ pdata->range_config__valid_phase_low;
+ *(pbuffer + 15) =
+ pdata->range_config__valid_phase_high;
+ VL53L1_i2c_encode_uint32_t(
+ pdata->system__intermeasurement_period,
+ 4,
+ pbuffer + 18);
+ *(pbuffer + 22) =
+ pdata->system__fractional_enable & 0x1;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_decode_timing_config(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_timing_config_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_timing_config_t from the input I2C read buffer
+ * Buffer must be at least 23 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_TIMING_CONFIG_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->mm_config__timeout_macrop_a_hi =
+ (*(pbuffer + 0)) & 0xF;
+ pdata->mm_config__timeout_macrop_a_lo =
+ (*(pbuffer + 1));
+ pdata->mm_config__timeout_macrop_b_hi =
+ (*(pbuffer + 2)) & 0xF;
+ pdata->mm_config__timeout_macrop_b_lo =
+ (*(pbuffer + 3));
+ pdata->range_config__timeout_macrop_a_hi =
+ (*(pbuffer + 4)) & 0xF;
+ pdata->range_config__timeout_macrop_a_lo =
+ (*(pbuffer + 5));
+ pdata->range_config__vcsel_period_a =
+ (*(pbuffer + 6)) & 0x3F;
+ pdata->range_config__timeout_macrop_b_hi =
+ (*(pbuffer + 7)) & 0xF;
+ pdata->range_config__timeout_macrop_b_lo =
+ (*(pbuffer + 8));
+ pdata->range_config__vcsel_period_b =
+ (*(pbuffer + 9)) & 0x3F;
+ pdata->range_config__sigma_thresh =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 10));
+ pdata->range_config__min_count_rate_rtn_limit_mcps =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 12));
+ pdata->range_config__valid_phase_low =
+ (*(pbuffer + 14));
+ pdata->range_config__valid_phase_high =
+ (*(pbuffer + 15));
+ pdata->system__intermeasurement_period =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 18));
+ pdata->system__fractional_enable =
+ (*(pbuffer + 22)) & 0x1;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_set_timing_config(
+ VL53L1_DEV Dev,
+ VL53L1_timing_config_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_timing_config_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_TIMING_CONFIG_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_timing_config(
+ pdata,
+ VL53L1_TIMING_CONFIG_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_MM_CONFIG__TIMEOUT_MACROP_A_HI,
+ comms_buffer,
+ VL53L1_TIMING_CONFIG_I2C_SIZE_BYTES);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_get_timing_config(
+ VL53L1_DEV Dev,
+ VL53L1_timing_config_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_timing_config_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_TIMING_CONFIG_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_MM_CONFIG__TIMEOUT_MACROP_A_HI,
+ comms_buffer,
+ VL53L1_TIMING_CONFIG_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_timing_config(
+ VL53L1_TIMING_CONFIG_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_i2c_encode_dynamic_config(
+ VL53L1_dynamic_config_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_dynamic_config_t into a I2C write buffer
+ * Buffer must be at least 18 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_DYNAMIC_CONFIG_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ *(pbuffer + 0) =
+ pdata->system__grouped_parameter_hold_0 & 0x3;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->system__thresh_high,
+ 2,
+ pbuffer + 1);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->system__thresh_low,
+ 2,
+ pbuffer + 3);
+ *(pbuffer + 5) =
+ pdata->system__enable_xtalk_per_quadrant & 0x1;
+ *(pbuffer + 6) =
+ pdata->system__seed_config & 0x7;
+ *(pbuffer + 7) =
+ pdata->sd_config__woi_sd0;
+ *(pbuffer + 8) =
+ pdata->sd_config__woi_sd1;
+ *(pbuffer + 9) =
+ pdata->sd_config__initial_phase_sd0 & 0x7F;
+ *(pbuffer + 10) =
+ pdata->sd_config__initial_phase_sd1 & 0x7F;
+ *(pbuffer + 11) =
+ pdata->system__grouped_parameter_hold_1 & 0x3;
+ *(pbuffer + 12) =
+ pdata->sd_config__first_order_select & 0x3;
+ *(pbuffer + 13) =
+ pdata->sd_config__quantifier & 0xF;
+ *(pbuffer + 14) =
+ pdata->roi_config__user_roi_centre_spad;
+ *(pbuffer + 15) =
+ pdata->roi_config__user_roi_requested_global_xy_size;
+ *(pbuffer + 16) =
+ pdata->system__sequence_config;
+ *(pbuffer + 17) =
+ pdata->system__grouped_parameter_hold & 0x3;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_decode_dynamic_config(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_dynamic_config_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_dynamic_config_t from the input I2C read buffer
+ * Buffer must be at least 18 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_DYNAMIC_CONFIG_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->system__grouped_parameter_hold_0 =
+ (*(pbuffer + 0)) & 0x3;
+ pdata->system__thresh_high =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 1));
+ pdata->system__thresh_low =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 3));
+ pdata->system__enable_xtalk_per_quadrant =
+ (*(pbuffer + 5)) & 0x1;
+ pdata->system__seed_config =
+ (*(pbuffer + 6)) & 0x7;
+ pdata->sd_config__woi_sd0 =
+ (*(pbuffer + 7));
+ pdata->sd_config__woi_sd1 =
+ (*(pbuffer + 8));
+ pdata->sd_config__initial_phase_sd0 =
+ (*(pbuffer + 9)) & 0x7F;
+ pdata->sd_config__initial_phase_sd1 =
+ (*(pbuffer + 10)) & 0x7F;
+ pdata->system__grouped_parameter_hold_1 =
+ (*(pbuffer + 11)) & 0x3;
+ pdata->sd_config__first_order_select =
+ (*(pbuffer + 12)) & 0x3;
+ pdata->sd_config__quantifier =
+ (*(pbuffer + 13)) & 0xF;
+ pdata->roi_config__user_roi_centre_spad =
+ (*(pbuffer + 14));
+ pdata->roi_config__user_roi_requested_global_xy_size =
+ (*(pbuffer + 15));
+ pdata->system__sequence_config =
+ (*(pbuffer + 16));
+ pdata->system__grouped_parameter_hold =
+ (*(pbuffer + 17)) & 0x3;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_set_dynamic_config(
+ VL53L1_DEV Dev,
+ VL53L1_dynamic_config_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_dynamic_config_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_DYNAMIC_CONFIG_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_dynamic_config(
+ pdata,
+ VL53L1_DYNAMIC_CONFIG_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_SYSTEM__GROUPED_PARAMETER_HOLD_0,
+ comms_buffer,
+ VL53L1_DYNAMIC_CONFIG_I2C_SIZE_BYTES);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_get_dynamic_config(
+ VL53L1_DEV Dev,
+ VL53L1_dynamic_config_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_dynamic_config_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_DYNAMIC_CONFIG_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_SYSTEM__GROUPED_PARAMETER_HOLD_0,
+ comms_buffer,
+ VL53L1_DYNAMIC_CONFIG_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_dynamic_config(
+ VL53L1_DYNAMIC_CONFIG_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_i2c_encode_system_control(
+ VL53L1_system_control_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_system_control_t into a I2C write buffer
+ * Buffer must be at least 5 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_SYSTEM_CONTROL_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ *(pbuffer + 0) =
+ pdata->power_management__go1_power_force & 0x1;
+ *(pbuffer + 1) =
+ pdata->system__stream_count_ctrl & 0x1;
+ *(pbuffer + 2) =
+ pdata->firmware__enable & 0x1;
+ *(pbuffer + 3) =
+ pdata->system__interrupt_clear & 0x3;
+ *(pbuffer + 4) =
+ pdata->system__mode_start;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_decode_system_control(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_system_control_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_system_control_t from the input I2C read buffer
+ * Buffer must be at least 5 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_SYSTEM_CONTROL_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->power_management__go1_power_force =
+ (*(pbuffer + 0)) & 0x1;
+ pdata->system__stream_count_ctrl =
+ (*(pbuffer + 1)) & 0x1;
+ pdata->firmware__enable =
+ (*(pbuffer + 2)) & 0x1;
+ pdata->system__interrupt_clear =
+ (*(pbuffer + 3)) & 0x3;
+ pdata->system__mode_start =
+ (*(pbuffer + 4));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_set_system_control(
+ VL53L1_DEV Dev,
+ VL53L1_system_control_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_system_control_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_SYSTEM_CONTROL_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_system_control(
+ pdata,
+ VL53L1_SYSTEM_CONTROL_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_POWER_MANAGEMENT__GO1_POWER_FORCE,
+ comms_buffer,
+ VL53L1_SYSTEM_CONTROL_I2C_SIZE_BYTES);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_get_system_control(
+ VL53L1_DEV Dev,
+ VL53L1_system_control_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_system_control_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_SYSTEM_CONTROL_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_POWER_MANAGEMENT__GO1_POWER_FORCE,
+ comms_buffer,
+ VL53L1_SYSTEM_CONTROL_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_system_control(
+ VL53L1_SYSTEM_CONTROL_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_encode_system_results(
+ VL53L1_system_results_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_system_results_t into a I2C write buffer
+ * Buffer must be at least 44 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_SYSTEM_RESULTS_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ *(pbuffer + 0) =
+ pdata->result__interrupt_status & 0x3F;
+ *(pbuffer + 1) =
+ pdata->result__range_status;
+ *(pbuffer + 2) =
+ pdata->result__report_status & 0xF;
+ *(pbuffer + 3) =
+ pdata->result__stream_count;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__dss_actual_effective_spads_sd0,
+ 2,
+ pbuffer + 4);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__peak_signal_count_rate_mcps_sd0,
+ 2,
+ pbuffer + 6);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__ambient_count_rate_mcps_sd0,
+ 2,
+ pbuffer + 8);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__sigma_sd0,
+ 2,
+ pbuffer + 10);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__phase_sd0,
+ 2,
+ pbuffer + 12);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__final_crosstalk_corrected_range_mm_sd0,
+ 2,
+ pbuffer + 14);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0,
+ 2,
+ pbuffer + 16);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__mm_inner_actual_effective_spads_sd0,
+ 2,
+ pbuffer + 18);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__mm_outer_actual_effective_spads_sd0,
+ 2,
+ pbuffer + 20);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__avg_signal_count_rate_mcps_sd0,
+ 2,
+ pbuffer + 22);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__dss_actual_effective_spads_sd1,
+ 2,
+ pbuffer + 24);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__peak_signal_count_rate_mcps_sd1,
+ 2,
+ pbuffer + 26);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__ambient_count_rate_mcps_sd1,
+ 2,
+ pbuffer + 28);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__sigma_sd1,
+ 2,
+ pbuffer + 30);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__phase_sd1,
+ 2,
+ pbuffer + 32);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__final_crosstalk_corrected_range_mm_sd1,
+ 2,
+ pbuffer + 34);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__spare_0_sd1,
+ 2,
+ pbuffer + 36);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__spare_1_sd1,
+ 2,
+ pbuffer + 38);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__spare_2_sd1,
+ 2,
+ pbuffer + 40);
+ *(pbuffer + 42) =
+ pdata->result__spare_3_sd1;
+ *(pbuffer + 43) =
+ pdata->result__thresh_info;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_i2c_decode_system_results(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_system_results_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_system_results_t from the input I2C read buffer
+ * Buffer must be at least 44 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_SYSTEM_RESULTS_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->result__interrupt_status =
+ (*(pbuffer + 0)) & 0x3F;
+ pdata->result__range_status =
+ (*(pbuffer + 1));
+ pdata->result__report_status =
+ (*(pbuffer + 2)) & 0xF;
+ pdata->result__stream_count =
+ (*(pbuffer + 3));
+ pdata->result__dss_actual_effective_spads_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 4));
+ pdata->result__peak_signal_count_rate_mcps_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 6));
+ pdata->result__ambient_count_rate_mcps_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 8));
+ pdata->result__sigma_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 10));
+ pdata->result__phase_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 12));
+ pdata->result__final_crosstalk_corrected_range_mm_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 14));
+ pdata->result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 16));
+ pdata->result__mm_inner_actual_effective_spads_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 18));
+ pdata->result__mm_outer_actual_effective_spads_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 20));
+ pdata->result__avg_signal_count_rate_mcps_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 22));
+ pdata->result__dss_actual_effective_spads_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 24));
+ pdata->result__peak_signal_count_rate_mcps_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 26));
+ pdata->result__ambient_count_rate_mcps_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 28));
+ pdata->result__sigma_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 30));
+ pdata->result__phase_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 32));
+ pdata->result__final_crosstalk_corrected_range_mm_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 34));
+ pdata->result__spare_0_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 36));
+ pdata->result__spare_1_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 38));
+ pdata->result__spare_2_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 40));
+ pdata->result__spare_3_sd1 =
+ (*(pbuffer + 42));
+ pdata->result__thresh_info =
+ (*(pbuffer + 43));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_set_system_results(
+ VL53L1_DEV Dev,
+ VL53L1_system_results_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_system_results_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_SYSTEM_RESULTS_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_system_results(
+ pdata,
+ VL53L1_SYSTEM_RESULTS_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_RESULT__INTERRUPT_STATUS,
+ comms_buffer,
+ VL53L1_SYSTEM_RESULTS_I2C_SIZE_BYTES);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_get_system_results(
+ VL53L1_DEV Dev,
+ VL53L1_system_results_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_system_results_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_SYSTEM_RESULTS_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_RESULT__INTERRUPT_STATUS,
+ comms_buffer,
+ VL53L1_SYSTEM_RESULTS_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_system_results(
+ VL53L1_SYSTEM_RESULTS_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_encode_core_results(
+ VL53L1_core_results_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_core_results_t into a I2C write buffer
+ * Buffer must be at least 33 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_CORE_RESULTS_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ VL53L1_i2c_encode_uint32_t(
+ pdata->result_core__ambient_window_events_sd0,
+ 4,
+ pbuffer + 0);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->result_core__ranging_total_events_sd0,
+ 4,
+ pbuffer + 4);
+ VL53L1_i2c_encode_int32_t(
+ pdata->result_core__signal_total_events_sd0,
+ 4,
+ pbuffer + 8);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->result_core__total_periods_elapsed_sd0,
+ 4,
+ pbuffer + 12);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->result_core__ambient_window_events_sd1,
+ 4,
+ pbuffer + 16);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->result_core__ranging_total_events_sd1,
+ 4,
+ pbuffer + 20);
+ VL53L1_i2c_encode_int32_t(
+ pdata->result_core__signal_total_events_sd1,
+ 4,
+ pbuffer + 24);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->result_core__total_periods_elapsed_sd1,
+ 4,
+ pbuffer + 28);
+ *(pbuffer + 32) =
+ pdata->result_core__spare_0;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_i2c_decode_core_results(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_core_results_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_core_results_t from the input I2C read buffer
+ * Buffer must be at least 33 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_CORE_RESULTS_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->result_core__ambient_window_events_sd0 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 0));
+ pdata->result_core__ranging_total_events_sd0 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 4));
+ pdata->result_core__signal_total_events_sd0 =
+ (VL53L1_i2c_decode_int32_t(4, pbuffer + 8));
+ pdata->result_core__total_periods_elapsed_sd0 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 12));
+ pdata->result_core__ambient_window_events_sd1 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 16));
+ pdata->result_core__ranging_total_events_sd1 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 20));
+ pdata->result_core__signal_total_events_sd1 =
+ (VL53L1_i2c_decode_int32_t(4, pbuffer + 24));
+ pdata->result_core__total_periods_elapsed_sd1 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 28));
+ pdata->result_core__spare_0 =
+ (*(pbuffer + 32));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_set_core_results(
+ VL53L1_DEV Dev,
+ VL53L1_core_results_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_core_results_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_CORE_RESULTS_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_core_results(
+ pdata,
+ VL53L1_CORE_RESULTS_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0,
+ comms_buffer,
+ VL53L1_CORE_RESULTS_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_get_core_results(
+ VL53L1_DEV Dev,
+ VL53L1_core_results_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_core_results_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_CORE_RESULTS_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0,
+ comms_buffer,
+ VL53L1_CORE_RESULTS_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_core_results(
+ VL53L1_CORE_RESULTS_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_i2c_encode_debug_results(
+ VL53L1_debug_results_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_debug_results_t into a I2C write buffer
+ * Buffer must be at least 56 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_DEBUG_RESULTS_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ VL53L1_i2c_encode_uint16_t(
+ pdata->phasecal_result__reference_phase,
+ 2,
+ pbuffer + 0);
+ *(pbuffer + 2) =
+ pdata->phasecal_result__vcsel_start & 0x7F;
+ *(pbuffer + 3) =
+ pdata->ref_spad_char_result__num_actual_ref_spads & 0x3F;
+ *(pbuffer + 4) =
+ pdata->ref_spad_char_result__ref_location & 0x3;
+ *(pbuffer + 5) =
+ pdata->vhv_result__coldboot_status & 0x1;
+ *(pbuffer + 6) =
+ pdata->vhv_result__search_result & 0x3F;
+ *(pbuffer + 7) =
+ pdata->vhv_result__latest_setting & 0x3F;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->result__osc_calibrate_val & 0x3FF,
+ 2,
+ pbuffer + 8);
+ *(pbuffer + 10) =
+ pdata->ana_config__powerdown_go1 & 0x3;
+ *(pbuffer + 11) =
+ pdata->ana_config__ref_bg_ctrl & 0x3;
+ *(pbuffer + 12) =
+ pdata->ana_config__regdvdd1v2_ctrl & 0xF;
+ *(pbuffer + 13) =
+ pdata->ana_config__osc_slow_ctrl & 0x7;
+ *(pbuffer + 14) =
+ pdata->test_mode__status & 0x1;
+ *(pbuffer + 15) =
+ pdata->firmware__system_status & 0x3;
+ *(pbuffer + 16) =
+ pdata->firmware__mode_status;
+ *(pbuffer + 17) =
+ pdata->firmware__secondary_mode_status;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->firmware__cal_repeat_rate_counter & 0xFFF,
+ 2,
+ pbuffer + 18);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->gph__system__thresh_high,
+ 2,
+ pbuffer + 22);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->gph__system__thresh_low,
+ 2,
+ pbuffer + 24);
+ *(pbuffer + 26) =
+ pdata->gph__system__enable_xtalk_per_quadrant & 0x1;
+ *(pbuffer + 27) =
+ pdata->gph__spare_0 & 0x7;
+ *(pbuffer + 28) =
+ pdata->gph__sd_config__woi_sd0;
+ *(pbuffer + 29) =
+ pdata->gph__sd_config__woi_sd1;
+ *(pbuffer + 30) =
+ pdata->gph__sd_config__initial_phase_sd0 & 0x7F;
+ *(pbuffer + 31) =
+ pdata->gph__sd_config__initial_phase_sd1 & 0x7F;
+ *(pbuffer + 32) =
+ pdata->gph__sd_config__first_order_select & 0x3;
+ *(pbuffer + 33) =
+ pdata->gph__sd_config__quantifier & 0xF;
+ *(pbuffer + 34) =
+ pdata->gph__roi_config__user_roi_centre_spad;
+ *(pbuffer + 35) =
+ pdata->gph__roi_config__user_roi_requested_global_xy_size;
+ *(pbuffer + 36) =
+ pdata->gph__system__sequence_config;
+ *(pbuffer + 37) =
+ pdata->gph__gph_id & 0x1;
+ *(pbuffer + 38) =
+ pdata->system__interrupt_set & 0x3;
+ *(pbuffer + 39) =
+ pdata->interrupt_manager__enables & 0x1F;
+ *(pbuffer + 40) =
+ pdata->interrupt_manager__clear & 0x1F;
+ *(pbuffer + 41) =
+ pdata->interrupt_manager__status & 0x1F;
+ *(pbuffer + 42) =
+ pdata->mcu_to_host_bank__wr_access_en & 0x1;
+ *(pbuffer + 43) =
+ pdata->power_management__go1_reset_status & 0x1;
+ *(pbuffer + 44) =
+ pdata->pad_startup_mode__value_ro & 0x3;
+ *(pbuffer + 45) =
+ pdata->pad_startup_mode__value_ctrl & 0x3F;
+ VL53L1_i2c_encode_uint32_t(
+ pdata->pll_period_us & 0x3FFFF,
+ 4,
+ pbuffer + 46);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->interrupt_scheduler__data_out,
+ 4,
+ pbuffer + 50);
+ *(pbuffer + 54) =
+ pdata->nvm_bist__complete & 0x1;
+ *(pbuffer + 55) =
+ pdata->nvm_bist__status & 0x1;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_i2c_decode_debug_results(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_debug_results_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_debug_results_t from the input I2C read buffer
+ * Buffer must be at least 56 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_DEBUG_RESULTS_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->phasecal_result__reference_phase =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 0));
+ pdata->phasecal_result__vcsel_start =
+ (*(pbuffer + 2)) & 0x7F;
+ pdata->ref_spad_char_result__num_actual_ref_spads =
+ (*(pbuffer + 3)) & 0x3F;
+ pdata->ref_spad_char_result__ref_location =
+ (*(pbuffer + 4)) & 0x3;
+ pdata->vhv_result__coldboot_status =
+ (*(pbuffer + 5)) & 0x1;
+ pdata->vhv_result__search_result =
+ (*(pbuffer + 6)) & 0x3F;
+ pdata->vhv_result__latest_setting =
+ (*(pbuffer + 7)) & 0x3F;
+ pdata->result__osc_calibrate_val =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 8)) & 0x3FF;
+ pdata->ana_config__powerdown_go1 =
+ (*(pbuffer + 10)) & 0x3;
+ pdata->ana_config__ref_bg_ctrl =
+ (*(pbuffer + 11)) & 0x3;
+ pdata->ana_config__regdvdd1v2_ctrl =
+ (*(pbuffer + 12)) & 0xF;
+ pdata->ana_config__osc_slow_ctrl =
+ (*(pbuffer + 13)) & 0x7;
+ pdata->test_mode__status =
+ (*(pbuffer + 14)) & 0x1;
+ pdata->firmware__system_status =
+ (*(pbuffer + 15)) & 0x3;
+ pdata->firmware__mode_status =
+ (*(pbuffer + 16));
+ pdata->firmware__secondary_mode_status =
+ (*(pbuffer + 17));
+ pdata->firmware__cal_repeat_rate_counter =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 18)) & 0xFFF;
+ pdata->gph__system__thresh_high =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 22));
+ pdata->gph__system__thresh_low =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 24));
+ pdata->gph__system__enable_xtalk_per_quadrant =
+ (*(pbuffer + 26)) & 0x1;
+ pdata->gph__spare_0 =
+ (*(pbuffer + 27)) & 0x7;
+ pdata->gph__sd_config__woi_sd0 =
+ (*(pbuffer + 28));
+ pdata->gph__sd_config__woi_sd1 =
+ (*(pbuffer + 29));
+ pdata->gph__sd_config__initial_phase_sd0 =
+ (*(pbuffer + 30)) & 0x7F;
+ pdata->gph__sd_config__initial_phase_sd1 =
+ (*(pbuffer + 31)) & 0x7F;
+ pdata->gph__sd_config__first_order_select =
+ (*(pbuffer + 32)) & 0x3;
+ pdata->gph__sd_config__quantifier =
+ (*(pbuffer + 33)) & 0xF;
+ pdata->gph__roi_config__user_roi_centre_spad =
+ (*(pbuffer + 34));
+ pdata->gph__roi_config__user_roi_requested_global_xy_size =
+ (*(pbuffer + 35));
+ pdata->gph__system__sequence_config =
+ (*(pbuffer + 36));
+ pdata->gph__gph_id =
+ (*(pbuffer + 37)) & 0x1;
+ pdata->system__interrupt_set =
+ (*(pbuffer + 38)) & 0x3;
+ pdata->interrupt_manager__enables =
+ (*(pbuffer + 39)) & 0x1F;
+ pdata->interrupt_manager__clear =
+ (*(pbuffer + 40)) & 0x1F;
+ pdata->interrupt_manager__status =
+ (*(pbuffer + 41)) & 0x1F;
+ pdata->mcu_to_host_bank__wr_access_en =
+ (*(pbuffer + 42)) & 0x1;
+ pdata->power_management__go1_reset_status =
+ (*(pbuffer + 43)) & 0x1;
+ pdata->pad_startup_mode__value_ro =
+ (*(pbuffer + 44)) & 0x3;
+ pdata->pad_startup_mode__value_ctrl =
+ (*(pbuffer + 45)) & 0x3F;
+ pdata->pll_period_us =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 46)) & 0x3FFFF;
+ pdata->interrupt_scheduler__data_out =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 50));
+ pdata->nvm_bist__complete =
+ (*(pbuffer + 54)) & 0x1;
+ pdata->nvm_bist__status =
+ (*(pbuffer + 55)) & 0x1;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_set_debug_results(
+ VL53L1_DEV Dev,
+ VL53L1_debug_results_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_debug_results_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_DEBUG_RESULTS_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_debug_results(
+ pdata,
+ VL53L1_DEBUG_RESULTS_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_PHASECAL_RESULT__REFERENCE_PHASE,
+ comms_buffer,
+ VL53L1_DEBUG_RESULTS_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_get_debug_results(
+ VL53L1_DEV Dev,
+ VL53L1_debug_results_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_debug_results_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_DEBUG_RESULTS_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_PHASECAL_RESULT__REFERENCE_PHASE,
+ comms_buffer,
+ VL53L1_DEBUG_RESULTS_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_debug_results(
+ VL53L1_DEBUG_RESULTS_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_encode_nvm_copy_data(
+ VL53L1_nvm_copy_data_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_nvm_copy_data_t into a I2C write buffer
+ * Buffer must be at least 49 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_NVM_COPY_DATA_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ *(pbuffer + 0) =
+ pdata->identification__model_id;
+ *(pbuffer + 1) =
+ pdata->identification__module_type;
+ *(pbuffer + 2) =
+ pdata->identification__revision_id;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->identification__module_id,
+ 2,
+ pbuffer + 3);
+ *(pbuffer + 5) =
+ pdata->ana_config__fast_osc__trim_max & 0x7F;
+ *(pbuffer + 6) =
+ pdata->ana_config__fast_osc__freq_set & 0x7;
+ *(pbuffer + 7) =
+ pdata->ana_config__vcsel_trim & 0x7;
+ *(pbuffer + 8) =
+ pdata->ana_config__vcsel_selion & 0x3F;
+ *(pbuffer + 9) =
+ pdata->ana_config__vcsel_selion_max & 0x3F;
+ *(pbuffer + 10) =
+ pdata->protected_laser_safety__lock_bit & 0x1;
+ *(pbuffer + 11) =
+ pdata->laser_safety__key & 0x7F;
+ *(pbuffer + 12) =
+ pdata->laser_safety__key_ro & 0x1;
+ *(pbuffer + 13) =
+ pdata->laser_safety__clip & 0x3F;
+ *(pbuffer + 14) =
+ pdata->laser_safety__mult & 0x3F;
+ *(pbuffer + 15) =
+ pdata->global_config__spad_enables_rtn_0;
+ *(pbuffer + 16) =
+ pdata->global_config__spad_enables_rtn_1;
+ *(pbuffer + 17) =
+ pdata->global_config__spad_enables_rtn_2;
+ *(pbuffer + 18) =
+ pdata->global_config__spad_enables_rtn_3;
+ *(pbuffer + 19) =
+ pdata->global_config__spad_enables_rtn_4;
+ *(pbuffer + 20) =
+ pdata->global_config__spad_enables_rtn_5;
+ *(pbuffer + 21) =
+ pdata->global_config__spad_enables_rtn_6;
+ *(pbuffer + 22) =
+ pdata->global_config__spad_enables_rtn_7;
+ *(pbuffer + 23) =
+ pdata->global_config__spad_enables_rtn_8;
+ *(pbuffer + 24) =
+ pdata->global_config__spad_enables_rtn_9;
+ *(pbuffer + 25) =
+ pdata->global_config__spad_enables_rtn_10;
+ *(pbuffer + 26) =
+ pdata->global_config__spad_enables_rtn_11;
+ *(pbuffer + 27) =
+ pdata->global_config__spad_enables_rtn_12;
+ *(pbuffer + 28) =
+ pdata->global_config__spad_enables_rtn_13;
+ *(pbuffer + 29) =
+ pdata->global_config__spad_enables_rtn_14;
+ *(pbuffer + 30) =
+ pdata->global_config__spad_enables_rtn_15;
+ *(pbuffer + 31) =
+ pdata->global_config__spad_enables_rtn_16;
+ *(pbuffer + 32) =
+ pdata->global_config__spad_enables_rtn_17;
+ *(pbuffer + 33) =
+ pdata->global_config__spad_enables_rtn_18;
+ *(pbuffer + 34) =
+ pdata->global_config__spad_enables_rtn_19;
+ *(pbuffer + 35) =
+ pdata->global_config__spad_enables_rtn_20;
+ *(pbuffer + 36) =
+ pdata->global_config__spad_enables_rtn_21;
+ *(pbuffer + 37) =
+ pdata->global_config__spad_enables_rtn_22;
+ *(pbuffer + 38) =
+ pdata->global_config__spad_enables_rtn_23;
+ *(pbuffer + 39) =
+ pdata->global_config__spad_enables_rtn_24;
+ *(pbuffer + 40) =
+ pdata->global_config__spad_enables_rtn_25;
+ *(pbuffer + 41) =
+ pdata->global_config__spad_enables_rtn_26;
+ *(pbuffer + 42) =
+ pdata->global_config__spad_enables_rtn_27;
+ *(pbuffer + 43) =
+ pdata->global_config__spad_enables_rtn_28;
+ *(pbuffer + 44) =
+ pdata->global_config__spad_enables_rtn_29;
+ *(pbuffer + 45) =
+ pdata->global_config__spad_enables_rtn_30;
+ *(pbuffer + 46) =
+ pdata->global_config__spad_enables_rtn_31;
+ *(pbuffer + 47) =
+ pdata->roi_config__mode_roi_centre_spad;
+ *(pbuffer + 48) =
+ pdata->roi_config__mode_roi_xy_size;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_i2c_decode_nvm_copy_data(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_nvm_copy_data_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_nvm_copy_data_t from the input I2C read buffer
+ * Buffer must be at least 49 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_NVM_COPY_DATA_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->identification__model_id =
+ (*(pbuffer + 0));
+ pdata->identification__module_type =
+ (*(pbuffer + 1));
+ pdata->identification__revision_id =
+ (*(pbuffer + 2));
+ pdata->identification__module_id =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 3));
+ pdata->ana_config__fast_osc__trim_max =
+ (*(pbuffer + 5)) & 0x7F;
+ pdata->ana_config__fast_osc__freq_set =
+ (*(pbuffer + 6)) & 0x7;
+ pdata->ana_config__vcsel_trim =
+ (*(pbuffer + 7)) & 0x7;
+ pdata->ana_config__vcsel_selion =
+ (*(pbuffer + 8)) & 0x3F;
+ pdata->ana_config__vcsel_selion_max =
+ (*(pbuffer + 9)) & 0x3F;
+ pdata->protected_laser_safety__lock_bit =
+ (*(pbuffer + 10)) & 0x1;
+ pdata->laser_safety__key =
+ (*(pbuffer + 11)) & 0x7F;
+ pdata->laser_safety__key_ro =
+ (*(pbuffer + 12)) & 0x1;
+ pdata->laser_safety__clip =
+ (*(pbuffer + 13)) & 0x3F;
+ pdata->laser_safety__mult =
+ (*(pbuffer + 14)) & 0x3F;
+ pdata->global_config__spad_enables_rtn_0 =
+ (*(pbuffer + 15));
+ pdata->global_config__spad_enables_rtn_1 =
+ (*(pbuffer + 16));
+ pdata->global_config__spad_enables_rtn_2 =
+ (*(pbuffer + 17));
+ pdata->global_config__spad_enables_rtn_3 =
+ (*(pbuffer + 18));
+ pdata->global_config__spad_enables_rtn_4 =
+ (*(pbuffer + 19));
+ pdata->global_config__spad_enables_rtn_5 =
+ (*(pbuffer + 20));
+ pdata->global_config__spad_enables_rtn_6 =
+ (*(pbuffer + 21));
+ pdata->global_config__spad_enables_rtn_7 =
+ (*(pbuffer + 22));
+ pdata->global_config__spad_enables_rtn_8 =
+ (*(pbuffer + 23));
+ pdata->global_config__spad_enables_rtn_9 =
+ (*(pbuffer + 24));
+ pdata->global_config__spad_enables_rtn_10 =
+ (*(pbuffer + 25));
+ pdata->global_config__spad_enables_rtn_11 =
+ (*(pbuffer + 26));
+ pdata->global_config__spad_enables_rtn_12 =
+ (*(pbuffer + 27));
+ pdata->global_config__spad_enables_rtn_13 =
+ (*(pbuffer + 28));
+ pdata->global_config__spad_enables_rtn_14 =
+ (*(pbuffer + 29));
+ pdata->global_config__spad_enables_rtn_15 =
+ (*(pbuffer + 30));
+ pdata->global_config__spad_enables_rtn_16 =
+ (*(pbuffer + 31));
+ pdata->global_config__spad_enables_rtn_17 =
+ (*(pbuffer + 32));
+ pdata->global_config__spad_enables_rtn_18 =
+ (*(pbuffer + 33));
+ pdata->global_config__spad_enables_rtn_19 =
+ (*(pbuffer + 34));
+ pdata->global_config__spad_enables_rtn_20 =
+ (*(pbuffer + 35));
+ pdata->global_config__spad_enables_rtn_21 =
+ (*(pbuffer + 36));
+ pdata->global_config__spad_enables_rtn_22 =
+ (*(pbuffer + 37));
+ pdata->global_config__spad_enables_rtn_23 =
+ (*(pbuffer + 38));
+ pdata->global_config__spad_enables_rtn_24 =
+ (*(pbuffer + 39));
+ pdata->global_config__spad_enables_rtn_25 =
+ (*(pbuffer + 40));
+ pdata->global_config__spad_enables_rtn_26 =
+ (*(pbuffer + 41));
+ pdata->global_config__spad_enables_rtn_27 =
+ (*(pbuffer + 42));
+ pdata->global_config__spad_enables_rtn_28 =
+ (*(pbuffer + 43));
+ pdata->global_config__spad_enables_rtn_29 =
+ (*(pbuffer + 44));
+ pdata->global_config__spad_enables_rtn_30 =
+ (*(pbuffer + 45));
+ pdata->global_config__spad_enables_rtn_31 =
+ (*(pbuffer + 46));
+ pdata->roi_config__mode_roi_centre_spad =
+ (*(pbuffer + 47));
+ pdata->roi_config__mode_roi_xy_size =
+ (*(pbuffer + 48));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_set_nvm_copy_data(
+ VL53L1_DEV Dev,
+ VL53L1_nvm_copy_data_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_nvm_copy_data_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_NVM_COPY_DATA_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_nvm_copy_data(
+ pdata,
+ VL53L1_NVM_COPY_DATA_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_IDENTIFICATION__MODEL_ID,
+ comms_buffer,
+ VL53L1_NVM_COPY_DATA_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+VL53L1_Error VL53L1_get_nvm_copy_data(
+ VL53L1_DEV Dev,
+ VL53L1_nvm_copy_data_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_nvm_copy_data_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_NVM_COPY_DATA_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_IDENTIFICATION__MODEL_ID,
+ comms_buffer,
+ VL53L1_NVM_COPY_DATA_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_nvm_copy_data(
+ VL53L1_NVM_COPY_DATA_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_i2c_encode_prev_shadow_system_results(
+ VL53L1_prev_shadow_system_results_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_prev_shadow_system_results_t into a I2C write buffer
+ * Buffer must be at least 44 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_PREV_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ *(pbuffer + 0) =
+ pdata->prev_shadow_result__interrupt_status & 0x3F;
+ *(pbuffer + 1) =
+ pdata->prev_shadow_result__range_status;
+ *(pbuffer + 2) =
+ pdata->prev_shadow_result__report_status & 0xF;
+ *(pbuffer + 3) =
+ pdata->prev_shadow_result__stream_count;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__dss_actual_effective_spads_sd0,
+ 2,
+ pbuffer + 4);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__peak_signal_count_rate_mcps_sd0,
+ 2,
+ pbuffer + 6);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__ambient_count_rate_mcps_sd0,
+ 2,
+ pbuffer + 8);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__sigma_sd0,
+ 2,
+ pbuffer + 10);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__phase_sd0,
+ 2,
+ pbuffer + 12);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__final_crosstalk_corrected_range_mm_sd0,
+ 2,
+ pbuffer + 14);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0,
+ 2,
+ pbuffer + 16);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__mm_inner_actual_effective_spads_sd0,
+ 2,
+ pbuffer + 18);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__mm_outer_actual_effective_spads_sd0,
+ 2,
+ pbuffer + 20);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__avg_signal_count_rate_mcps_sd0,
+ 2,
+ pbuffer + 22);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__dss_actual_effective_spads_sd1,
+ 2,
+ pbuffer + 24);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__peak_signal_count_rate_mcps_sd1,
+ 2,
+ pbuffer + 26);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__ambient_count_rate_mcps_sd1,
+ 2,
+ pbuffer + 28);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__sigma_sd1,
+ 2,
+ pbuffer + 30);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__phase_sd1,
+ 2,
+ pbuffer + 32);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__final_crosstalk_corrected_range_mm_sd1,
+ 2,
+ pbuffer + 34);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__spare_0_sd1,
+ 2,
+ pbuffer + 36);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__spare_1_sd1,
+ 2,
+ pbuffer + 38);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__spare_2_sd1,
+ 2,
+ pbuffer + 40);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->prev_shadow_result__spare_3_sd1,
+ 2,
+ pbuffer + 42);
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_decode_prev_shadow_system_results(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_prev_shadow_system_results_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_prev_shadow_system_results_t from the input I2C read buffer
+ * Buffer must be at least 44 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_PREV_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->prev_shadow_result__interrupt_status =
+ (*(pbuffer + 0)) & 0x3F;
+ pdata->prev_shadow_result__range_status =
+ (*(pbuffer + 1));
+ pdata->prev_shadow_result__report_status =
+ (*(pbuffer + 2)) & 0xF;
+ pdata->prev_shadow_result__stream_count =
+ (*(pbuffer + 3));
+ pdata->prev_shadow_result__dss_actual_effective_spads_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 4));
+ pdata->prev_shadow_result__peak_signal_count_rate_mcps_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 6));
+ pdata->prev_shadow_result__ambient_count_rate_mcps_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 8));
+ pdata->prev_shadow_result__sigma_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 10));
+ pdata->prev_shadow_result__phase_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 12));
+ pdata->prev_shadow_result__final_crosstalk_corrected_range_mm_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 14));
+ pdata->prev_shadow_result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 16));
+ pdata->prev_shadow_result__mm_inner_actual_effective_spads_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 18));
+ pdata->prev_shadow_result__mm_outer_actual_effective_spads_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 20));
+ pdata->prev_shadow_result__avg_signal_count_rate_mcps_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 22));
+ pdata->prev_shadow_result__dss_actual_effective_spads_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 24));
+ pdata->prev_shadow_result__peak_signal_count_rate_mcps_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 26));
+ pdata->prev_shadow_result__ambient_count_rate_mcps_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 28));
+ pdata->prev_shadow_result__sigma_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 30));
+ pdata->prev_shadow_result__phase_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 32));
+ pdata->prev_shadow_result__final_crosstalk_corrected_range_mm_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 34));
+ pdata->prev_shadow_result__spare_0_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 36));
+ pdata->prev_shadow_result__spare_1_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 38));
+ pdata->prev_shadow_result__spare_2_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 40));
+ pdata->prev_shadow_result__spare_3_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 42));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_prev_shadow_system_results(
+ VL53L1_DEV Dev,
+ VL53L1_prev_shadow_system_results_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_prev_shadow_system_results_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_PREV_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_prev_shadow_system_results(
+ pdata,
+ VL53L1_PREV_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_PREV_SHADOW_RESULT__INTERRUPT_STATUS,
+ comms_buffer,
+ VL53L1_PREV_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_get_prev_shadow_system_results(
+ VL53L1_DEV Dev,
+ VL53L1_prev_shadow_system_results_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_prev_shadow_system_results_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_PREV_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_PREV_SHADOW_RESULT__INTERRUPT_STATUS,
+ comms_buffer,
+ VL53L1_PREV_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_prev_shadow_system_results(
+ VL53L1_PREV_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_encode_prev_shadow_core_results(
+ VL53L1_prev_shadow_core_results_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_prev_shadow_core_results_t into a I2C write buffer
+ * Buffer must be at least 33 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_PREV_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ VL53L1_i2c_encode_uint32_t(
+ pdata->prev_shadow_result_core__ambient_window_events_sd0,
+ 4,
+ pbuffer + 0);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->prev_shadow_result_core__ranging_total_events_sd0,
+ 4,
+ pbuffer + 4);
+ VL53L1_i2c_encode_int32_t(
+ pdata->prev_shadow_result_core__signal_total_events_sd0,
+ 4,
+ pbuffer + 8);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->prev_shadow_result_core__total_periods_elapsed_sd0,
+ 4,
+ pbuffer + 12);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->prev_shadow_result_core__ambient_window_events_sd1,
+ 4,
+ pbuffer + 16);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->prev_shadow_result_core__ranging_total_events_sd1,
+ 4,
+ pbuffer + 20);
+ VL53L1_i2c_encode_int32_t(
+ pdata->prev_shadow_result_core__signal_total_events_sd1,
+ 4,
+ pbuffer + 24);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->prev_shadow_result_core__total_periods_elapsed_sd1,
+ 4,
+ pbuffer + 28);
+ *(pbuffer + 32) =
+ pdata->prev_shadow_result_core__spare_0;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_decode_prev_shadow_core_results(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_prev_shadow_core_results_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_prev_shadow_core_results_t from the input I2C read buffer
+ * Buffer must be at least 33 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_PREV_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->prev_shadow_result_core__ambient_window_events_sd0 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 0));
+ pdata->prev_shadow_result_core__ranging_total_events_sd0 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 4));
+ pdata->prev_shadow_result_core__signal_total_events_sd0 =
+ (VL53L1_i2c_decode_int32_t(4, pbuffer + 8));
+ pdata->prev_shadow_result_core__total_periods_elapsed_sd0 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 12));
+ pdata->prev_shadow_result_core__ambient_window_events_sd1 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 16));
+ pdata->prev_shadow_result_core__ranging_total_events_sd1 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 20));
+ pdata->prev_shadow_result_core__signal_total_events_sd1 =
+ (VL53L1_i2c_decode_int32_t(4, pbuffer + 24));
+ pdata->prev_shadow_result_core__total_periods_elapsed_sd1 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 28));
+ pdata->prev_shadow_result_core__spare_0 =
+ (*(pbuffer + 32));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_prev_shadow_core_results(
+ VL53L1_DEV Dev,
+ VL53L1_prev_shadow_core_results_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_prev_shadow_core_results_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_PREV_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_prev_shadow_core_results(
+ pdata,
+ VL53L1_PREV_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_PREV_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0,
+ comms_buffer,
+ VL53L1_PREV_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_get_prev_shadow_core_results(
+ VL53L1_DEV Dev,
+ VL53L1_prev_shadow_core_results_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_prev_shadow_core_results_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_PREV_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_PREV_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0,
+ comms_buffer,
+ VL53L1_PREV_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_prev_shadow_core_results(
+ VL53L1_PREV_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_encode_patch_debug(
+ VL53L1_patch_debug_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_patch_debug_t into a I2C write buffer
+ * Buffer must be at least 2 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_PATCH_DEBUG_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ *(pbuffer + 0) =
+ pdata->result__debug_status;
+ *(pbuffer + 1) =
+ pdata->result__debug_stage;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+
+VL53L1_Error VL53L1_i2c_decode_patch_debug(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_patch_debug_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_patch_debug_t from the input I2C read buffer
+ * Buffer must be at least 2 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_PATCH_DEBUG_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->result__debug_status =
+ (*(pbuffer + 0));
+ pdata->result__debug_stage =
+ (*(pbuffer + 1));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_patch_debug(
+ VL53L1_DEV Dev,
+ VL53L1_patch_debug_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_patch_debug_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_PATCH_DEBUG_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_patch_debug(
+ pdata,
+ VL53L1_PATCH_DEBUG_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_RESULT__DEBUG_STATUS,
+ comms_buffer,
+ VL53L1_PATCH_DEBUG_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_get_patch_debug(
+ VL53L1_DEV Dev,
+ VL53L1_patch_debug_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_patch_debug_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_PATCH_DEBUG_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_RESULT__DEBUG_STATUS,
+ comms_buffer,
+ VL53L1_PATCH_DEBUG_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_patch_debug(
+ VL53L1_PATCH_DEBUG_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_encode_gph_general_config(
+ VL53L1_gph_general_config_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_gph_general_config_t into a I2C write buffer
+ * Buffer must be at least 5 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_GPH_GENERAL_CONFIG_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ VL53L1_i2c_encode_uint16_t(
+ pdata->gph__system__thresh_rate_high,
+ 2,
+ pbuffer + 0);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->gph__system__thresh_rate_low,
+ 2,
+ pbuffer + 2);
+ *(pbuffer + 4) =
+ pdata->gph__system__interrupt_config_gpio;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+#endif
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_decode_gph_general_config(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_gph_general_config_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_gph_general_config_t from the input I2C read buffer
+ * Buffer must be at least 5 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_GPH_GENERAL_CONFIG_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->gph__system__thresh_rate_high =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 0));
+ pdata->gph__system__thresh_rate_low =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 2));
+ pdata->gph__system__interrupt_config_gpio =
+ (*(pbuffer + 4));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_set_gph_general_config(
+ VL53L1_DEV Dev,
+ VL53L1_gph_general_config_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_gph_general_config_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_GPH_GENERAL_CONFIG_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_gph_general_config(
+ pdata,
+ VL53L1_GPH_GENERAL_CONFIG_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_GPH__SYSTEM__THRESH_RATE_HIGH,
+ comms_buffer,
+ VL53L1_GPH_GENERAL_CONFIG_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_get_gph_general_config(
+ VL53L1_DEV Dev,
+ VL53L1_gph_general_config_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_gph_general_config_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_GPH_GENERAL_CONFIG_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_GPH__SYSTEM__THRESH_RATE_HIGH,
+ comms_buffer,
+ VL53L1_GPH_GENERAL_CONFIG_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_gph_general_config(
+ VL53L1_GPH_GENERAL_CONFIG_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_encode_gph_static_config(
+ VL53L1_gph_static_config_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_gph_static_config_t into a I2C write buffer
+ * Buffer must be at least 6 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_GPH_STATIC_CONFIG_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ *(pbuffer + 0) =
+ pdata->gph__dss_config__roi_mode_control & 0x7;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->gph__dss_config__manual_effective_spads_select,
+ 2,
+ pbuffer + 1);
+ *(pbuffer + 3) =
+ pdata->gph__dss_config__manual_block_select;
+ *(pbuffer + 4) =
+ pdata->gph__dss_config__max_spads_limit;
+ *(pbuffer + 5) =
+ pdata->gph__dss_config__min_spads_limit;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+#endif
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_decode_gph_static_config(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_gph_static_config_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_gph_static_config_t from the input I2C read buffer
+ * Buffer must be at least 6 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_GPH_STATIC_CONFIG_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->gph__dss_config__roi_mode_control =
+ (*(pbuffer + 0)) & 0x7;
+ pdata->gph__dss_config__manual_effective_spads_select =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 1));
+ pdata->gph__dss_config__manual_block_select =
+ (*(pbuffer + 3));
+ pdata->gph__dss_config__max_spads_limit =
+ (*(pbuffer + 4));
+ pdata->gph__dss_config__min_spads_limit =
+ (*(pbuffer + 5));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_set_gph_static_config(
+ VL53L1_DEV Dev,
+ VL53L1_gph_static_config_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_gph_static_config_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_GPH_STATIC_CONFIG_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_gph_static_config(
+ pdata,
+ VL53L1_GPH_STATIC_CONFIG_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_GPH__DSS_CONFIG__ROI_MODE_CONTROL,
+ comms_buffer,
+ VL53L1_GPH_STATIC_CONFIG_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_get_gph_static_config(
+ VL53L1_DEV Dev,
+ VL53L1_gph_static_config_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_gph_static_config_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_GPH_STATIC_CONFIG_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_GPH__DSS_CONFIG__ROI_MODE_CONTROL,
+ comms_buffer,
+ VL53L1_GPH_STATIC_CONFIG_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_gph_static_config(
+ VL53L1_GPH_STATIC_CONFIG_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_encode_gph_timing_config(
+ VL53L1_gph_timing_config_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_gph_timing_config_t into a I2C write buffer
+ * Buffer must be at least 16 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_GPH_TIMING_CONFIG_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ *(pbuffer + 0) =
+ pdata->gph__mm_config__timeout_macrop_a_hi & 0xF;
+ *(pbuffer + 1) =
+ pdata->gph__mm_config__timeout_macrop_a_lo;
+ *(pbuffer + 2) =
+ pdata->gph__mm_config__timeout_macrop_b_hi & 0xF;
+ *(pbuffer + 3) =
+ pdata->gph__mm_config__timeout_macrop_b_lo;
+ *(pbuffer + 4) =
+ pdata->gph__range_config__timeout_macrop_a_hi & 0xF;
+ *(pbuffer + 5) =
+ pdata->gph__range_config__timeout_macrop_a_lo;
+ *(pbuffer + 6) =
+ pdata->gph__range_config__vcsel_period_a & 0x3F;
+ *(pbuffer + 7) =
+ pdata->gph__range_config__vcsel_period_b & 0x3F;
+ *(pbuffer + 8) =
+ pdata->gph__range_config__timeout_macrop_b_hi & 0xF;
+ *(pbuffer + 9) =
+ pdata->gph__range_config__timeout_macrop_b_lo;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->gph__range_config__sigma_thresh,
+ 2,
+ pbuffer + 10);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->gph__range_config__min_count_rate_rtn_limit_mcps,
+ 2,
+ pbuffer + 12);
+ *(pbuffer + 14) =
+ pdata->gph__range_config__valid_phase_low;
+ *(pbuffer + 15) =
+ pdata->gph__range_config__valid_phase_high;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+#endif
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_i2c_decode_gph_timing_config(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_gph_timing_config_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_gph_timing_config_t from the input I2C read buffer
+ * Buffer must be at least 16 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_GPH_TIMING_CONFIG_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->gph__mm_config__timeout_macrop_a_hi =
+ (*(pbuffer + 0)) & 0xF;
+ pdata->gph__mm_config__timeout_macrop_a_lo =
+ (*(pbuffer + 1));
+ pdata->gph__mm_config__timeout_macrop_b_hi =
+ (*(pbuffer + 2)) & 0xF;
+ pdata->gph__mm_config__timeout_macrop_b_lo =
+ (*(pbuffer + 3));
+ pdata->gph__range_config__timeout_macrop_a_hi =
+ (*(pbuffer + 4)) & 0xF;
+ pdata->gph__range_config__timeout_macrop_a_lo =
+ (*(pbuffer + 5));
+ pdata->gph__range_config__vcsel_period_a =
+ (*(pbuffer + 6)) & 0x3F;
+ pdata->gph__range_config__vcsel_period_b =
+ (*(pbuffer + 7)) & 0x3F;
+ pdata->gph__range_config__timeout_macrop_b_hi =
+ (*(pbuffer + 8)) & 0xF;
+ pdata->gph__range_config__timeout_macrop_b_lo =
+ (*(pbuffer + 9));
+ pdata->gph__range_config__sigma_thresh =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 10));
+ pdata->gph__range_config__min_count_rate_rtn_limit_mcps =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 12));
+ pdata->gph__range_config__valid_phase_low =
+ (*(pbuffer + 14));
+ pdata->gph__range_config__valid_phase_high =
+ (*(pbuffer + 15));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_set_gph_timing_config(
+ VL53L1_DEV Dev,
+ VL53L1_gph_timing_config_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_gph_timing_config_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_GPH_TIMING_CONFIG_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_gph_timing_config(
+ pdata,
+ VL53L1_GPH_TIMING_CONFIG_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_GPH__MM_CONFIG__TIMEOUT_MACROP_A_HI,
+ comms_buffer,
+ VL53L1_GPH_TIMING_CONFIG_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifdef PAL_EXTENDED
+VL53L1_Error VL53L1_get_gph_timing_config(
+ VL53L1_DEV Dev,
+ VL53L1_gph_timing_config_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_gph_timing_config_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_GPH_TIMING_CONFIG_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_GPH__MM_CONFIG__TIMEOUT_MACROP_A_HI,
+ comms_buffer,
+ VL53L1_GPH_TIMING_CONFIG_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_gph_timing_config(
+ VL53L1_GPH_TIMING_CONFIG_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
+
+
+#ifdef VL53L1_DEBUG
+VL53L1_Error VL53L1_i2c_encode_fw_internal(
+ VL53L1_fw_internal_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_fw_internal_t into a I2C write buffer
+ * Buffer must be at least 2 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_FW_INTERNAL_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ *(pbuffer + 0) =
+ pdata->firmware__internal_stream_count_div;
+ *(pbuffer + 1) =
+ pdata->firmware__internal_stream_counter_val;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_decode_fw_internal(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_fw_internal_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_fw_internal_t from the input I2C read buffer
+ * Buffer must be at least 2 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_FW_INTERNAL_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->firmware__internal_stream_count_div =
+ (*(pbuffer + 0));
+ pdata->firmware__internal_stream_counter_val =
+ (*(pbuffer + 1));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_fw_internal(
+ VL53L1_DEV Dev,
+ VL53L1_fw_internal_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_fw_internal_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_FW_INTERNAL_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_fw_internal(
+ pdata,
+ VL53L1_FW_INTERNAL_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_FIRMWARE__INTERNAL_STREAM_COUNT_DIV,
+ comms_buffer,
+ VL53L1_FW_INTERNAL_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+VL53L1_Error VL53L1_get_fw_internal(
+ VL53L1_DEV Dev,
+ VL53L1_fw_internal_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_fw_internal_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_FW_INTERNAL_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_FIRMWARE__INTERNAL_STREAM_COUNT_DIV,
+ comms_buffer,
+ VL53L1_FW_INTERNAL_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_fw_internal(
+ VL53L1_FW_INTERNAL_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_encode_patch_results(
+ VL53L1_patch_results_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_patch_results_t into a I2C write buffer
+ * Buffer must be at least 90 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_PATCH_RESULTS_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ *(pbuffer + 0) =
+ pdata->dss_calc__roi_ctrl & 0x3;
+ *(pbuffer + 1) =
+ pdata->dss_calc__spare_1;
+ *(pbuffer + 2) =
+ pdata->dss_calc__spare_2;
+ *(pbuffer + 3) =
+ pdata->dss_calc__spare_3;
+ *(pbuffer + 4) =
+ pdata->dss_calc__spare_4;
+ *(pbuffer + 5) =
+ pdata->dss_calc__spare_5;
+ *(pbuffer + 6) =
+ pdata->dss_calc__spare_6;
+ *(pbuffer + 7) =
+ pdata->dss_calc__spare_7;
+ *(pbuffer + 8) =
+ pdata->dss_calc__user_roi_spad_en_0;
+ *(pbuffer + 9) =
+ pdata->dss_calc__user_roi_spad_en_1;
+ *(pbuffer + 10) =
+ pdata->dss_calc__user_roi_spad_en_2;
+ *(pbuffer + 11) =
+ pdata->dss_calc__user_roi_spad_en_3;
+ *(pbuffer + 12) =
+ pdata->dss_calc__user_roi_spad_en_4;
+ *(pbuffer + 13) =
+ pdata->dss_calc__user_roi_spad_en_5;
+ *(pbuffer + 14) =
+ pdata->dss_calc__user_roi_spad_en_6;
+ *(pbuffer + 15) =
+ pdata->dss_calc__user_roi_spad_en_7;
+ *(pbuffer + 16) =
+ pdata->dss_calc__user_roi_spad_en_8;
+ *(pbuffer + 17) =
+ pdata->dss_calc__user_roi_spad_en_9;
+ *(pbuffer + 18) =
+ pdata->dss_calc__user_roi_spad_en_10;
+ *(pbuffer + 19) =
+ pdata->dss_calc__user_roi_spad_en_11;
+ *(pbuffer + 20) =
+ pdata->dss_calc__user_roi_spad_en_12;
+ *(pbuffer + 21) =
+ pdata->dss_calc__user_roi_spad_en_13;
+ *(pbuffer + 22) =
+ pdata->dss_calc__user_roi_spad_en_14;
+ *(pbuffer + 23) =
+ pdata->dss_calc__user_roi_spad_en_15;
+ *(pbuffer + 24) =
+ pdata->dss_calc__user_roi_spad_en_16;
+ *(pbuffer + 25) =
+ pdata->dss_calc__user_roi_spad_en_17;
+ *(pbuffer + 26) =
+ pdata->dss_calc__user_roi_spad_en_18;
+ *(pbuffer + 27) =
+ pdata->dss_calc__user_roi_spad_en_19;
+ *(pbuffer + 28) =
+ pdata->dss_calc__user_roi_spad_en_20;
+ *(pbuffer + 29) =
+ pdata->dss_calc__user_roi_spad_en_21;
+ *(pbuffer + 30) =
+ pdata->dss_calc__user_roi_spad_en_22;
+ *(pbuffer + 31) =
+ pdata->dss_calc__user_roi_spad_en_23;
+ *(pbuffer + 32) =
+ pdata->dss_calc__user_roi_spad_en_24;
+ *(pbuffer + 33) =
+ pdata->dss_calc__user_roi_spad_en_25;
+ *(pbuffer + 34) =
+ pdata->dss_calc__user_roi_spad_en_26;
+ *(pbuffer + 35) =
+ pdata->dss_calc__user_roi_spad_en_27;
+ *(pbuffer + 36) =
+ pdata->dss_calc__user_roi_spad_en_28;
+ *(pbuffer + 37) =
+ pdata->dss_calc__user_roi_spad_en_29;
+ *(pbuffer + 38) =
+ pdata->dss_calc__user_roi_spad_en_30;
+ *(pbuffer + 39) =
+ pdata->dss_calc__user_roi_spad_en_31;
+ *(pbuffer + 40) =
+ pdata->dss_calc__user_roi_0;
+ *(pbuffer + 41) =
+ pdata->dss_calc__user_roi_1;
+ *(pbuffer + 42) =
+ pdata->dss_calc__mode_roi_0;
+ *(pbuffer + 43) =
+ pdata->dss_calc__mode_roi_1;
+ *(pbuffer + 44) =
+ pdata->sigma_estimator_calc__spare_0;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->vhv_result__peak_signal_rate_mcps,
+ 2,
+ pbuffer + 46);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->vhv_result__signal_total_events_ref,
+ 4,
+ pbuffer + 48);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->phasecal_result__phase_output_ref,
+ 2,
+ pbuffer + 52);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->dss_result__total_rate_per_spad,
+ 2,
+ pbuffer + 54);
+ *(pbuffer + 56) =
+ pdata->dss_result__enabled_blocks;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->dss_result__num_requested_spads,
+ 2,
+ pbuffer + 58);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->mm_result__inner_intersection_rate,
+ 2,
+ pbuffer + 62);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->mm_result__outer_complement_rate,
+ 2,
+ pbuffer + 64);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->mm_result__total_offset,
+ 2,
+ pbuffer + 66);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->xtalk_calc__xtalk_for_enabled_spads & 0xFFFFFF,
+ 4,
+ pbuffer + 68);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->xtalk_result__avg_xtalk_user_roi_kcps & 0xFFFFFF,
+ 4,
+ pbuffer + 72);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->xtalk_result__avg_xtalk_mm_inner_roi_kcps & 0xFFFFFF,
+ 4,
+ pbuffer + 76);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->xtalk_result__avg_xtalk_mm_outer_roi_kcps & 0xFFFFFF,
+ 4,
+ pbuffer + 80);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->range_result__accum_phase,
+ 4,
+ pbuffer + 84);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->range_result__offset_corrected_range,
+ 2,
+ pbuffer + 88);
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_decode_patch_results(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_patch_results_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_patch_results_t from the input I2C read buffer
+ * Buffer must be at least 90 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_PATCH_RESULTS_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->dss_calc__roi_ctrl =
+ (*(pbuffer + 0)) & 0x3;
+ pdata->dss_calc__spare_1 =
+ (*(pbuffer + 1));
+ pdata->dss_calc__spare_2 =
+ (*(pbuffer + 2));
+ pdata->dss_calc__spare_3 =
+ (*(pbuffer + 3));
+ pdata->dss_calc__spare_4 =
+ (*(pbuffer + 4));
+ pdata->dss_calc__spare_5 =
+ (*(pbuffer + 5));
+ pdata->dss_calc__spare_6 =
+ (*(pbuffer + 6));
+ pdata->dss_calc__spare_7 =
+ (*(pbuffer + 7));
+ pdata->dss_calc__user_roi_spad_en_0 =
+ (*(pbuffer + 8));
+ pdata->dss_calc__user_roi_spad_en_1 =
+ (*(pbuffer + 9));
+ pdata->dss_calc__user_roi_spad_en_2 =
+ (*(pbuffer + 10));
+ pdata->dss_calc__user_roi_spad_en_3 =
+ (*(pbuffer + 11));
+ pdata->dss_calc__user_roi_spad_en_4 =
+ (*(pbuffer + 12));
+ pdata->dss_calc__user_roi_spad_en_5 =
+ (*(pbuffer + 13));
+ pdata->dss_calc__user_roi_spad_en_6 =
+ (*(pbuffer + 14));
+ pdata->dss_calc__user_roi_spad_en_7 =
+ (*(pbuffer + 15));
+ pdata->dss_calc__user_roi_spad_en_8 =
+ (*(pbuffer + 16));
+ pdata->dss_calc__user_roi_spad_en_9 =
+ (*(pbuffer + 17));
+ pdata->dss_calc__user_roi_spad_en_10 =
+ (*(pbuffer + 18));
+ pdata->dss_calc__user_roi_spad_en_11 =
+ (*(pbuffer + 19));
+ pdata->dss_calc__user_roi_spad_en_12 =
+ (*(pbuffer + 20));
+ pdata->dss_calc__user_roi_spad_en_13 =
+ (*(pbuffer + 21));
+ pdata->dss_calc__user_roi_spad_en_14 =
+ (*(pbuffer + 22));
+ pdata->dss_calc__user_roi_spad_en_15 =
+ (*(pbuffer + 23));
+ pdata->dss_calc__user_roi_spad_en_16 =
+ (*(pbuffer + 24));
+ pdata->dss_calc__user_roi_spad_en_17 =
+ (*(pbuffer + 25));
+ pdata->dss_calc__user_roi_spad_en_18 =
+ (*(pbuffer + 26));
+ pdata->dss_calc__user_roi_spad_en_19 =
+ (*(pbuffer + 27));
+ pdata->dss_calc__user_roi_spad_en_20 =
+ (*(pbuffer + 28));
+ pdata->dss_calc__user_roi_spad_en_21 =
+ (*(pbuffer + 29));
+ pdata->dss_calc__user_roi_spad_en_22 =
+ (*(pbuffer + 30));
+ pdata->dss_calc__user_roi_spad_en_23 =
+ (*(pbuffer + 31));
+ pdata->dss_calc__user_roi_spad_en_24 =
+ (*(pbuffer + 32));
+ pdata->dss_calc__user_roi_spad_en_25 =
+ (*(pbuffer + 33));
+ pdata->dss_calc__user_roi_spad_en_26 =
+ (*(pbuffer + 34));
+ pdata->dss_calc__user_roi_spad_en_27 =
+ (*(pbuffer + 35));
+ pdata->dss_calc__user_roi_spad_en_28 =
+ (*(pbuffer + 36));
+ pdata->dss_calc__user_roi_spad_en_29 =
+ (*(pbuffer + 37));
+ pdata->dss_calc__user_roi_spad_en_30 =
+ (*(pbuffer + 38));
+ pdata->dss_calc__user_roi_spad_en_31 =
+ (*(pbuffer + 39));
+ pdata->dss_calc__user_roi_0 =
+ (*(pbuffer + 40));
+ pdata->dss_calc__user_roi_1 =
+ (*(pbuffer + 41));
+ pdata->dss_calc__mode_roi_0 =
+ (*(pbuffer + 42));
+ pdata->dss_calc__mode_roi_1 =
+ (*(pbuffer + 43));
+ pdata->sigma_estimator_calc__spare_0 =
+ (*(pbuffer + 44));
+ pdata->vhv_result__peak_signal_rate_mcps =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 46));
+ pdata->vhv_result__signal_total_events_ref =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 48));
+ pdata->phasecal_result__phase_output_ref =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 52));
+ pdata->dss_result__total_rate_per_spad =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 54));
+ pdata->dss_result__enabled_blocks =
+ (*(pbuffer + 56));
+ pdata->dss_result__num_requested_spads =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 58));
+ pdata->mm_result__inner_intersection_rate =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 62));
+ pdata->mm_result__outer_complement_rate =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 64));
+ pdata->mm_result__total_offset =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 66));
+ pdata->xtalk_calc__xtalk_for_enabled_spads =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 68)) & 0xFFFFFF;
+ pdata->xtalk_result__avg_xtalk_user_roi_kcps =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 72)) & 0xFFFFFF;
+ pdata->xtalk_result__avg_xtalk_mm_inner_roi_kcps =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 76)) & 0xFFFFFF;
+ pdata->xtalk_result__avg_xtalk_mm_outer_roi_kcps =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 80)) & 0xFFFFFF;
+ pdata->range_result__accum_phase =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 84));
+ pdata->range_result__offset_corrected_range =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 88));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_patch_results(
+ VL53L1_DEV Dev,
+ VL53L1_patch_results_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_patch_results_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_PATCH_RESULTS_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_patch_results(
+ pdata,
+ VL53L1_PATCH_RESULTS_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_DSS_CALC__ROI_CTRL,
+ comms_buffer,
+ VL53L1_PATCH_RESULTS_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+VL53L1_Error VL53L1_get_patch_results(
+ VL53L1_DEV Dev,
+ VL53L1_patch_results_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_patch_results_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_PATCH_RESULTS_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_DSS_CALC__ROI_CTRL,
+ comms_buffer,
+ VL53L1_PATCH_RESULTS_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_patch_results(
+ VL53L1_PATCH_RESULTS_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_encode_shadow_system_results(
+ VL53L1_shadow_system_results_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_shadow_system_results_t into a I2C write buffer
+ * Buffer must be at least 82 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ *(pbuffer + 0) =
+ pdata->shadow_phasecal_result__vcsel_start;
+ *(pbuffer + 2) =
+ pdata->shadow_result__interrupt_status & 0x3F;
+ *(pbuffer + 3) =
+ pdata->shadow_result__range_status;
+ *(pbuffer + 4) =
+ pdata->shadow_result__report_status & 0xF;
+ *(pbuffer + 5) =
+ pdata->shadow_result__stream_count;
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__dss_actual_effective_spads_sd0,
+ 2,
+ pbuffer + 6);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__peak_signal_count_rate_mcps_sd0,
+ 2,
+ pbuffer + 8);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__ambient_count_rate_mcps_sd0,
+ 2,
+ pbuffer + 10);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__sigma_sd0,
+ 2,
+ pbuffer + 12);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__phase_sd0,
+ 2,
+ pbuffer + 14);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__final_crosstalk_corrected_range_mm_sd0,
+ 2,
+ pbuffer + 16);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0,
+ 2,
+ pbuffer + 18);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__mm_inner_actual_effective_spads_sd0,
+ 2,
+ pbuffer + 20);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__mm_outer_actual_effective_spads_sd0,
+ 2,
+ pbuffer + 22);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__avg_signal_count_rate_mcps_sd0,
+ 2,
+ pbuffer + 24);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__dss_actual_effective_spads_sd1,
+ 2,
+ pbuffer + 26);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__peak_signal_count_rate_mcps_sd1,
+ 2,
+ pbuffer + 28);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__ambient_count_rate_mcps_sd1,
+ 2,
+ pbuffer + 30);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__sigma_sd1,
+ 2,
+ pbuffer + 32);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__phase_sd1,
+ 2,
+ pbuffer + 34);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__final_crosstalk_corrected_range_mm_sd1,
+ 2,
+ pbuffer + 36);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__spare_0_sd1,
+ 2,
+ pbuffer + 38);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__spare_1_sd1,
+ 2,
+ pbuffer + 40);
+ VL53L1_i2c_encode_uint16_t(
+ pdata->shadow_result__spare_2_sd1,
+ 2,
+ pbuffer + 42);
+ *(pbuffer + 44) =
+ pdata->shadow_result__spare_3_sd1;
+ *(pbuffer + 45) =
+ pdata->shadow_result__thresh_info;
+ *(pbuffer + 80) =
+ pdata->shadow_phasecal_result__reference_phase_hi;
+ *(pbuffer + 81) =
+ pdata->shadow_phasecal_result__reference_phase_lo;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_decode_shadow_system_results(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_shadow_system_results_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_shadow_system_results_t from the input I2C read buffer
+ * Buffer must be at least 82 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->shadow_phasecal_result__vcsel_start =
+ (*(pbuffer + 0));
+ pdata->shadow_result__interrupt_status =
+ (*(pbuffer + 2)) & 0x3F;
+ pdata->shadow_result__range_status =
+ (*(pbuffer + 3));
+ pdata->shadow_result__report_status =
+ (*(pbuffer + 4)) & 0xF;
+ pdata->shadow_result__stream_count =
+ (*(pbuffer + 5));
+ pdata->shadow_result__dss_actual_effective_spads_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 6));
+ pdata->shadow_result__peak_signal_count_rate_mcps_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 8));
+ pdata->shadow_result__ambient_count_rate_mcps_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 10));
+ pdata->shadow_result__sigma_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 12));
+ pdata->shadow_result__phase_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 14));
+ pdata->shadow_result__final_crosstalk_corrected_range_mm_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 16));
+ pdata->shadow_result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 18));
+ pdata->shadow_result__mm_inner_actual_effective_spads_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 20));
+ pdata->shadow_result__mm_outer_actual_effective_spads_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 22));
+ pdata->shadow_result__avg_signal_count_rate_mcps_sd0 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 24));
+ pdata->shadow_result__dss_actual_effective_spads_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 26));
+ pdata->shadow_result__peak_signal_count_rate_mcps_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 28));
+ pdata->shadow_result__ambient_count_rate_mcps_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 30));
+ pdata->shadow_result__sigma_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 32));
+ pdata->shadow_result__phase_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 34));
+ pdata->shadow_result__final_crosstalk_corrected_range_mm_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 36));
+ pdata->shadow_result__spare_0_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 38));
+ pdata->shadow_result__spare_1_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 40));
+ pdata->shadow_result__spare_2_sd1 =
+ (VL53L1_i2c_decode_uint16_t(2, pbuffer + 42));
+ pdata->shadow_result__spare_3_sd1 =
+ (*(pbuffer + 44));
+ pdata->shadow_result__thresh_info =
+ (*(pbuffer + 45));
+ pdata->shadow_phasecal_result__reference_phase_hi =
+ (*(pbuffer + 80));
+ pdata->shadow_phasecal_result__reference_phase_lo =
+ (*(pbuffer + 81));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_shadow_system_results(
+ VL53L1_DEV Dev,
+ VL53L1_shadow_system_results_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_shadow_system_results_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_shadow_system_results(
+ pdata,
+ VL53L1_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_SHADOW_PHASECAL_RESULT__VCSEL_START,
+ comms_buffer,
+ VL53L1_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+VL53L1_Error VL53L1_get_shadow_system_results(
+ VL53L1_DEV Dev,
+ VL53L1_shadow_system_results_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_shadow_system_results_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_SHADOW_PHASECAL_RESULT__VCSEL_START,
+ comms_buffer,
+ VL53L1_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_shadow_system_results(
+ VL53L1_SHADOW_SYSTEM_RESULTS_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_encode_shadow_core_results(
+ VL53L1_shadow_core_results_t *pdata,
+ uint16_t buf_size,
+ uint8_t *pbuffer)
+{
+ /**
+ * Encodes data structure VL53L1_shadow_core_results_t into a I2C write buffer
+ * Buffer must be at least 33 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ VL53L1_i2c_encode_uint32_t(
+ pdata->shadow_result_core__ambient_window_events_sd0,
+ 4,
+ pbuffer + 0);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->shadow_result_core__ranging_total_events_sd0,
+ 4,
+ pbuffer + 4);
+ VL53L1_i2c_encode_int32_t(
+ pdata->shadow_result_core__signal_total_events_sd0,
+ 4,
+ pbuffer + 8);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->shadow_result_core__total_periods_elapsed_sd0,
+ 4,
+ pbuffer + 12);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->shadow_result_core__ambient_window_events_sd1,
+ 4,
+ pbuffer + 16);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->shadow_result_core__ranging_total_events_sd1,
+ 4,
+ pbuffer + 20);
+ VL53L1_i2c_encode_int32_t(
+ pdata->shadow_result_core__signal_total_events_sd1,
+ 4,
+ pbuffer + 24);
+ VL53L1_i2c_encode_uint32_t(
+ pdata->shadow_result_core__total_periods_elapsed_sd1,
+ 4,
+ pbuffer + 28);
+ *(pbuffer + 32) =
+ pdata->shadow_result_core__spare_0;
+ LOG_FUNCTION_END(status);
+
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_i2c_decode_shadow_core_results(
+ uint16_t buf_size,
+ uint8_t *pbuffer,
+ VL53L1_shadow_core_results_t *pdata)
+{
+ /**
+ * Decodes data structure VL53L1_shadow_core_results_t from the input I2C read buffer
+ * Buffer must be at least 33 bytes
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ if (VL53L1_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES > buf_size)
+ return VL53L1_ERROR_COMMS_BUFFER_TOO_SMALL;
+
+ pdata->shadow_result_core__ambient_window_events_sd0 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 0));
+ pdata->shadow_result_core__ranging_total_events_sd0 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 4));
+ pdata->shadow_result_core__signal_total_events_sd0 =
+ (VL53L1_i2c_decode_int32_t(4, pbuffer + 8));
+ pdata->shadow_result_core__total_periods_elapsed_sd0 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 12));
+ pdata->shadow_result_core__ambient_window_events_sd1 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 16));
+ pdata->shadow_result_core__ranging_total_events_sd1 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 20));
+ pdata->shadow_result_core__signal_total_events_sd1 =
+ (VL53L1_i2c_decode_int32_t(4, pbuffer + 24));
+ pdata->shadow_result_core__total_periods_elapsed_sd1 =
+ (VL53L1_i2c_decode_uint32_t(4, pbuffer + 28));
+ pdata->shadow_result_core__spare_0 =
+ (*(pbuffer + 32));
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_set_shadow_core_results(
+ VL53L1_DEV Dev,
+ VL53L1_shadow_core_results_t *pdata)
+{
+ /**
+ * Serialises and sends the contents of VL53L1_shadow_core_results_t
+ * data structure to the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_i2c_encode_shadow_core_results(
+ pdata,
+ VL53L1_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES,
+ comms_buffer);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_WriteMulti(
+ Dev,
+ VL53L1_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0,
+ comms_buffer,
+ VL53L1_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_get_shadow_core_results(
+ VL53L1_DEV Dev,
+ VL53L1_shadow_core_results_t *pdata)
+{
+ /**
+ * Reads and de-serialises the contents of VL53L1_shadow_core_results_t
+ * data structure from the device
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t comms_buffer[VL53L1_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES];
+
+ LOG_FUNCTION_START("");
+
+ if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
+ status = VL53L1_disable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_SHADOW_RESULT_CORE__AMBIENT_WINDOW_EVENTS_SD0,
+ comms_buffer,
+ VL53L1_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_enable_firmware(Dev);
+
+ if (status == VL53L1_ERROR_NONE)
+ status = VL53L1_i2c_decode_shadow_core_results(
+ VL53L1_SHADOW_CORE_RESULTS_I2C_SIZE_BYTES,
+ comms_buffer,
+ pdata);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+#endif
diff --git a/src/lib/vl53l1/core/src/vl53l1_silicon_core.c b/src/lib/vl53l1/core/src/vl53l1_silicon_core.c
new file mode 100644
index 0000000000..4010b1afeb
--- /dev/null
+++ b/src/lib/vl53l1/core/src/vl53l1_silicon_core.c
@@ -0,0 +1,113 @@
+/*******************************************************************************
+ Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ ******************************************************************************/
+
+/**
+ * @file vl53l1_silicon_core.c
+ *
+ * @brief EwokPlus25 low level silicon LL Driver function definition
+ */
+
+
+#include "vl53l1_ll_def.h"
+#include "vl53l1_register_map.h"
+#include "vl53l1_core.h"
+#include "vl53l1_silicon_core.h"
+
+#include "../../../../drivers/interface/vl53l1x.h"
+
+
+#define LOG_FUNCTION_START(fmt, ...) \
+ _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_CORE, fmt, ##__VA_ARGS__)
+#define LOG_FUNCTION_END(status, ...) \
+ _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_CORE, status, ##__VA_ARGS__)
+#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
+ _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_CORE, status, fmt, ##__VA_ARGS__)
+
+
+VL53L1_Error VL53L1_is_firmware_ready_silicon(
+ VL53L1_DEV Dev,
+ uint8_t *pready)
+{
+ /**
+ * Determines if the firmware is ready to range
+ *
+ * There are 2 different behaviors depending on whether
+ * power force is enabled or not
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint8_t comms_buffer[5];
+
+ LOG_FUNCTION_START("");
+
+ /* read interrupt and power force reset status */
+
+ status = VL53L1_ReadMulti(
+ Dev,
+ VL53L1_INTERRUPT_MANAGER__ENABLES,
+ comms_buffer,
+ 5);
+
+ if (status == VL53L1_ERROR_NONE) {
+
+ pdev->dbg_results.interrupt_manager__enables =
+ comms_buffer[0];
+ pdev->dbg_results.interrupt_manager__clear =
+ comms_buffer[1];
+ pdev->dbg_results.interrupt_manager__status =
+ comms_buffer[2];
+ pdev->dbg_results.mcu_to_host_bank__wr_access_en =
+ comms_buffer[3];
+ pdev->dbg_results.power_management__go1_reset_status =
+ comms_buffer[4];
+
+ if ((pdev->sys_ctrl.power_management__go1_power_force & 0x01) == 0x01) {
+
+ if (((pdev->dbg_results.interrupt_manager__enables & 0x1F) == 0x1F) &&
+ ((pdev->dbg_results.interrupt_manager__clear & 0x1F) == 0x1F))
+ *pready = 0x01;
+ else
+ *pready = 0x00;
+
+ } else {
+
+ /* set ready flag if bit 0 is zero i.g G01 is in reset */
+ if ((pdev->dbg_results.power_management__go1_reset_status & 0x01) == 0x00)
+ *pready = 0x01;
+ else
+ *pready = 0x00;
+ }
+
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
diff --git a/src/lib/vl53l1/core/src/vl53l1_wait.c b/src/lib/vl53l1/core/src/vl53l1_wait.c
new file mode 100644
index 0000000000..e0853a5e14
--- /dev/null
+++ b/src/lib/vl53l1/core/src/vl53l1_wait.c
@@ -0,0 +1,524 @@
+/*******************************************************************************
+ Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ ******************************************************************************/
+
+/**
+ * @file vl53l1_wait.c
+ *
+ * @brief EwokPlus25 low level Driver wait function definition
+ */
+
+
+#include "vl53l1_ll_def.h"
+#include "vl53l1_ll_device.h"
+#include "vl53l1_platform.h"
+#include "vl53l1_core.h"
+#include "vl53l1_silicon_core.h"
+#include "vl53l1_wait.h"
+#include "vl53l1_register_settings.h"
+
+
+#define LOG_FUNCTION_START(fmt, ...) \
+ _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_CORE, fmt, ##__VA_ARGS__)
+#define LOG_FUNCTION_END(status, ...) \
+ _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_CORE, status, ##__VA_ARGS__)
+#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
+ _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_CORE, status, \
+ fmt, ##__VA_ARGS__)
+
+
+VL53L1_Error VL53L1_wait_for_boot_completion(
+ VL53L1_DEV Dev)
+{
+
+ /* Waits for firmware boot to finish
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint8_t fw_ready = 0;
+
+ LOG_FUNCTION_START("");
+
+ if (pdev->wait_method == VL53L1_WAIT_METHOD_BLOCKING) {
+
+ /* blocking version */
+
+ status =
+ VL53L1_poll_for_boot_completion(
+ Dev,
+ VL53L1_BOOT_COMPLETION_POLLING_TIMEOUT_MS);
+
+ } else {
+
+ /* implement non blocking version below */
+
+ fw_ready = 0;
+ while (fw_ready == 0x00 && status == VL53L1_ERROR_NONE) {
+ status = VL53L1_is_boot_complete(
+ Dev,
+ &fw_ready);
+
+ if (status == VL53L1_ERROR_NONE) {
+ status = VL53L1_WaitMs(
+ Dev,
+ VL53L1_POLLING_DELAY_MS);
+ }
+ }
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+
+}
+
+
+VL53L1_Error VL53L1_wait_for_firmware_ready(
+ VL53L1_DEV Dev)
+{
+
+ /* If in timed mode or single shot then check firmware is ready
+ * before sending handshake
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint8_t fw_ready = 0;
+ uint8_t mode_start = 0;
+
+ LOG_FUNCTION_START("");
+
+ /* Filter out tje measure mode part of the mode
+ * start register
+ */
+ mode_start =
+ pdev->sys_ctrl.system__mode_start &
+ VL53L1_DEVICEMEASUREMENTMODE_MODE_MASK;
+
+ /*
+ * conditional wait for firmware ready
+ * only waits for timed and single shot modes
+ */
+
+ if ((mode_start == VL53L1_DEVICEMEASUREMENTMODE_TIMED) ||
+ (mode_start == VL53L1_DEVICEMEASUREMENTMODE_SINGLESHOT)) {
+
+ if (pdev->wait_method == VL53L1_WAIT_METHOD_BLOCKING) {
+
+ /* blocking version */
+
+ status =
+ VL53L1_poll_for_firmware_ready(
+ Dev,
+ VL53L1_RANGE_COMPLETION_POLLING_TIMEOUT_MS);
+
+ } else {
+
+ /* implement non blocking version below */
+
+ fw_ready = 0;
+ while (fw_ready == 0x00 && status == VL53L1_ERROR_NONE) {
+ status = VL53L1_is_firmware_ready(
+ Dev,
+ &fw_ready);
+
+ if (status == VL53L1_ERROR_NONE) {
+ status = VL53L1_WaitMs(
+ Dev,
+ VL53L1_POLLING_DELAY_MS);
+ }
+ }
+ }
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_wait_for_range_completion(
+ VL53L1_DEV Dev)
+{
+
+ /* Wrapper function for waiting for range completion
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint8_t data_ready = 0;
+
+ LOG_FUNCTION_START("");
+
+ if (pdev->wait_method == VL53L1_WAIT_METHOD_BLOCKING) {
+
+ /* blocking version */
+
+ status =
+ VL53L1_poll_for_range_completion(
+ Dev,
+ VL53L1_RANGE_COMPLETION_POLLING_TIMEOUT_MS);
+
+ } else {
+
+ /* implement non blocking version below */
+
+ data_ready = 0;
+ while (data_ready == 0x00 && status == VL53L1_ERROR_NONE) {
+ status = VL53L1_is_new_data_ready(
+ Dev,
+ &data_ready);
+
+ if (status == VL53L1_ERROR_NONE) {
+ status = VL53L1_WaitMs(
+ Dev,
+ VL53L1_POLLING_DELAY_MS);
+ }
+ }
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_wait_for_test_completion(
+ VL53L1_DEV Dev)
+{
+
+ /* Wrapper function for waiting for test mode completion
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint8_t data_ready = 0;
+
+ LOG_FUNCTION_START("");
+
+ if (pdev->wait_method == VL53L1_WAIT_METHOD_BLOCKING) {
+
+ /* blocking version */
+
+ status =
+ VL53L1_poll_for_range_completion(
+ Dev,
+ VL53L1_TEST_COMPLETION_POLLING_TIMEOUT_MS);
+
+ } else {
+
+ /* implement non blocking version below */
+
+ data_ready = 0;
+ while (data_ready == 0x00 && status == VL53L1_ERROR_NONE) {
+ status = VL53L1_is_new_data_ready(
+ Dev,
+ &data_ready);
+
+ if (status == VL53L1_ERROR_NONE) {
+ status = VL53L1_WaitMs(
+ Dev,
+ VL53L1_POLLING_DELAY_MS);
+ }
+ }
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+
+
+VL53L1_Error VL53L1_is_boot_complete(
+ VL53L1_DEV Dev,
+ uint8_t *pready)
+{
+ /**
+ * Determines if the firmware finished booting by reading
+ * bit 0 of firmware__system_status register
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ uint8_t firmware__system_status = 0;
+
+ LOG_FUNCTION_START("");
+
+ /* read current range interrupt state */
+
+ status =
+ VL53L1_RdByte(
+ Dev,
+ VL53L1_FIRMWARE__SYSTEM_STATUS,
+ &firmware__system_status);
+
+ /* set *pready = 1 if new range data ready complete
+ * zero otherwise
+ */
+
+ if ((firmware__system_status & 0x01) == 0x01) {
+ *pready = 0x01;
+ VL53L1_init_ll_driver_state(
+ Dev,
+ VL53L1_DEVICESTATE_SW_STANDBY);
+ } else {
+ *pready = 0x00;
+ VL53L1_init_ll_driver_state(
+ Dev,
+ VL53L1_DEVICESTATE_FW_COLDBOOT);
+ }
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_is_firmware_ready(
+ VL53L1_DEV Dev,
+ uint8_t *pready)
+{
+ /**
+ * Determines if the firmware is ready to range
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ LOG_FUNCTION_START("");
+
+ status = VL53L1_is_firmware_ready_silicon(
+ Dev,
+ pready);
+
+ pdev->fw_ready = *pready;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_is_new_data_ready(
+ VL53L1_DEV Dev,
+ uint8_t *pready)
+{
+ /**
+ * Determines if new range data is ready by reading bit 0 of
+ * VL53L1_GPIO__TIO_HV_STATUS to determine the current state
+ * of output interrupt pin
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint8_t gpio__mux_active_high_hv = 0;
+ uint8_t gpio__tio_hv_status = 0;
+ uint8_t interrupt_ready = 0;
+
+ LOG_FUNCTION_START("");
+
+ gpio__mux_active_high_hv =
+ pdev->stat_cfg.gpio_hv_mux__ctrl &
+ VL53L1_DEVICEINTERRUPTLEVEL_ACTIVE_MASK;
+
+ if (gpio__mux_active_high_hv == VL53L1_DEVICEINTERRUPTLEVEL_ACTIVE_HIGH)
+ interrupt_ready = 0x01;
+ else
+ interrupt_ready = 0x00;
+
+ /* read current range interrupt state */
+
+ status = VL53L1_RdByte(
+ Dev,
+ VL53L1_GPIO__TIO_HV_STATUS,
+ &gpio__tio_hv_status);
+
+ /* set *pready = 1 if new range data ready complete zero otherwise */
+
+ if ((gpio__tio_hv_status & 0x01) == interrupt_ready)
+ *pready = 0x01;
+ else
+ *pready = 0x00;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+
+
+VL53L1_Error VL53L1_poll_for_boot_completion(
+ VL53L1_DEV Dev,
+ uint32_t timeout_ms)
+{
+ /**
+ * Polls the bit 0 of the FIRMWARE__SYSTEM_STATUS register to see if
+ * the firmware is ready.
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+
+ LOG_FUNCTION_START("");
+
+ /* after reset for the firmware blocks I2C access while
+ * it copies the NVM data into the G02 host register banks
+ * The host must wait the required time to allow the copy
+ * to complete before attempting to read the firmware status
+ */
+
+ status = VL53L1_WaitUs(
+ Dev,
+ VL53L1_FIRMWARE_BOOT_TIME_US);
+
+ if (status == VL53L1_ERROR_NONE)
+ status =
+ VL53L1_WaitValueMaskEx(
+ Dev,
+ timeout_ms,
+ VL53L1_FIRMWARE__SYSTEM_STATUS,
+ 0x01,
+ 0x01,
+ VL53L1_POLLING_DELAY_MS);
+
+ if (status == VL53L1_ERROR_NONE)
+ VL53L1_init_ll_driver_state(Dev, VL53L1_DEVICESTATE_SW_STANDBY);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_poll_for_firmware_ready(
+ VL53L1_DEV Dev,
+ uint32_t timeout_ms)
+{
+ /**
+ * Polls the bit 0 of the FIRMWARE__SYSTEM_STATUS register to see if
+ * the firmware is ready.
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint32_t start_time_ms = 0;
+ uint32_t current_time_ms = 0;
+ int32_t poll_delay_ms = VL53L1_POLLING_DELAY_MS;
+ uint8_t fw_ready = 0;
+
+ /* calculate time limit in absolute time */
+
+ VL53L1_GetTickCount(&start_time_ms); /*lint !e534 ignoring return*/
+ pdev->fw_ready_poll_duration_ms = 0;
+
+ /* wait until firmware is ready, timeout reached on error occurred */
+
+ while ((status == VL53L1_ERROR_NONE) &&
+ (pdev->fw_ready_poll_duration_ms < timeout_ms) &&
+ (fw_ready == 0)) {
+
+ status = VL53L1_is_firmware_ready(
+ Dev,
+ &fw_ready);
+
+ if (status == VL53L1_ERROR_NONE &&
+ fw_ready == 0 &&
+ poll_delay_ms > 0) {
+ status = VL53L1_WaitMs(
+ Dev,
+ poll_delay_ms);
+ }
+
+ /*
+ * Update polling time (Compare difference rather than
+ * absolute to negate 32bit wrap around issue)
+ */
+ VL53L1_GetTickCount(¤t_time_ms); /*lint !e534 ignoring return*/
+ pdev->fw_ready_poll_duration_ms =
+ current_time_ms - start_time_ms;
+ }
+
+ if (fw_ready == 0 && status == VL53L1_ERROR_NONE)
+ status = VL53L1_ERROR_TIME_OUT;
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
+
+VL53L1_Error VL53L1_poll_for_range_completion(
+ VL53L1_DEV Dev,
+ uint32_t timeout_ms)
+{
+ /**
+ * Polls bit 0 of VL53L1_GPIO__TIO_HV_STATUS to determine
+ * the state of output interrupt pin
+ *
+ * Interrupt may be either active high or active low. Use active_high to
+ * select the required level check
+ */
+
+ VL53L1_Error status = VL53L1_ERROR_NONE;
+ VL53L1_LLDriverData_t *pdev = VL53L1DevStructGetLLDriverHandle(Dev);
+
+ uint8_t gpio__mux_active_high_hv = 0;
+ uint8_t interrupt_ready = 0;
+
+ LOG_FUNCTION_START("");
+
+ gpio__mux_active_high_hv =
+ pdev->stat_cfg.gpio_hv_mux__ctrl &
+ VL53L1_DEVICEINTERRUPTLEVEL_ACTIVE_MASK;
+
+ if (gpio__mux_active_high_hv == VL53L1_DEVICEINTERRUPTLEVEL_ACTIVE_HIGH)
+ interrupt_ready = 0x01;
+ else
+ interrupt_ready = 0x00;
+
+ status =
+ VL53L1_WaitValueMaskEx(
+ Dev,
+ timeout_ms,
+ VL53L1_GPIO__TIO_HV_STATUS,
+ interrupt_ready,
+ 0x01,
+ VL53L1_POLLING_DELAY_MS);
+
+ LOG_FUNCTION_END(status);
+
+ return status;
+}
+
diff --git a/src/lib/vl53l1/vl53l1_platform.h b/src/lib/vl53l1/vl53l1_platform.h
new file mode 100644
index 0000000000..96fe8847bc
--- /dev/null
+++ b/src/lib/vl53l1/vl53l1_platform.h
@@ -0,0 +1,37 @@
+/*******************************************************************************
+ Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ ******************************************************************************/
+
+
+#ifndef _VL53L1_PLATFORM_H_
+#define _VL53L1_PLATFORM_H_
+
+#include "vl53l1x.h"
+#include "vl53l1_platform_log.h"
+
+#endif
+
diff --git a/src/lib/vl53l1/vl53l1_platform_log.h b/src/lib/vl53l1/vl53l1_platform_log.h
new file mode 100644
index 0000000000..5bff5bd026
--- /dev/null
+++ b/src/lib/vl53l1/vl53l1_platform_log.h
@@ -0,0 +1,223 @@
+/*******************************************************************************
+Copyright (C) 2015, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+********************************************************************************/
+
+/**
+ * @file vl53l1_platform_log.h
+ *
+ * @brief EwokPlus25 platform logging function definition
+ */
+
+
+#ifndef _VL53L1_PLATFORM_LOG_H_
+#define _VL53L1_PLATFORM_LOG_H_
+
+
+#ifdef VL53L1_LOG_ENABLE
+ #include "vl53l1_platform_user_config.h"
+
+ #ifdef _MSC_VER
+ # define EWOKPLUS_EXPORTS __declspec(dllexport)
+ #else
+ # define EWOKPLUS_EXPORTS
+ #endif
+
+ #include "vl53l1_types.h"
+
+ #ifdef __cplusplus
+ extern "C" {
+ #endif
+
+ #include
+
+ /**
+ * @brief Set the level, output and specific functions for module logging.
+ *
+ *
+ * @param filename - full path of output log file, NULL for print to stdout
+ *
+ * @param modules - Module or None or All to trace
+ * VL53L1_TRACE_MODULE_NONE
+ * VL53L1_TRACE_MODULE_API
+ * VL53L1_TRACE_MODULE_CORE
+ * VL53L1_TRACE_MODULE_TUNING
+ * VL53L1_TRACE_MODULE_CHARACTERISATION
+ * VL53L1_TRACE_MODULE_PLATFORM
+ * VL53L1_TRACE_MODULE_ALL
+ *
+ * @param level - trace level
+ * VL53L1_TRACE_LEVEL_NONE
+ * VL53L1_TRACE_LEVEL_ERRORS
+ * VL53L1_TRACE_LEVEL_WARNING
+ * VL53L1_TRACE_LEVEL_INFO
+ * VL53L1_TRACE_LEVEL_DEBUG
+ * VL53L1_TRACE_LEVEL_ALL
+ * VL53L1_TRACE_LEVEL_IGNORE
+ *
+ * @param functions - function level to trace;
+ * VL53L1_TRACE_FUNCTION_NONE
+ * VL53L1_TRACE_FUNCTION_I2C
+ * VL53L1_TRACE_FUNCTION_ALL
+ *
+ * @return status - always VL53L1_ERROR_NONE
+ *
+ */
+
+ #define VL53L1_TRACE_LEVEL_NONE 0x00000000
+ #define VL53L1_TRACE_LEVEL_ERRORS 0x00000001
+ #define VL53L1_TRACE_LEVEL_WARNING 0x00000002
+ #define VL53L1_TRACE_LEVEL_INFO 0x00000004
+ #define VL53L1_TRACE_LEVEL_DEBUG 0x00000008
+ #define VL53L1_TRACE_LEVEL_ALL 0x00000010
+ #define VL53L1_TRACE_LEVEL_IGNORE 0x00000020
+
+ #define VL53L1_TRACE_FUNCTION_NONE 0x00000000
+ #define VL53L1_TRACE_FUNCTION_I2C 0x00000001
+ #define VL53L1_TRACE_FUNCTION_ALL 0x7fffffff
+
+ #define VL53L1_TRACE_MODULE_NONE 0x00000000
+ #define VL53L1_TRACE_MODULE_API 0x00000001
+ #define VL53L1_TRACE_MODULE_CORE 0x00000002
+ #define VL53L1_TRACE_MODULE_PROTECTED 0x00000004
+ #define VL53L1_TRACE_MODULE_HISTOGRAM 0x00000008
+ #define VL53L1_TRACE_MODULE_REGISTERS 0x00000010
+ #define VL53L1_TRACE_MODULE_PLATFORM 0x00000020
+ #define VL53L1_TRACE_MODULE_NVM 0x00000040
+ #define VL53L1_TRACE_MODULE_CALIBRATION_DATA 0x00000080
+ #define VL53L1_TRACE_MODULE_NVM_DATA 0x00000100
+ #define VL53L1_TRACE_MODULE_HISTOGRAM_DATA 0x00000200
+ #define VL53L1_TRACE_MODULE_RANGE_RESULTS_DATA 0x00000400
+ #define VL53L1_TRACE_MODULE_XTALK_DATA 0x00000800
+ #define VL53L1_TRACE_MODULE_OFFSET_DATA 0x00001000
+ #define VL53L1_TRACE_MODULE_DATA_INIT 0x00002000
+ #define VL53L1_TRACE_MODULE_REF_SPAD_CHAR 0x00004000
+ #define VL53L1_TRACE_MODULE_SPAD_RATE_MAP 0x00008000
+ #ifdef PAL_EXTENDED
+ #define VL53L1_TRACE_MODULE_SPAD 0x01000000
+ #define VL53L1_TRACE_MODULE_FMT 0x02000000
+ #define VL53L1_TRACE_MODULE_UTILS 0x04000000
+ #define VL53L1_TRACE_MODULE_BENCH_FUNCS 0x08000000
+ #endif
+ #define VL53L1_TRACE_MODULE_CUSTOMER_API 0x40000000
+ #define VL53L1_TRACE_MODULE_ALL 0x7fffffff
+
+
+ extern uint32_t _trace_level;
+
+ /*
+ * NOTE: dynamically exported if we enable logging.
+ * this way, Python interfaces can access this function, but we don't
+ * need to include it in the .def files.
+ */
+ EWOKPLUS_EXPORTS int8_t VL53L1_trace_config(
+ char *filename,
+ uint32_t modules,
+ uint32_t level,
+ uint32_t functions);
+
+ /**
+ * @brief Print trace module function.
+ *
+ * @param module - ??
+ * @param level - ??
+ * @param function - ??
+ * @param format - ??
+ *
+ */
+
+ EWOKPLUS_EXPORTS void VL53L1_trace_print_module_function(
+ uint32_t module,
+ uint32_t level,
+ uint32_t function,
+ const char *format, ...);
+
+ /**
+ * @brief Get global _trace_functions parameter
+ *
+ * @return _trace_functions
+ */
+
+ uint32_t VL53L1_get_trace_functions(void);
+
+ /**
+ * @brief Set global _trace_functions parameter
+ *
+ * @param[in] function : new function code
+ */
+
+ void VL53L1_set_trace_functions(uint32_t function);
+
+
+ /*
+ * @brief Returns the current system tick count in [ms]
+ *
+ * @return time_ms : current time in [ms]
+ *
+ */
+
+ uint32_t VL53L1_clock(void);
+
+ #define LOG_GET_TIME() \
+ ((int)VL53L1_clock())
+
+ #define _LOG_TRACE_PRINT(module, level, function, ...) \
+ VL53L1_trace_print_module_function(module, level, function, ##__VA_ARGS__);
+
+ #define _LOG_FUNCTION_START(module, fmt, ...) \
+ VL53L1_trace_print_module_function(module, _trace_level, VL53L1_TRACE_FUNCTION_ALL, "%6ld %s "fmt"\n", LOG_GET_TIME(), __FUNCTION__, ##__VA_ARGS__);
+
+ #define _LOG_FUNCTION_END(module, status, ...)\
+ VL53L1_trace_print_module_function(module, _trace_level, VL53L1_TRACE_FUNCTION_ALL, "%6ld %s %d\n", LOG_GET_TIME(), __FUNCTION__, (int)status, ##__VA_ARGS__)
+
+ #define _LOG_FUNCTION_END_FMT(module, status, fmt, ...)\
+ VL53L1_trace_print_module_function(module, _trace_level, VL53L1_TRACE_FUNCTION_ALL, "%6ld %s %d "fmt"\n", LOG_GET_TIME(), __FUNCTION__, (int)status, ##__VA_ARGS__)
+
+ #define _LOG_GET_TRACE_FUNCTIONS()\
+ VL53L1_get_trace_functions()
+
+ #define _LOG_SET_TRACE_FUNCTIONS(functions)\
+ VL53L1_set_trace_functions(functions)
+
+ #define _LOG_STRING_BUFFER(x) char x[VL53L1_MAX_STRING_LENGTH]
+
+ #ifdef __cplusplus
+ }
+ #endif
+
+#else /* VL53L1_LOG_ENABLE - no logging */
+
+ #define _LOG_TRACE_PRINT(module, level, function, ...)
+ #define _LOG_FUNCTION_START(module, fmt, ...)
+ #define _LOG_FUNCTION_END(module, status, ...)
+ #define _LOG_FUNCTION_END_FMT(module, status, fmt, ...)
+ #define _LOG_GET_TRACE_FUNCTIONS() 0
+ #define _LOG_SET_TRACE_FUNCTIONS(functions)
+ #define _LOG_STRING_BUFFER(x)
+
+#endif /* VL53L1_LOG_ENABLE */
+
+#endif /* _VL53L1_PLATFORM_LOG_H_ */
diff --git a/src/lib/vl53l1/vl53l1_platform_user_config.h b/src/lib/vl53l1/vl53l1_platform_user_config.h
new file mode 100644
index 0000000000..e73bb9150d
--- /dev/null
+++ b/src/lib/vl53l1/vl53l1_platform_user_config.h
@@ -0,0 +1,84 @@
+/*******************************************************************************
+Copyright (C) 2015, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+********************************************************************************/
+
+/**
+ * @file vl53l1_platform_user_config.h
+ *
+ * @brief EwokPlus compile time user modifiable configuration
+ */
+
+
+#ifndef _VL53L1_PLATFORM_USER_CONFIG_H_
+#define _VL53L1_PLATFORM_USER_CONFIG_H_
+
+#define VL53L1_BYTES_PER_WORD 2
+#define VL53L1_BYTES_PER_DWORD 4
+
+/* Define polling delays */
+#define VL53L1_BOOT_COMPLETION_POLLING_TIMEOUT_MS 500
+#define VL53L1_RANGE_COMPLETION_POLLING_TIMEOUT_MS 2000
+#define VL53L1_TEST_COMPLETION_POLLING_TIMEOUT_MS 60000
+
+#define VL53L1_POLLING_DELAY_MS 1
+
+/* Define LLD TuningParms Page Base Address
+ * - Part of Patch_AddedTuningParms_11761
+ */
+#define VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS 0x8000
+#define VL53L1_TUNINGPARM_PRIVATE_PAGE_BASE_ADDRESS 0xC000
+
+#define VL53L1_GAIN_FACTOR__STANDARD_DEFAULT 0x0800
+ /*!< Default standard ranging gain correction factor
+ 1.11 format. 1.0 = 0x0800, 0.980 = 0x07D7 */
+
+#define VL53L1_OFFSET_CAL_MIN_EFFECTIVE_SPADS 0x0500
+ /*!< Lower Limit for the MM1 effective SPAD count during offset
+ calibration Format 8.8 0x0500 -> 5.0 effective SPADs */
+
+#define VL53L1_OFFSET_CAL_MAX_PRE_PEAK_RATE_MCPS 0x1900
+ /*!< Max Limit for the pre range peak rate during offset
+ calibration Format 9.7 0x1900 -> 50.0 Mcps.
+ If larger then in pile up */
+
+#define VL53L1_OFFSET_CAL_MAX_SIGMA_MM 0x0040
+ /*!< Max sigma estimate limit during offset calibration
+ Check applies to pre-range, mm1 and mm2 ranges
+ Format 14.2 0x0040 -> 16.0mm. */
+
+#define VL53L1_MAX_USER_ZONES 1
+ /*!< Max number of user Zones - maximal limitation from
+ FW stream divide - value of 254 */
+
+#define VL53L1_MAX_RANGE_RESULTS 2
+ /*!< Allocates storage for return and reference restults */
+
+
+#define VL53L1_MAX_STRING_LENGTH 512
+
+#endif /* _VL53L1_PLATFORM_USER_CONFIG_H_ */
+
diff --git a/src/lib/vl53l1/vl53l1_platform_user_data.h b/src/lib/vl53l1/vl53l1_platform_user_data.h
new file mode 100644
index 0000000000..76d93071bc
--- /dev/null
+++ b/src/lib/vl53l1/vl53l1_platform_user_data.h
@@ -0,0 +1,120 @@
+/*******************************************************************************
+ Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ ******************************************************************************/
+
+
+#ifndef _VL53L1_PLATFORM_USER_DATA_H_
+#define _VL53L1_PLATFORM_USER_DATA_H_
+
+#ifndef __KERNEL__
+#include
+#endif
+
+#include "vl53l1_def.h"
+#include "i2cdev.h"
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/**
+ * @file vl53l1_platform_user_data.h
+ *
+ * @brief All end user OS/platform/application porting
+ */
+
+/** @brief Contains the current state and internal values of the API
+ */
+
+typedef struct {
+
+ VL53L1_DevData_t Data;
+ /*!< Low Level Driver data structure */
+
+ uint8_t devAddr;
+ /*!< i2c device address user specific field */
+ I2C_Dev *I2Cx;
+
+ uint32_t new_data_ready_poll_duration_ms;
+ /*!< New data ready poll duration in ms - for debug */
+} VL53L1_Dev_t;
+
+
+/**
+ * @brief Declare the device Handle as a pointer of the structure @a VL53L1_Dev_t.
+ *
+ */
+typedef VL53L1_Dev_t *VL53L1_DEV;
+
+/**
+ * @def PALDevDataGet
+ * @brief Get ST private structure @a VL53L1_DevData_t data access
+ *
+ * @param Dev Device Handle
+ * @param field ST structure field name
+ * It maybe used and as real data "ref" not just as "get" for sub-structure item
+ * like PALDevDataGet(FilterData.field)[i] or
+ * PALDevDataGet(FilterData.MeasurementIndex)++
+ */
+#define PALDevDataGet(Dev, field) (Dev->Data.field)
+
+
+/**
+ * @def PALDevDataSet(Dev, field, data)
+ * @brief Set ST private structure @a VL53L1_DevData_t data field
+ * @param Dev Device Handle
+ * @param field ST structure field name
+ * @param data Data to be set
+ */
+#define PALDevDataSet(Dev, field, data) ((Dev->Data.field) = (data))
+
+
+/**
+ * @def VL53L1DevStructGetLLDriverHandle
+ * @brief Get LL Driver handle @a VL53L0_Dev_t data access
+ *
+ * @param Dev Device Handle
+ */
+#define VL53L1DevStructGetLLDriverHandle(Dev) (&Dev->Data.LLData)
+
+/**
+ * @def VL53L1DevStructGetLLResultsHandle
+ * @brief Get LL Results handle @a VL53L0_Dev_t data access
+ *
+ * @param Dev Device Handle
+ */
+#define VL53L1DevStructGetLLResultsHandle(Dev) (&Dev->Data.llresults)
+
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
+
diff --git a/src/lib/vl53l1/vl53l1_platform_user_defines.h b/src/lib/vl53l1/vl53l1_platform_user_defines.h
new file mode 100644
index 0000000000..04ad850147
--- /dev/null
+++ b/src/lib/vl53l1/vl53l1_platform_user_defines.h
@@ -0,0 +1,95 @@
+/*******************************************************************************
+ Copyright (C) 2016, STMicroelectronics International N.V.
+ All rights reserved.
+
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+ NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+ IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+ DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ ******************************************************************************/
+
+
+#ifndef _VL53L1_PLATFORM_USER_DEFINES_H_
+#define _VL53L1_PLATFORM_USER_DEFINES_H_
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/**
+ * @file vl53l1_platform_user_defines.h
+ *
+ * @brief All end user OS/platform/application definitions
+ */
+
+
+/**
+ * @def do_division_u
+ * @brief customer supplied division operation - 64-bit unsigned
+ *
+ * @param dividend unsigned 64-bit numerator
+ * @param divisor unsigned 64-bit denominator
+ */
+#define do_division_u(dividend, divisor) (dividend / divisor)
+
+
+/**
+ * @def do_division_s
+ * @brief customer supplied division operation - 64-bit signed
+ *
+ * @param dividend signed 64-bit numerator
+ * @param divisor signed 64-bit denominator
+ */
+#define do_division_s(dividend, divisor) (dividend / divisor)
+
+
+/**
+ * @def WARN_OVERRIDE_STATUS
+ * @brief customer supplied macro to optionally output info when a specific
+ error has been overridden with success within the EwokPlus driver
+ *
+ * @param __X__ the macro which enabled the suppression
+ */
+#define WARN_OVERRIDE_STATUS(__X__)\
+ trace_print (VL53L1_TRACE_LEVEL_WARNING, #__X__);
+
+
+#ifdef _MSC_VER
+#define DISABLE_WARNINGS() { \
+ __pragma (warning (push)); \
+ __pragma (warning (disable:4127)); \
+ }
+#define ENABLE_WARNINGS() { \
+ __pragma (warning (pop)); \
+ }
+#else
+ #define DISABLE_WARNINGS()
+ #define ENABLE_WARNINGS()
+#endif
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif // _VL53L1_PLATFORM_USER_DEFINES_H_
+
diff --git a/src/lib/vl53l1/vl53l1_types.h b/src/lib/vl53l1/vl53l1_types.h
new file mode 100644
index 0000000000..c0603b707b
--- /dev/null
+++ b/src/lib/vl53l1/vl53l1_types.h
@@ -0,0 +1,114 @@
+/*******************************************************************************
+Copyright (C) 2015, STMicroelectronics International N.V.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright
+ notice, this list of conditions and the following disclaimer in the
+ documentation and/or other materials provided with the distribution.
+ * Neither the name of STMicroelectronics nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
+NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
+IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+********************************************************************************/
+/**
+ * @file vl53l1_types.h
+ * @brief VL53L1 types definition
+ */
+
+#ifndef _VL53L1_TYPES_H_
+#define _VL53L1_TYPES_H_
+
+/** @defgroup porting_type Basic type definition
+ * @ingroup api_platform
+ *
+ * @brief file vl53l1_types.h files hold basic type definition that may requires porting
+ *
+ * contains type that must be defined for the platform\n
+ * when target platform and compiler provide stdint.h and stddef.h it is enough to include it.\n
+ * If stdint.h is not available review and adapt all signed and unsigned 8/16/32 bits basic types. \n
+ * If stddef.h is not available review and adapt NULL definition .
+ */
+#include
+#include
+#include
+#include
+#include
+
+#ifndef NULL
+#error "Error NULL definition should be done. Please add required include "
+#endif
+
+
+#if !defined(STDINT_H) && !defined(_STDINT_H) && !defined(_GCC_STDINT_H) && !defined(__STDINT_DECLS) && !defined(_GCC_WRAP_STDINT_H) && !defined(_STDINT)
+
+ #pragma message("Please review type definition of STDINT define for your platform and add to list above ")
+
+ /*
+ * target platform do not provide stdint or use a different #define than above
+ * to avoid seeing the message below addapt the #define list above or implement
+ * all type and delete these pragma
+ */
+
+/** \ingroup VL53L1_portingType_group
+ * @{
+ */
+
+
+typedef unsigned long long uint64_t;
+
+
+/** @brief Typedef defining 32 bit unsigned int type.\n
+ * The developer should modify this to suit the platform being deployed.
+ */
+typedef unsigned int uint32_t;
+
+/** @brief Typedef defining 32 bit int type.\n
+ * The developer should modify this to suit the platform being deployed.
+ */
+typedef int int32_t;
+
+/** @brief Typedef defining 16 bit unsigned short type.\n
+ * The developer should modify this to suit the platform being deployed.
+ */
+typedef unsigned short uint16_t;
+
+/** @brief Typedef defining 16 bit short type.\n
+ * The developer should modify this to suit the platform being deployed.
+ */
+typedef short int16_t;
+
+/** @brief Typedef defining 8 bit unsigned char type.\n
+ * The developer should modify this to suit the platform being deployed.
+ */
+typedef unsigned char uint8_t;
+
+/** @brief Typedef defining 8 bit char type.\n
+ * The developer should modify this to suit the platform being deployed.
+ */
+typedef signed char int8_t;
+
+/** @} */
+#endif /* _STDINT_H */
+
+
+/** use where fractional values are expected
+ *
+ * Given a floating point value f it's .16 bit point is (int)(f*(1<<16))*/
+typedef uint32_t FixPoint1616_t;
+
+#endif /* VL53L1_TYPES_H_ */