Condensed Version of Public VL53L0X

Dependents:   ToF-Only-Tryout

VL53L0X.h

Committer:
sepp_nepp
Date:
2019-04-08
Revision:
11:c6f95a42d4d7
Parent:
10:cd251e0fc2fd
Child:
12:aa177f0e4c10

File content as of revision 11:c6f95a42d4d7:

/*******************************************************************************
 Copyright © 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 __VL53L0X_CLASS_H
#define __VL53L0X_CLASS_H

/* Includes ------------------------------------------------------------------*/
#include "mbed.h"
#include "pinmap.h"
#include "PinNames.h"
#include "VL53L0X_def.h"

/* Classes -------------------------------------------------------------------*/
/** Class representing a VL53L0 sensor component
 */
class VL53L0X 
{
public:
    /* Device data made accessible for further usage */
    TVL53L0X_DeviceInfo Device_Info;

public: 
	/******************************************************************************/
	/****************** Public Initialization Methods     *************************/
	/******************************************************************************/

    /** Constructor
     * @param[in] &i2c device I2C to be used for communication
     * @param[in] &pin_gpio1 pin Mbed InterruptIn PinName to be used as component GPIO_1 INT
     * @param[in] dev_addr device address, 0x29 by default
     */
    VL53L0X(I2C *i2c, DigitalOut *pin, PinName pin_gpio1, 
        uint8_t dev_addr = VL53L0X_DEFAULT_ADDRESS) : _dev_i2c(i2c), _gpio0(pin)
    {   I2cDevAddr = dev_addr;
        if (pin_gpio1 != NC) { _gpio1Int = new InterruptIn(pin_gpio1); } 
           else { _gpio1Int = NULL;  }
    }

    /**
     * @brief       Turns on, checks the ID, Set new device address, 
     *              Initialize the calss, and the sensor with default values
     *
     * After completion the device will answer to the address new_addr.
     * This new_addr should be set to individual values when several devices are used in parallel
     * before using the individual sensors.
     * When a single device us used, there is no need to set new_addr.
     * @return      VL53L0X_Error   	= 0 on success
     */
    VL53L0X_Error Start_Sensor(uint8_t new_addr = VL53L0X_DEFAULT_ADDRESS);

    /**
     * @brief       PowerOff the sensor with the XShutdown Pin
     */
    void Power_Off(void)
    {	if (_gpio0) { *_gpio0 = 0; }   wait_ms(1); }


    /** Destructor  */
    virtual ~VL53L0X()
    {  if (_gpio1Int != NULL) { delete _gpio1Int; } }


private: 
	/******************************************************************************/
	/****************** Private Initialization Methods    *************************/
	/******************************************************************************/

    /**
     * @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 void WaitDeviceBooted()
     *
     * @par Function Description
     * When not used after a fresh device "power up" or reset, it may return
     * @a #VL53L0X_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 VL53L0X_DataInit
     * multiple time then it  must ensure proper offset calibration saving and
     * restore on its own by using @a VL53L0X_GetOffsetCalibrationData() on first
     * power up and then @a VL53L0X_SetOffsetCalibrationData() in all subsequent init
     * This function will change the VL53L0X_State from VL53L0X_STATE_POWERDOWN to
     * VL53L0X_STATE_WAIT_STATICINIT.
     *
     * @note This function accesses to the device
     * 
     * @return  None; instead check class Field "ErrState"
     */
    void Data_init();
 
    /**
     * @brief Reads the Device information for given Device
     *
     * @note This function is called once at Sensor Init, then all device info
     *    available in the Device_Info Structure
     * 
     * @return   Device_Info  Structure is filled with device info for the Device
     *           Also check and fix errors reported Field "ErrState"   */
    void Fill_device_info();
    
public:
    /**
     * @brief       Start the measure indicated by operating mode
     * @param[in]   operating_mode specifies requested measure
     * @param[in]   fptr specifies call back function must be !NULL in case of interrupt measure
     */
    VL53L0X_Error Start_Measurement(TOperatingMode operating_mode, 
                   void (*fptr)(void));

    /**
     * @brief       Get results for the measure indicated by operating mode
     * @param[in]   operating_mode specifies requested measure results
     * @result       TRangeResults The MeasureData_t structure with all results
     */
    TRangeResults Get_Measurement(TOperatingMode operating_mode);

    /**
     * @brief       Stop the currently running measure indicate by operating_mode
     * @param[in]   operating_mode specifies requested measure to stop
     "0" on success
     */
    VL53L0X_Error Stop_Measurement(TOperatingMode operating_mode);

    /**
     * @brief     Interrupt handling func to be called by user after an INT is occourred
     * @param[in] operating_mode  Opeating_mode indicating the in progress measure
     * @result    TRangeResults   The Measurement Data structure given back
     */
    TRangeResults Handle_irq(TOperatingMode operating_mode);

    /**
     * @brief       Enable interrupt measure IRQ
     */
    void Enable_interrupt_measure_detection_irq(void)
    {  if (_gpio1Int != NULL) { _gpio1Int->enable_irq(); }  }

    /**
     * @brief       Disable interrupt measure IRQ
     "0" on success
     */
    void Disable_interrupt_measure_detection_irq(void)
    {  if (_gpio1Int != NULL) { _gpio1Int->disable_irq(); }  }

    /**
     * @brief       Attach a function to call when an interrupt is detected, i.e. measurement is ready
     * @param[in]   fptr pointer to call back function to be called whenever an interrupt occours
     "0" on success
     */
    void Attach_interrupt_measure_detection_irq(void (*fptr)(void))
    {   if (_gpio1Int != NULL) { _gpio1Int->rise(fptr);  }    }

    /** Wrapper functions */
    /** @defgroup api_init Init functions
     *  @brief    API init functions
     *  @ingroup  api_hl
     *  @{
     */

    /**
      * @brief  Prepare device for operation
      * @par Function Description
      * Does static initialization and reprogram common default settings \n
      * Device is prepared for new measure, ready single shot ranging or ALS typical polling operation\n
      * After prepare user can : \n
      * @li Call other API function to set other settings\n
      * @li Configure the interrupt pins, etc... \n
      * @li Then start ranging or ALS operations in single shot or continuous mode
      *
      * @param void
      * @return  "0" on success
      */
    VL53L0X_Error Prepare();

    /**
    * @brief Start continuous ranging mode
    *
    * @details End user should ensure device is in idle state and not already running
    * @return  "0" on success
    */
    void Range_start_continuous_mode()
    {	Set_device_mode( VL53L0X_DEVICEMODE_CONTINUOUS_RANGING);
        if (ErrState == VL53L0X_OK) {  Start_Measurement();  }
    }

    /**
     * @brief Get ranging result and only that
     *
     * @par Function Description
     * Unlike @a Get_ranging_results() this function only retrieves the range in millimeter \n
     * It does any required up-scale translation\n
     * It can be called after success ErrState polling or in interrupt mode \n
     * @warning these function is not doing wrap around filtering \n
     * This function doesn't perform any data ready check!
     *
     * @param p_data  Pointer to range distance
       "0" on success
     */
    uint32_t Get_distance();

    /** @}  */



    /**
     * @brief Do basic device init (and eventually patch loading)
     * This function will change the VL53L0X_State from
     * VL53L0X_STATE_WAIT_STATICINIT to VL53L0X_STATE_IDLE.
     * In this stage all default setting will be applied.
     *
     * @note This function Access to the device
     *
     * 
     * @return  None; instead check class Field "ErrState"
     */
    void Static_init();

    /**
     * @brief Perform Reference Calibration
     *
     * @details Perform a reference calibration of the Device.
     * This function should be run from time to time before doing
     * a ranging measurement.
     * This function will launch a special ranging measurement, so
     * if interrupt are enable an interrupt will be done.
     * This function will clear the interrupt generated automatically.
     *
     * @warning This function is a blocking function
     *
     * @note This function Access to the device
     *
     * 
     * @param   p_vhv_settings       Pointer to vhv settings parameter.
     * @param   p_phase_cal          Pointer to PhaseCal parameter.
     * @param   get_data_enable      1 to enable to get the data
     * @return  None; instead check class Field "ErrState"
     */
    void Perf_Ref_calibration(
            uint8_t *p_vhv_settings, uint8_t *p_phase_cal, uint8_t get_data_enable);

    /**
     * @brief Get Reference Calibration Parameters
     *
     * @par Function Description
     * Get Reference Calibration Parameters.
     *
     * @note This function Access to the device
     *
     * 
     * @param   p_vhv_settings                 Pointer to VHV parameter
     * @param   p_phase_cal                    Pointer to PhaseCal Parameter
     * @return  None; instead check class Field "ErrState"            
     */
    void Get_Ref_calibration(
            uint8_t *p_vhv_settings, uint8_t *p_phase_cal);

    void Set_Ref_calibration(
            uint8_t vhv_settings, uint8_t phase_cal);

    /**
     * @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
     *
     * @note This function change the device mode to
     * VL53L0X_DEVICEMODE_SINGLE_RANGING
     *
     * 
     * @param   ref_SPAD_count               Reports ref SPAD Count
     * @param   is_aperture_SPADS            Reports if SPADS are of type
     *                                       aperture or non-aperture.
     *                                       1:=aperture, 0:=Non-Aperture
     * @return  None; instead check class Field "ErrState"       
     * @return  VL53L0X_ERROR_REF_SPAD_INIT  Error in the Ref SPAD procedure.
     */
    void Perf_Ref_SPAD_management(
            uint32_t *ref_SPAD_count, uint8_t *is_aperture_SPADS);

    /**
     * @brief Applies Reference SPAD configuration
     *
     * @par Function Description
     * This function applies a given number of reference SPADS, identified as
     * either Aperture or Non-Aperture.
     * The requested SPAD count and type are stored within the device specific
     * parameters data for access by the host.
     *
     * @note This function Access to the device
     *
     * 
     * @param   refSPADCount                 Number of ref SPADS.
     * @param   is_aperture_SPADS            Defines if SPADS are of type
     *                                       aperture or non-aperture.
     *                                       1:=aperture, 0:=Non-Aperture
     * @return  None; instead check class Field "ErrState"       
     * @return  VL53L0X_ERROR_REF_SPAD_INIT  Error in the in the reference
     *                                       SPAD configuration.
     */
    void Set_Reference_SPADS(
            uint32_t refSPADCount, uint8_t is_aperture_SPADS);

    /**
     * @brief Retrieves SPAD configuration
     *
     * @par Function Description
     * This function retrieves the current number of applied reference SPADS
     * and also their type : Aperture or Non-Aperture.
     *
     * @note This function Access to the device
     *
     * 
     * @param   p_SPAD_count                 Number ref SPAD Count
     * @param   p_is_aperture_SPADS          Reports if SPADS are of type
     *                                       aperture or non-aperture.
     *                                       1:=aperture, 0:=Non-Aperture
     * @return  None; instead check class Field "ErrState"       
     * @return  VL53L0X_ERROR_REF_SPAD_INIT  Error in the in the reference
     *                                       SPAD configuration.
     */
    void Get_Reference_SPADS(
            uint32_t *p_SPAD_count, uint8_t *p_is_aperture_SPADS);

    /**
     * @brief Get part to part calibration offset
     *
     * @par Function Description
     * Should only be used after a successful call to @a VL53L0X_DataInit to backup
     * device NVM value
     *
     * @note This function Access to the device
     *
     * @param   p_Offset_Cal_um   
     * @return  int32_t; Return part to part calibration offset from device (microns), also check class Field "ErrState"                           
     */
    int32_t Get_Offset_Cal_um();
    /**
     * Set or over-hide part to part calibration offset
     * \sa VL53L0X_DataInit()   VL53L0X_GetOffsetCalibrationData_um()
     *
     * @note This function Access to the device
     *
     * @param   p_Offset_Cal_um    Offset (microns)
     * @return  None; instead check class Field "ErrState"                           
     */
    void Set_Offset_Cal_um(  int32_t Offset_Cal_um  );

    void Perf_offset_calibration( TFP1616 cal_distance_milli_meter,
            int32_t *p_offset_um);

    void Perf_xtalk_calibration(  TFP1616 xtalk_cal_distance,
            TFP1616 *p_Xtalk_CompRate_MHz);

    /**
     * @brief Perform XTalk Measurement
     *
     * @details Measures the current cross talk from glass in front
     * of the sensor.
     * This functions performs a histogram measurement and uses the results
     * to measure the crosstalk. For the function to be successful, there
     * must be no target in front of the sensor.
     *
     * @warning This function is a blocking function
     *
     * @warning This function is not supported when the final range
     * vcsel clock period is set below 10 PCLKS.
     *
     * @note This function Access to the device
     *
     * 
     * @param   timeout_ms             Histogram measurement duration.
     * @param   p_xtalk_per_SPAD       Output parameter containing the crosstalk
     *                                 measurement result, in MHz/SPAD.
     *                                 Format fixpoint 16:16.
     * @param   p_ambient_too_high     Output parameter which indicate that
     *                                 pXtalkPerSPAD is not good if the Ambient
     *                                 is too high.
     * @return  None; instead check class Field "ErrState" 
     * @return  VL53L0X_ERROR_INVALID_PARAMS vcsel clock period not supported
     *                                 for this operation.
     *                                 Must not be less than 10PCLKS.
     */
    void Perf_xtalk_measurement(
            uint32_t timeout_ms, TFP1616 *p_xtalk_per_SPAD,
            uint8_t *p_ambient_too_high);

    /**
     * @brief Enable/Disable Cross talk compensation feature
     *
     * @note This function is not Implemented.
     * Enable/Disable Cross Talk by set to zero the Cross Talk value
     * by using @a VL53L0X_SetXtalk_CompRate_MHz().
     *
     * 
     * @param  xtalk_compensation_enable    Cross talk compensation
     *                                       to be set 0=disabled else = enabled
     * @return VL53L0X_ERROR_NOT_IMPLEMENTED Not implemented
     */
    void Set_xtalk_compensation_enable(
            uint8_t xtalk_compensation_enable);

     /**
     * @brief Set Cross talk compensation rate
     *
     * @par Function Description
     * Set Cross talk compensation rate.
     *
     * @note This function Access to the device
     *
     * 
     * @param   Xtalk_CompRate_MHz   Compensation rate in
     *                                              Mega counts per second
     *                                              (16.16 fix point) see
     *                                              datasheet for details
     * @return  None; instead check class Field "ErrState"              
     */
    void Set_Xtalk_CompRate_MHz(  TFP1616 Xtalk_CompRate_MHz );

    /**
     * @brief Get Cross talk compensation rate
     *
     * @par Function Description 
     * Get Cross talk compensation rate.
     *
     * @note This function Access to the device
     *
     * 
     * @param   p_Xtalk_CompRate_MHz  Pointer to Compensation rate
     *                                              in Mega counts per second
     *                                              (16.16 fix point) see
     *                                              datasheet for details
     * @return  None; instead check class Field "ErrState"                
     */
     
    void Get_Xtalk_CompRate_MHz(
            TFP1616 *p_Xtalk_CompRate_MHz);

    /**
     * @brief  Set a new device mode
     * @par Function Description
     * Set device to a new mode (ranging, histogram ...)
     *
     * @note This function doesn't Access to the device
     *
     * 
     * @param   device_mode           New device mode to apply
     *                                Valid values are:
     *                                VL53L0X_DEVICEMODE_SINGLE_RANGING
     *                                VL53L0X_DEVICEMODE_CONTINUOUS_RANGING
     *                                VL53L0X_DEVICEMODE_CONTINUOUS_TIMED_RANGING
     *                                VL53L0X_DEVICEMODE_SINGLE_HISTOGRAM
     *                                VL53L0X_HISTOGRAMMODE_REFERENCE_ONLY
     *                                VL53L0X_HISTOGRAMMODE_RETURN_ONLY
     *                                VL53L0X_HISTOGRAMMODE_BOTH
     *
     *
     * @return  None; instead check class Field "ErrState"           
     * @return  VL53L0X_ERROR_MODE_NOT_SUPPORTED This error occurs when
     *                                           DeviceMode is not in the
     *                                           supported list
     */
    void Set_device_mode( VL53L0X_DeviceModes device_mode);

    /**
    * @brief Get current configuration for GPIO pin for a given device
    *
    * @note This function Access to the device
    *
    * 
    * @param   pin                   ID of the GPIO Pin
    * @param   p_device_mode         Pointer to Device Mode associated to the Gpio.
    * @param   p_functionality       Pointer to Pin functionality.
    *                                Refer to ::TGPIO_Func
    * @param   p_polarity            Pointer to interrupt polarity.
    *                                Active high or active low see
    *                                ::VL53L0X_InterruptPolarity
    * @return  None; instead check class Field "ErrState"
    * @return  VL53L0X_ERROR_GPIO_NOT_EXISTING           Only Pin=0 is accepted.
    * @return  VL53L0X_ERROR_GPIO_FUNC_NOT_SUPPORTED
    *          This error occurs
    *          when Funcionality programmed is not in the supported list:
    *                      Supported value are:
    *                      GPIO_FUNC_OFF,
    *                      GPIO_FUNC_THRESHOLD_CROSSED_LOW,
    *                      GPIO_FUNC_THRESHOLD_CROSSED_HIGH,
    *                      GPIO_FUNC_THRESHOLD_CROSSED_OUT,
    *                      GPIO_FUNC_NEW_MEASURE_READY
    */
    void Get_gpio_config( uint8_t pin, VL53L0X_DeviceModes *p_device_mode,
                                          TGPIO_Func *p_functionality,
                                          VL53L0X_InterruptPolarity *p_polarity);

    /**
     * @brief Set the configuration of GPIO pin for a given device
     *
     * @note This function Access to the device
     * 
     * @param   pin                   ID of the GPIO Pin
     * @param   functionality         Select Pin functionality.
     *  Refer to ::TGPIO_Func
     * @param   device_mode            Device Mode associated to the Gpio.
     * @param   polarity              Set interrupt polarity. Active high
     *   or active low see ::VL53L0X_InterruptPolarity
     * @return  None; instead check class Field "ErrState"                        
     * @return  VL53L0X_ERROR_GPIO_NOT_EXISTING               Only Pin=0 is accepted.
     * @return  VL53L0X_ERROR_GPIO_FUNC_NOT_SUPPORTED    This error occurs
     * when Functionality programmed is not in the supported list:
     *                             Supported value are:
     *                             	GPIO_FUNC_OFF,
     *                             	GPIO_FUNC_THRESHOLD_CROSSED_LOW,
     *                             	GPIO_FUNC_THRESHOLD_CROSSED_HIGH,
     *								GPIO_FUNC_THRESHOLD_CROSSED_OUT,
     *                              GPIO_FUNC_NEW_MEASURE_READY
     */
    void Set_GPIO_config( VL53L0X_DeviceModes device_mode, 
         TGPIO_Func functionality,  VL53L0X_InterruptPolarity polarity);

    /**
     * @brief Start device measurement
     *
     * @details Started measurement will depend on device parameters set through
     * @a VL53L0X_SetParameters()
     * This is a non-blocking function.
     * This function will change the VL53L0X_State from VL53L0X_STATE_IDLE to
     * VL53L0X_STATE_RUNNING.
     *
     * @note This function Access to the device
     *

     * 
     * @return  None; instead check class Field "ErrState"              
     * @return  VL53L0X_ERROR_MODE_NOT_SUPPORTED    This error occurs when
     * DeviceMode programmed with @a VL53L0X_SetDeviceMode is not in the supported
     * list:
     *                                   Supported mode are:
     *                                   VL53L0X_DEVICEMODE_SINGLE_RANGING,
     *                                   VL53L0X_DEVICEMODE_CONTINUOUS_RANGING,
     *                                   VL53L0X_DEVICEMODE_CONTINUOUS_TIMED_RANGING
     * @return  VL53L0X_ERROR_TIME_OUT    Time out on start measurement
     */
    void Start_Measurement();

    /**
     * @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 VL53L0X_State from VL53L0X_STATE_RUNNING
     *          to VL53L0X_STATE_IDLE.
     *
     * @note This function Access to the device
     *
     * 
     * @return  None; instead check class Field "ErrState"
     */
    void Stop_Measurement();

    /**
     * @brief Return device stop completion ErrState
     *
     * @par Function Description
     * Returns stop completiob ErrState.
     * User shall call this function after a stop command
     *
     * @note This function Access to the device
     *
     * 
     * @return   p_stop_status            Pointer to ErrState variable to update
     *                                    Also instead check class Field "ErrState"  
     */
    uint8_t Get_Stop_Completed( );

    /**
     * @brief Return Measurement is Ready
     *
     * @par Function Description
     * This function indicate that a measurement data is ready.
     * This function check if interrupt mode is used then check is done accordingly.
     * If perform function clear the interrupt, this function will not work,
     * like in case of @a VL53L0X_PerformSingleRangingMeasurement().
     * The previous function is blocking function, VL53L0X_GetMeasurementDataReady
     * is used for non-blocking capture.
     *
     * @note This function Access to the device
     *
     * 
     * @return   uint8_t     Is Measurement Ready 0= not ready, 1 = ready
     * 					     Also check class Field "ErrState"  
     */
    uint8_t Get_Measurement_Ready();

    /**
     * @brief Retrieve the measurements from device for a given setup
     *
     * @par Function Description
     * Get data from last successful Ranging measurement
     * @warning USER should take care about  @a VL53L0X_GetNumberOfROIZones()
     * before get data.
     * Device will fill a NumberOfROIZones times the corresponding data
     * structure used in the measurement function.
     *
     * @note This function Access to the device
     *
     * 
     * @param   p_ranging_results  Pointer to the data structure to fill up.
     * @return  None; instead check class Field "ErrState"    
     */
    void Get_ranging_results(
            TRangeResults *p_ranging_results);

    /**
     * @brief Clear given system interrupt condition
     *
     * @par Function Description
     * Clear given interrupt(s) cause by writing into register #SYSINT_CLEAR register.
     *
     * @note   This function Access to the device
     * 
     * @param   interrupt_mask        Which interrupt source to clear. Use any combinations of #INTERRUPT_CLEAR_RANGING , #INTERRUPT_CLEAR_ALS , #INTERRUPT_CLEAR_ERROR.
     * @return  None; instead check class Field "ErrState"
     * @return  VL53L0X_ERROR_INTERRUPT_NOT_CLEARED    Cannot clear interrupts
     */
     void Clear_interrupt_mask( uint32_t interrupt_mask);

    /**
     * @brief Return device interrupt ErrState
     *
     * @par Function Description
     * Returns currently raised interrupts by the device.
     * User shall be able to activate/deactivate interrupts through
     * @a VL53L0X_SetGpioConfig()
     *
     * @note This function Access to the device
     *
     * 
     * @param   p_interrupt_mask_status   Pointer to ErrState variable to update
     * @return  None; instead check class Field "ErrState"
     */
    void Get_interrupt_mask_status(  uint32_t *p_interrupt_mask_status);

    /**
     * @brief Performs a single ranging measurement and retrieve the ranging
     * measurement data
     *
     * @par Function Description
     * This function will change the device mode to VL53L0X_DEVICEMODE_SINGLE_RANGING
     * with @a VL53L0X_SetDeviceMode(),
     * It performs measurement with @a VL53L0X_PerformSingleMeasurement()
     * It get data from last successful Ranging measurement with
     * @a VL53L0X_GetRangingMeasurementData.
     * Finally it clear the interrupt with @a VL53L0X_ClearInterruptMask().
     *
     * @note This function Access to the device
     *
     * @note This function change the device mode to
     * VL53L0X_DEVICEMODE_SINGLE_RANGING
     *
     * 
     * @param   p_ranging_results   Pointer to the data structure to fill up.
     * @return  None; instead check class Field "ErrState"     
     */
    void Perf_single_ranging_measurement(
            TRangeResults *p_ranging_results);

    /**
     * @brief Single shot measurement.
     *
     * @par Function Description
     * Perform simple measurement sequence (Start measure, Wait measure to end,
     * and returns when measurement is done).
     * Once function returns, user can get valid data by calling
     * VL53L0X_GetRangingMeasurement or VL53L0X_GetHistogramMeasurement
     * depending on defined measurement mode
     * User should Clear the interrupt in case this are enabled by using the
     * function VL53L0X_ClearInterruptMask().
     *
     * @warning This function is a blocking function
     *
     * @note This function Access to the device
     *
     * 
     * @return  None; instead check class Field "ErrState"
     */
    void Perf_single_measurement();

    /**
    * @brief Read current ErrState of the error register for the selected device
    *
    * @note This function Access to the device
    *
    * @param   p_device_error_status    Pointer to current error code of the device
    * @return  None; instead check class Field "ErrState" 
    */
    void Get_device_error_status(TDevError *p_device_error_status);

    /**
    * @brief Human readable error string for a given Error Code
    *
    * @note This function doesn't access to the device
    *
    * @param   error_code           The error code as stored on ::TDevError
    * @param   p_device_error_string  The error string corresponding to the ErrorCode
    * @return  None; instead check class Field "ErrState"
    */
    void Get_device_error_string(TDevError error_code, char *p_device_error_string);

    void Get_total_SIG_rate( TRangeResults *p_ranging_results,
            TFP1616 *p_total_SIG_rate_mcps);

    TFP1616 Get_total_xtalk_rate( TRangeResults *p_ranging_results);
            
    /**
     * @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 ...)
     *
     * @note This function Access to the device
     *
     * 
     * @return   uint32_t   Max measurement time in microseconds.
     *                                   Valid values are:
     *                                   >= 17000 microsecs when wraparound enabled
     *                                   >= 12000 microsecs when wraparound disabled
     *   						Also check class Field "ErrState"                            
     */
    uint32_t Get_Measure_Time_Budget_us();

    /**
     * @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 ...)
     *
     * @note This function Access to the device
     *
     * 
     * @param Measure_Time_Budget_us  Max measurement time in
     * microseconds.
     *                                   Valid values are:
     *                                   >= 17000 microsecs when wraparound enabled
     *                                   >= 12000 microsecs when wraparound disabled
     * @return  None; instead check class Field "ErrState"         
     * @return  VL53L0X_ERROR_INVALID_PARAMS   This error is returned if
     MeasurementTimingBudgetMicroSeconds out of range
     */
    void Set_Measure_Time_Budget_us( uint32_t Measure_Time_Budget_us);

    /**
     * @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 limit_check_id.
     *
     * @note This function Access to the device
     *
     * 
     * @param   limit_check_id                  Limit Check ID
     *  (0<= limit_check_id < VL53L0X_GetNumberOfLimitCheck() ).
     * @return   uint8_t      Check limit enable value.
     *  if 1 the check limit
     *        corresponding to limit_check_id is Enabled
     *  if 0 the check limit
     *        corresponding to limit_check_id is disabled
     * @return  also check class Field "ErrState"         
     * @return  VL53L0X_ERROR_INVALID_PARAMS   This error is returned when limit_check_id value is out of range.
     */
    uint8_t Get_limit_chk_en( uint16_t limit_check_id);

    /**
     * @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 limit_check_id.
     *
     * @note This function doesn't Access to the device
     * 
     * @param   limit_check_id         Limit Check ID
     *  (0<= limit_check_id < VL53L0X_GetNumberOfLimitCheck() ).
     * @param   limit_chk_en           if 1 the check limit corresponding to limit_check_id is Enabled
     *                                 if 0 the check limit corresponding to limit_check_id is disabled
     * @return  None; instead check class Field "ErrState"         
     * @return  VL53L0X_ERROR_INVALID_PARAMS   This error is returned
     *  when limit_check_id value is out of range.
     */
    void Set_limit_chk_en( uint16_t limit_check_id, uint8_t limit_chk_en);

    /**
     * @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 limit_check_id.
     *
     * @note This function Access to the device
     *
     * 
     * @param   limit_check_id                  Limit Check ID
     *  (0<= limit_check_id < VL53L0X_GetNumberOfLimitCheck() ).
     * @return  TFP1616         Limit  check Value for a given limit_check_id.
     * @return  Also check class Field "ErrState";returned VL53L0X_ERROR_INVALID_PARAMS
     *          when limit_check_id value is out of range.  
     */
    TFP1616 Get_limit_chk_val( uint16_t limit_check_id);

    /**
     * @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 limit_check_id.
     *
     * @note This function Access to the device
     * 
     * @param   limit_check_id                  Limit Check ID
     *  (0<= limit_check_id < VL53L0X_GetNumberOfLimitCheck() ).
     * @param   limit_chk_val               Limit check Value for a given
     * limit_check_id
     * @return  None; instead check class Field "ErrState"         
     * @return  VL53L0X_ERROR_INVALID_PARAMS   This error is returned when either
     *  limit_check_id or LimitCheckValue value is out of range.
     */
    void Set_limit_chk_val( uint16_t limit_check_id, TFP1616 limit_chk_val);

    /**
     * @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 ranging before.
     * The value reported is linked to the limit check identified with the
     * limit_check_id.
     *
     * @note This function Access to the device
     * 
     * @param   limit_check_id                  Limit Check ID
     *  (0<= limit_check_id < VL53L0X_GetNumberOfLimitCheck() ).
     * @param   p_limit_check_current            Pointer to current Value for a
     * given limit_check_id.
     * @return  None; instead check class Field "ErrState"         
     * @return  VL53L0X_ERROR_INVALID_PARAMS   This error is returned when
     * limit_check_id value is out of range.
     */
    void Get_limit_check_current( uint16_t limit_check_id, 
                                  TFP1616 *p_limit_check_current);

    /**
     * @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 limit_check_id.
     *
     * @note This function doesn't Access to the device
     * 
     * @param   limit_check_id                  Limit Check ID
     (0<= limit_check_id < VL53L0X_GetNumberOfLimitCheck() ).
     * @param   p_limit_check_status             Pointer to the
     Limit Check Status of the given check limit.
     * LimitCheckStatus :
     * 0 the check is not fail
     * 1 the check if fail or not enabled
     *
     * @return  None; instead check class Field "ErrState"         
     * @return  VL53L0X_ERROR_INVALID_PARAMS   This error is
     returned when limit_check_id value is out of range.             
     */
    void Get_limit_check_status(uint16_t limit_check_id, uint8_t *p_limit_check_status);

    /**
     * Get continuous mode Inter-Measurement period in milliseconds
     *
     * @par Function Description
     * When trying to set too short time return  INVALID_PARAMS minimal value
     *
     * @note This function Access to the device
     * 
     * @param   p_measure_period_ms  Pointer to programmed
     *  Inter-Measurement Period in milliseconds.
     * @return  None; instead check class Field "ErrState"                               
     */
    void Get_measure_period_ms(uint32_t *p_measure_period_ms);

    /**
     * Program continuous mode Inter-Measurement period in milliseconds
     *
     * @par Function Description
     * When trying to set too short time return  INVALID_PARAMS minimal value
     *
     * @note This function Access to the device
     * 
     * @param   measure_period_ms   Inter-Measurement Period in ms.
     * @return  None; instead check class Field "ErrState"                         
     */
    void Set_measure_period_ms( uint32_t measure_period_ms );

    /**
     * @brief Do an hard reset or soft reset (depending on implementation) of the
     * device \nAfter call of this function, device must be in same state as right
     * after a power-up sequence.This function will change the VL53L0X_State to
     * VL53L0X_STATE_POWERDOWN.
     *
     * @note This function Access to the device
     * 
     * @return  None; instead check class Field "ErrState" 
     */
    void Reset_device();

    /**
     * @brief  Get setup of Wrap around Check
     *
     * @par Function Description
     * This function get the wrapAround check enable parameters
     *
     * @note This function Access to the device
     * 
     * @return  uint8_t  Wrap around Check state 0=disabled or 1 = enabled
     * @return  None  	   Also check class Field "ErrState"   
     */
    uint8_t Get_Wrap_Around_Chk_En();

    /**
     * @brief  Enable (or disable) Wrap around Check
     *
     * @note This function Access to the device
     *
     * 
     * @param   wrap_around_Chk_En  Wrap around Check to be set
     *                                 0=disabled, other = enabled
     * @return  None; instead check class Field "ErrState"  
     */
    void Set_wrap_around_Chk_En( uint8_t wrap_around_Chk_En);

    /**
     * @brief Sets the VCSEL pulse period.
     *
     * @par Function Description
     * This function retrieves the VCSEL pulse period for the given period type.
     *
     * @note This function Accesses the device
     * 
     * @param   Vcsel_Range_Phase	      VCSEL period identifier (pre-range|final).
     * @param   vcsel_PPeriod          VCSEL period value
     * @return  None; instead check class Field "ErrState"        
     * @return  VL53L0X_ERROR_INVALID_PARAMS  Error VcselPeriodType parameter not
     *                                       supported.
     */
    void Set_vcsel_PPeriod( VL53L0X_Range_Phase Vcsel_Range_Phase, 
                                uint8_t vcsel_PPeriod);

    /**
     * @brief Set low and high Interrupt thresholds for a given mode
     * (ranging, ALS, ...) for a given device
     *
     * @par Function Description
     * Set low and high Interrupt thresholds for a given mode (ranging, ALS, ...)
     * for a given device
     *
     * @note This function Access to the device
     *
     * @note DeviceMode is ignored for the current device
     * 
     * @param   device_mode       Device Mode for which change thresholds
     * @param   threshold_low     Low threshold (mm, lux ..., depending on the mode)
     * @param   threshold_high    High threshold (mm, lux ..., depending on the mode)
     * @return  None; instead check class Field "ErrState"
     */
    void Set_interrupt_thresholds( VL53L0X_DeviceModes device_mode, 
           TFP1616 threshold_low,  TFP1616 threshold_high);

    /**
     * @brief  Get high and low Interrupt thresholds for a given mode
     *  (ranging, ALS, ...) for a given device
     *
     * @par Function Description
     * Get high and low Interrupt thresholds for a given mode (ranging, ALS, ...)
     * for a given device
     *
     * @note This function Access to the device
     *
     * @note DeviceMode is ignored for the current device
     * 
     * @param   device_mode       Device Mode from which read thresholds
     * @param   p_threshold_low    Low threshold (mm, lux ..., depending on the mode)
     * @param   p_threshold_high   High threshold (mm, lux ..., depending on the mode)
     * @return  None; instead check class Field "ErrState"
     */
    void Get_interrupt_thresholds( VL53L0X_DeviceModes device_mode, 
    		TFP1616 *p_threshold_low, TFP1616 *p_threshold_high);

    /**
     * @brief Gets the (on/off) state of all sequence steps.
     *
     * @par Function Description
     * This function retrieves the state of all sequence step in the scheduler.
     *
     * @note This function Accesses the device
     * 
     * @return  VL53L0X_Sequence_Steps_t      Struct containing result.
     *                                          Also check class Field "ErrState"        
     */
    VL53L0X_Sequence_Steps_t Get_sequence_step_enables();

    /**
     * @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   sequence_step_id	         Sequence step identifier.
     * @param   sequence_step_enabled          Demanded state {0=Off,1=On}
     *                                       is enabled.
     * @return  None; instead check class Field "ErrState"        
     * @return  VL53L0X_ERROR_INVALID_PARAMS  Error SequenceStepId parameter not
     *                                       supported.   
     */
    void Set_sequence_step_enable(VL53L0X_SequenceStepId sequence_step_id, 
                                  uint8_t sequence_step_enabled);

    /**
     * @brief  Gets the fraction enable parameter indicating the resolution of
     * range measurements.
     *
     * @par Function Description
     * Gets the fraction enable state, which translates to the resolution of
     * range measurements as follows :Enabled:=0.25mm resolution,
     * Not Enabled:=1mm resolution.
     *
     * @note This function Accesses the device
     * 
     * @param   p_enabled           Output Parameter reporting the fraction enable state.
     *
     * @return  None; instead check class Field "ErrState"                         
     */
    void Get_fraction_enable( uint8_t *p_enabled);

    /**
     * @brief  Sets the resolution of range measurements.
     * @par Function Description
     * Set resolution of range measurements to either 0.25mm if
     * fraction enabled or 1mm if not enabled.
     *
     * @note This function Accesses the device
     * 
     * @param   enable            Enable high resolution
     *
     * @return  None; instead check class Field "ErrState"              
     */
    void Set_range_fraction_enable(  uint8_t enable);

    /**
    * @brief Return the VL53L0X Device Implementation Version
    *
    * @note This function doesn't access to the device
    *
    * @param   p_version              Pointer to current Device Implementation Version
    * @return  None; instead check class Field "ErrState" 
    */
    void Get_version(VL53L0X_Version_t *p_version);

    /**
     * @brief Reads the Product Revision for a for given Device
     * This function can be used to distinguish cut1.0 from cut1.1.
     *
     * @note This function Access to the device
     * 
     * @param   p_product_revision_major  Pointer to Product Revision Major
     * for a given Device
     * @param   p_product_revision_minor  Pointer to Product Revision Minor
     * for a given Device
     * @return  None; instead check class Field "ErrState"  
     */
    void Get_product_revision(  uint8_t *p_product_revision_major, 
            uint8_t *p_product_revision_minor);

    /**
     * @brief  Retrieve current device parameters
     * @par Function Description
     * Get actual parameters of the device
     * @li Then start ranging operation.
     *
     * @note This function Access to the device
     * 
     * @return   VL53L0X_DeviceParams_t     Current device parameters.
     * 					    Also check class Field "ErrState" 
     */
    VL53L0X_DeviceParams_t Get_device_parameters();

    /**
     * @brief Return the Device Specification Version used for the current
     * implementation.
     *
     * @note This function doesn't access to the device
     *
     * @param   p_Device_spec_version       Pointer to current Device Specification Version
     * @return  None; instead check class Field "ErrState"    
     */
    void Get_Device_spec_version(VL53L0X_Version_t  *p_Device_spec_version);

    /**
     * @brief Reads the internal state of the Device for a given Device
     *
     * @note This function doesn't access to the device
     * 
     * @param   p_Device_state             Pointer to current state of the Device for a
     * given Device
     * @return  None; instead check class Field "ErrState" 
     */
    void Get_Device_state(VL53L0X_State *p_Device_state);

	/* New Strategy, Moving to a global variable to track error states: */
	VL53L0X_Error  ErrState;
	
    VL53L0X_State Current_State;  /*!< Current state of this device; use Set_Current_State to change it  */

    /*** End High level API ***/
private:
    void Wait_read_strobe();

    void Check_and_load_interrupt_settings( uint8_t start_not_stopflag);

    /* api_core.h functions */
    void Get_info_from_device( uint8_t option);

    uint32_t Decode_timeout(uint16_t encoded_timeout);

    uint32_t Calc_timeout_us(uint16_t timeout_period_mclks,
                                     uint8_t vcsel_period_pclks);

    void Poll_Measure_Completion(); // was Measurement_poll_for_completion

    void Load_tuning_settings( uint8_t *p_tuning_setting_buffer );

    void Get_Device_range_status( uint8_t device_range_status,
            TFP1616 signal_rate, uint16_t effective_SPAD_rtn_count,
            TRangeResults *p_ranging_results,
            uint8_t *p_Device_range_status);

    void Calc_sigma_estimate(
            TRangeResults *p_ranging_results,
            TFP1616 *p_sigma_estimate, uint32_t *p_dmax_mm);
            
    uint32_t Calc_timeout_mclks(uint32_t timeout_period_us,
                                        uint8_t vcsel_period_pclks);
    
    void Calc_dmax( TFP1616 total_SIG_rate_mcps,
        TFP1616 total_corr_SIG_rate_mcps,
        TFP1616 pw_mult, uint32_t sigma_estimate_p1,
        TFP1616 sigma_estimate_p2,  uint32_t peak_vcsel_duration_us,
        uint32_t *pd_max_mm);
        
    uint16_t Encode_timeout(uint32_t timeout_macro_clks);

    /* api_calibration.h functions */
    void VL53L0X_Apply_Offset_Cal();
    
    void Perf_vhv_calibration( uint8_t *p_vhv_settings, 
            const uint8_t get_data_enable,  const uint8_t restore_config);
            
    void Perf_single_Ref_calibration( uint8_t vhv_init_byte );
    
    void Ref_calibration_io( uint8_t read_not_write,
            uint8_t vhv_settings, uint8_t phase_cal,
            uint8_t *p_vhv_settings, uint8_t *p_phase_cal,
            const uint8_t vhv_enable, const uint8_t phase_enable);
            
    void Perf_phase_calibration( uint8_t *p_phase_cal, const uint8_t get_data_enable,
            const uint8_t restore_config);
            
    void Enable_Ref_SPADS(uint8_t aperture_SPADS, uint8_t good_SPAD_array[],
            uint8_t SPAD_array[], uint32_t size, uint32_t start,
            uint32_t offset, uint32_t SPAD_count,  uint32_t *p_last_SPAD);
                                   
    void Get_Next_Good_SPAD(uint8_t good_SPAD_array[], uint32_t size,
                            uint32_t curr, int32_t *p_next);
                            
    void Enable_SPAD_bit( uint8_t SPAD_array[], uint32_t size, uint32_t SPAD_index);
                                    
    void Get_Ref_SPAD_map( uint8_t *p_Ref_SPAD_array );
    
    uint16_t Get_Perf_Ref_SIG_measurement();
    

    /* Read function of the ID device */
    virtual int read_id(uint8_t *id);
    
    void Wait_Measurement_Ready();

    void Wait_Stop_Completed();

    /**
     * @brief execute delay in all polling API call
     *
     * A typical multi-thread or RTOs implementation is to sleep the task for some 
     * 5ms (with 100Hz max rate faster polling is not needed)
     * if nothing specific is need you can define it as an empty/void macro
     * @code
     * #define VL53L0X_PollingDelay(...) (void)0
     * @endcode
     * 
     * @return  None; instead check class Field "ErrState"    
     */
    void Polling_delay();   /* usually best implemented as a real function */

    ///////////////////////////////////////////////////////////////////////////////////////////////////////
    //Added functions                                                                                    //
    ///////////////////////////////////////////////////////////////////////////////////////////////////////

    /**
     * @brief  Cycle Power to Device
     *
     * @return ErrState - ErrState 0 = ok, 1 = error
     */
    int32_t Cycle_power(void);

    void count_enabled_SPADS(uint8_t SPAD_array[],  uint32_t byte_count, 
       uint32_t max_SPADS, uint32_t *p_total_SPADS_enabled, uint8_t *p_is_aperture);

        /**
     * @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   sequence_step_id               Sequence step identifier.
     * @param   p_sequence_steps_string         Pointer to Info string
     *
     * @return  None; instead check class Field "ErrState"        
     */
    void Get_sequence_steps_info(VL53L0X_SequenceStepId sequence_step_id,
            char *p_sequence_steps_string);

    /**
    * @brief Get the frequency of the timer used for ranging results time stamps
    *
    * @param[out] p_timer_freq_hz : pointer for timer frequency
    *
    * @return ErrState : 0 = ok, 1 = error
    */
    int32_t Get_timer_frequency(int32_t *p_timer_freq_hz);

    /**
    * @brief Get the timer value in units of timer_freq_hz (see Get_timestamp_frequency())
    *
    * @param[out] p_timer_count : pointer for timer count value
    *
    * @return ErrState : 0 = ok, 1 = error
    */
    int32_t Get_timer_value(int32_t *p_timer_count);

    /**
    * @brief Configure ranging interrupt reported to system
    *
    * @note This function is not Implemented
    * 
    * @param   interrupt_mask         Mask of interrupt to Enable/disable
    *  (0:interrupt disabled or 1: interrupt enabled)
    * @return  VL53L0X_ERROR_NOT_IMPLEMENTED   Not implemented
    */
    void Enable_interrupt_mask(uint32_t interrupt_mask);

    /**
     * @brief  Get Dmax Calibration Parameters for a given device
     *
     * @note This function Access to the device
     * 
     * @param   p_range_milli_meter        Pointer to Calibration Distance
     * @param   p_SIG_rate_rtn_MHz   Pointer to Signal rate return
     * @return  None; instead check class Field "ErrState"   
     */
    void Get_dmax_cal_parameters(uint16_t *p_range_milli_meter,
             TFP1616 *p_SIG_rate_rtn_MHz);

    /**
    * @brief   Set Dmax Calibration Parameters for a given device
    * When one of the parameter is zero, this function will get parameter
    * from NVM.
    * @note This function doesn't Access to the device
    * 
    * @param   range_milli_meter        Calibration Distance
    * @param   signal_rate_rtn_MHz   Signal rate return read at CalDistance
    * @return  None; instead check class Field "ErrState"  
     
    */
    void Get_dmax_cal_parameters(uint16_t range_milli_meter, 
            TFP1616 signal_rate_rtn_MHz);

    /**
    * @brief Retrieve the measurements from device for a given setup
    *
    * @par Function Description
    * Get data from last successful Histogram measurement
    * @warning USER should take care about  @a VL53L0X_GetNumberOfROIZones()
    * before get data.
    * Device will fill a NumberOfROIZones times the corresponding data structure
    * used in the measurement function.
    *
    * @note This function is not Implemented
    * 
    * @param   p_histogram_measurement_data   Pointer to the histogram data structure.
    * @return  VL53L0X_ERROR_NOT_IMPLEMENTED   Not implemented
    */
    void Get_histogram_measurement_data(
            VL53L0X_HistogramMeasurementData_t *p_histogram_measurement_data);

    /**
    * @brief  Get current new device mode
    * @par Function Description
    * Get current Histogram mode of a Device
    *
    * @note This function doesn't Access to the device
    * 
    * @param   p_histogram_mode        Pointer to current Histogram Mode value
    *                                Valid values are:
    *                                VL53L0X_HISTOGRAMMODE_DISABLED
    *                                VL53L0X_DEVICEMODE_SINGLE_HISTOGRAM
    *                                VL53L0X_HISTOGRAMMODE_REFERENCE_ONLY
    *                                VL53L0X_HISTOGRAMMODE_RETURN_ONLY
    *                                VL53L0X_HISTOGRAMMODE_BOTH
    * @return  None; instead check class Field "ErrState" 
    */
    void Get_histogram_mode(
            VL53L0X_HistogramModes *p_histogram_mode);

    /**
     * @brief  Set a new Histogram mode
     * @par Function Description
     * Set device to a new Histogram mode
     *
     * @note This function doesn't Access to the device
     * 
     * @param   histogram_mode         New device mode to apply
     *                                Valid values are:
     *                                VL53L0X_HISTOGRAMMODE_DISABLED
     *                                VL53L0X_DEVICEMODE_SINGLE_HISTOGRAM
     *                                VL53L0X_HISTOGRAMMODE_REFERENCE_ONLY
     *                                VL53L0X_HISTOGRAMMODE_RETURN_ONLY
     *                                VL53L0X_HISTOGRAMMODE_BOTH
     *
     * @return  None; instead check class Field "ErrState"               
     * @return  VL53L0X_ERROR_MODE_NOT_SUPPORTED     This error occurs when
     * HistogramMode is not in the supported list
     */
    void Set_histogram_mode(
            VL53L0X_HistogramModes histogram_mode);

    /**
     * @brief Get the linearity corrective gain
     *
     * @par Function Description
     * Should only be used after a successful call to @a VL53L0X_DataInit to backup
     * device NVM value
     *
     * @note This function Access to the device
     * 
     * @param   p_linearity_corrective_gain           Pointer to the linearity
     * corrective gain in x1000
     * if value is 1000 then no modification is applied.
     * @return  None; instead check class Field "ErrState"    
     */
    void Get_linearity_corrective_gain(
            uint16_t *p_linearity_corrective_gain);

    /**
     * Set the linearity corrective gain
     *
     * @note This function Access to the device
     * 
     * @param   linearity_corrective_gain            Linearity corrective
     * gain in x1000
     * if value is 1000 then no modification is applied.
     * @return  None; instead check class Field "ErrState"    
     */
    void Set_linearity_corrective_gain(
            int16_t linearity_corrective_gain);

    /**
     * @brief Get the Maximum number of ROI Zones managed by the Device
     *
     * @par Function Description
     * Get Maximum number of ROI Zones managed by the Device.
     *
     * @note This function doesn't Access to the device
     * 
     * @param   p_max_number_of_roi_zones   Pointer to the Maximum Number
     *  of ROI Zones value.
     * @return  None; instead check class Field "ErrState"  
     */
    void Get_max_number_of_roi_zones(
            uint8_t *p_max_number_of_roi_zones);

    /**
     * @brief Retrieve the Reference Signal after a measurements
     *
     * @par Function Description
     * Get Reference Signal from last successful Ranging measurement
     * This function return a valid value after that you call the
     * @a VL53L0X_GetRangingMeasurementData().
     *
     * @note This function Access to the device
     * 
     * @param   p_measurement_Ref_signal    Pointer to the Ref Signal to fill up.
     * @return  None; instead check class Field "ErrState" 
     */
    void Get_Measurement_Ref_signal(
            TFP1616 *p_measurement_Ref_signal);

    /**
     * @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
     *
     * @note This function doesn't Access to the device
     *
     * @param   p_number_of_limit_check           Pointer to the number of check limit.
     * @return  None; instead check class Field "ErrState" 
     */
    void Get_number_of_limit_check(
                       uint16_t *p_number_of_limit_check);

    /**
     * @brief Get the number of ROI Zones managed by the Device
     *
     * @par Function Description
     * Get number of ROI Zones managed by the Device
     * USER should take care about  @a VL53L0X_GetNumberOfROIZones()
     * before get data after a perform measurement.
     * Device will fill a NumberOfROIZones times the corresponding data
     * structure used in the measurement function.
     *
     * @note This function doesn't Access to the device
     *
     * 
     * @param   p_number_of_roi_zones     Pointer to the Number of ROI Zones value.
     * @return  None; instead check class Field "ErrState" 
     */
    void Get_number_of_roi_zones(
            uint8_t *p_number_of_roi_zones);

    /**
     * @brief Set the number of ROI Zones to be used for a specific Device
     *
     * @par Function Description
     * Set the number of ROI Zones to be used for a specific Device.
     * The programmed value should be less than the max number of ROI Zones given
     * with @a VL53L0X_GetMaxNumberOfROIZones().
     * This version of API manages only one zone.
     * 
     * @param   number_of_roi_zones      Number of ROI Zones to be used 
     * @return  None; instead check class Field "ErrState"         
     * @return  VL53L0X_ERROR_INVALID_PARAMS   This error is returned if NumberOfROIZones != 1
     */
    void Set_number_of_roi_zones(  uint8_t number_of_roi_zones);

    /**
     * @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   p_number_of_sequence_steps       Out parameter reporting the number of
     *                                       sequence steps.
     * @return  None; instead check class Field "ErrState"        
     */
    void Get_number_of_sequence_steps( uint8_t *p_number_of_sequence_steps);
    /**
     * @brief Get the power mode for a given Device
     *
     * @note This function Access to the device
     * 
     * @param   p_power_mode            Pointer to the current value of the power
     * mode. see ::VL53L0X_PowerModes
     *                                Valid values are:
     *                                VL53L0X_POWERMODE_STANDBY_LEVEL1,
     *                                VL53L0X_POWERMODE_IDLE_LEVEL1
     * @return  None; instead check class Field "ErrState"
     */
    void Get_power_mode( VL53L0X_PowerModes *p_power_mode);

    /**
     * @brief Set the power mode for a given Device
     * The power mode can be Standby or Idle. Different level of both Standby and
     * Idle can exists.
     * This function should not be used when device is in Ranging state.
     *
     * @note This function Access to the device
     * 
     * @param   power_mode             The value of the power mode to set.
     * see ::VL53L0X_PowerModes
     *                                Valid values are:
     *                                VL53L0X_POWERMODE_STANDBY_LEVEL1,
     *                                VL53L0X_POWERMODE_IDLE_LEVEL1
     * @return  None; instead check class Field "ErrState"              
     * @return  VL53L0X_ERROR_MODE_NOT_SUPPORTED    This error occurs when PowerMode
     * is not in the supported list
     */
    void Set_power_mode(VL53L0X_PowerModes power_mode);

    /**
     * @brief Retrieves SPAD configuration
     *
     * @par Function Description
     * This function retrieves the current number of applied reference SPADS
     * and also their type : Aperture or Non-Aperture.
     *
     * @note This function Access to the device
     * 
     * @param   p_SPAD_count                 Number ref SPAD Count
     * @param   p_is_aperture_SPADS              Reports if SPADS are of type
     *                                       aperture or non-aperture.
     *                                       1:=aperture, 0:=Non-Aperture
     * @return  None; instead check class Field "ErrState"        
     * @return  VL53L0X_ERROR_REF_SPAD_INIT   Error in the in the reference
     *                                       SPAD configuration.
     */
    void wrapped_Get_Reference_SPADS(
            uint32_t *p_SPAD_count, uint8_t *p_is_aperture_SPADS);

    /**
     * @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   sequence_step_id         Sequence step identifier.
     * @param   p_sequence_step_enabled   Out parameter reporting if the sequence step
     *                                 is enabled {0=Off,1=On}.
     * @return  None; instead check class Field "ErrState"        
     * @return  VL53L0X_ERROR_INVALID_PARAMS  Error SequenceStepId parameter not
     *                                        supported.
     */
    void Get_sequence_step_enable(
            VL53L0X_SequenceStepId sequence_step_id, uint8_t *p_sequence_step_enabled);


    /**
     * @brief Gets the timeout of a requested sequence step.
     *
     * @par Function Description
     * This function retrieves the timeout of a requested sequence step.
     *
     * @note This function Accesses the device
     *
     * @param   sequence_step_id               Sequence step identifier.
     * @param   p_time_out_milli_secs            Timeout value.
     * @return  None; instead check class Field "ErrState"        
     * @return  VL53L0X_ERROR_INVALID_PARAMS  Error SequenceStepId parameter not
     *                                       supported.
     */
    void Get_Sequence_Step_Timeout(VL53L0X_SequenceStepId sequence_step_id,
                                            uint32_t *p_time_out_micro_secs);

    /**
     * @brief Sets the timeout of a requested sequence step.
     *
     * @par Function Description
     * This function sets the timeout of a requested sequence step.
     *
     * @note This function Accesses the device
     * 
     * @param   sequence_step_id               Sequence step identifier.
     * @param   time_out_milli_secs             Demanded timeout
     * @return  None; instead check class Field "ErrState"        
     * @return  VL53L0X_ERROR_INVALID_PARAMS  Error SequenceStepId parameter not
     *                                       supported.
     */
    void Set_Sequence_Step_Timeout(VL53L0X_SequenceStepId sequence_step_id,
                                            uint32_t timeout_micro_secs);

    /**
    * @brief  Get the current SPAD Ambient Damper Factor value
    *
    * @par Function Description
    * This function get the SPAD Ambient Damper Factor value
    *
    * @note This function Access to the device
    * 
    * @param   p_SPAD_ambient_damper_factor      Pointer to programmed SPAD Ambient
    * Damper Factor value
    * @return  None; instead check class Field "ErrState"         
    */
    void Get_SPAD_ambient_damper_factor(
            uint16_t *p_SPAD_ambient_damper_factor);
    /**
    * @brief  Set the SPAD Ambient Damper Factor value
    *
    * @par Function Description
    * This function set the SPAD Ambient Damper Factor value
    *
    * @note This function Access to the device
    * 
    * @param   SPAD_ambient_damper_factor       SPAD Ambient Damper Factor value
    * @return  None; instead check class Field "ErrState"         
    */
    void Set_SPAD_ambient_damper_factor(
            uint16_t SPAD_ambient_damper_factor);

    /**
     * @brief  Get the current SPAD Ambient Damper Threshold value
     *
     * @par Function Description
     * This function get the SPAD Ambient Damper Threshold value
     *
     * @note This function Access to the device
     * 
     * @param   p_SPAD_ambient_damper_threshold   Pointer to programmed
     *                                        SPAD Ambient Damper Threshold value
     * @return  None; instead check class Field "ErrState"         
     */
    void Get_SPAD_ambient_damper_threshold(
            uint16_t *p_SPAD_ambient_damper_threshold);

    /**
     * @brief  Set the SPAD Ambient Damper Threshold value
     *
     * @par Function Description
     * This function set the SPAD Ambient Damper Threshold value
     *
     * @note This function Access to the device
     * 
     * @param   SPAD_ambient_damper_threshold    SPAD Ambient Damper Threshold value
     * @return  None; instead check class Field "ErrState"         
     */
    void Set_SPAD_ambient_damper_threshold(
            uint16_t SPAD_ambient_damper_threshold);

    /**
     * @brief Get the maximal distance for actual setup
     * @par Function Description
     * Device must be initialized through @a VL53L0X_SetParameters() prior calling
     * this function.
     *
     * Any range value more than the value returned is to be considered as
     * "no target detected" or
     * "no target in detectable range"\n
     * @warning The maximal distance depends on the setup
     *
     * @note This function is not Implemented
     * 
     * @param   p_upper_limit_milli_meter   The maximal range limit for actual setup
     * (in millimeter)
     * @return  VL53L0X_ERROR_NOT_IMPLEMENTED        Not implemented
     */
    void Get_upper_limit_milli_meter(
            uint16_t *p_upper_limit_milli_meter);

    /**
    * @brief Get the tuning settings pointer and the internal external switch
    * value.
    *
    * This function is used to get the Tuning settings buffer pointer and the
    * value.
    * of the switch to select either external or internal tuning settings.
    *
    * @note This function Access to the device
    * 
    * @param   pp_tuning_setting_buffer      Pointer to tuning settings buffer.
    * @param   p_use_internal_tuning_settings Pointer to store Use internal tuning
    *                                     settings value.
    * @return  None; instead check class Field "ErrState"      
    */
    void Get_tuning_setting_buffer( uint8_t **pp_tuning_setting_buffer, 
                  uint8_t *p_use_internal_tuning_settings);

    /**
     * @brief Set the tuning settings pointer
     *
     * This function is used to specify the Tuning settings buffer to be used
     * for a given device. The buffer contains all the necessary data to permit
     * the API to write tuning settings.
     * This function permit to force the usage of either external or internal
     * tuning settings.
     *
     * @note This function Access to the device
     * 
     * @param   p_tuning_setting_buffer            Pointer to tuning settings buffer.
     * @param   use_internal_tuning_settings       Use internal tuning settings value.
     * @return  None; instead check class Field "ErrState" 
     */
    void Set_tuning_setting_buffer(  uint8_t *p_tuning_setting_buffer, 
            uint8_t use_internal_tuning_settings);

    /**
     * @defgroup VL53L0X_registerAccess_group Device Register Access Functions
     * @brief    Device Register Access Functions
     *  @{
     */

    /**
     * Lock comms interface to serialize all commands to a shared I2C interface for a specific device
     * 
     * @return  None; instead check class Field "ErrState"    
     */
    void VL53L0X_lock_sequence_access();

    /**
     * Unlock comms interface to serialize all commands to a shared I2C interface for a specific device
     * 
     * @return  None; instead check class Field "ErrState"    
     */
    void VL53L0X_unlock_sequence_access();

    /**
     * @brief  Prepare device for operation
     * @par Function Description
     * Update device with provided parameters
     * @li Then start ranging operation.
     *
     * @note This function Access to the device
     * 
     * @param   pDeviceParameters     Pointer to store current device parameters.
     * @return  None; instead check class Field "ErrState" 
     */
    void VL53L0x_set_device_parameters(
            const VL53L0X_DeviceParams_t *pDeviceParameters);

    /**
     * Set Group parameter Hold state
     *
     * @par Function Description
     * Set or remove device internal group parameter hold
     *
     * @note This function is not Implemented
     * 
     * @param   group_param_hold   Group parameter Hold state to be set (on/off)
     * @return  VL53L0X_ERROR_NOT_IMPLEMENTED        Not implemented
     */
    void Set_group_param_hold(uint8_t group_param_hold);

    /**
     * @brief Wait for device ready for a new measurement command.
     * Blocking function.
     *
     * @note This function is not Implemented
     * 
     * @param   max_loop    Max Number of polling loop (timeout).
     * @return  VL53L0X_ERROR_NOT_IMPLEMENTED   Not implemented
     */
    void Wait_device_ready_for_new_measurement( uint32_t max_loop);

private:
/******************************************************************************/
/****************** Write and read functions from I2C *************************/
/******************************************************************************/
    /**
     * Thread safe Update (read/modify/write) single byte register
     *
     * Final_reg = (Initial_reg & and_mask) | or_mask
     *
     * 
     * @param   index      The register index
     * @param   and_mask    8 bit and data
     * @param   or_mask     8 bit or data
     * @return  None; instead check class Field "ErrState"    
     */
    void Register_BitMask(uint8_t index, uint8_t and_mask, uint8_t or_mask);

    /* Write and read functions from I2C */
    /**
     * Write single byte register
     * 
     * @param   index     The register index
     * @param   data      8 bit register data
     * @return  None; instead check class Field "ErrState"    
     */
    void Write_Byte( uint8_t index, uint8_t data);

    /**
     * Write word register
     * 
     * @param   index     The register index
     * @param   data      16 bit register data
     * @return  None; instead check class Field "ErrState"    
     */
    void Write_Word( uint8_t index, uint16_t data);
    /**
     * Write double word (4 byte) register
     * 
     * @param   index     The register index
     * @param   data      32 bit register data
     * @return  None; instead check class Field "ErrState"    
     */
    void Write_DWord( uint8_t index, uint32_t data);

    /**
     * Read single byte register
     * 
     * @param   index     The register index
     * @return  uint8_t  Returned 8 bit data; also check class Field "ErrState"    
     */
	uint8_t Read_Byte(uint8_t index);
	
    /**
     * Read word (2byte) register
     * 
     * @param   index     The register index
     * @return  uint16_t  Returned 16 bit data; also check class Field "ErrState"    
     */
    uint16_t Read_Word( uint8_t index);
    /**
     * Read dword (4byte) register
     * 
     * @param   index     The register index
     * @return  uint32_t  Returned 32 bit data; also check class Field "ErrState"    
     */
    uint32_t Read_DWord( uint8_t index);
    
    /**
     * @brief  Writes a buffer towards the I2C peripheral device.
     * 
	 * @param  RegisterAddr specifies the internal address register
	 * @param  p_data pointer to the byte-array data to send
	 *         where to start writing to (must be correctly masked).
	 * @param  NumByteToWrite number of bytes to be written.
	 * @retval VL53L0X_OK  if  ok,
	 * @retval VL53L0X_ERROR_CONTROL_INTERFACE  if  an  I2C error has occured, or
	 * @retval VL53L0X_ERROR_I2C_BUF_OVERFLOW on temporary buffer overflow (i.e. NumByteToWrite was too high)
	 * @note   On some devices if NumByteToWrite is greater
	 *         than one, the RegisterAddr must be masked correctly!
     */
    void I2c_Write(uint8_t RegisterAddr, uint8_t *p_data, uint16_t NumByteToWrite);

    /**
     * @brief  Reads a buffer from the I2C peripheral device.
     * 
	 * @param  RegisterAddr specifies the internal address register
	 * @param  p_data pointer to the byte-array data to receive
	 *         where to start writing to (must be correctly masked).
	 * @param  NumByteToRead number of bytes to be read; maximum VL53L0X_MAX_I2C_XFER_SIZE
     * @retval 0 if ok,
     * @retval -1 if an I2C error has occured
     * @note   On some devices if NumByteToRead is greater
     *         than one, the RegisterAddr must be masked correctly!
     */
    void I2c_Read(uint8_t RegisterAddr, uint8_t *p_data, uint16_t NumByteToRead);

    /* IO Device */
    I2C *_dev_i2c;

    /*!< i2c device address user specific field */
    uint8_t   I2cDevAddr;     

private:
    uint8_t Is_ApertureSPAD(uint32_t SPAD_index);
    
    void Reverse_bytes(uint8_t *data, uint32_t size);

    void Range_meas_int_continuous_mode(void (*fptr)(void));

    uint32_t ISQRT(uint32_t num);

    uint32_t Quadrature_sum(uint32_t a, uint32_t b);
    
    void Set_Current_State( VL53L0X_State NewState )
    {  if (ErrState == VL53L0X_OK) { Current_State = NewState; }
    	  else { Current_State = VL53L0X_STATE_ERROR; }
	} // end of Set_Current_State
	
	// NB: it seems that the state SequenceConfig is only written to never read from ;)
    void Set_SequenceConfig ( uint8_t NewSequenceConfig ) 
    { Write_Byte(REG_SYSTEM_SEQUENCE_CONFIG, NewSequenceConfig);
      if (ErrState == VL53L0X_OK) { SequenceConfig = NewSequenceConfig; } } 

private:
    static const unsigned int TEMP_BUF_SIZE = 64;

    /* Digital out pin */
    DigitalOut *_gpio0;
    
    /* Measure detection IRQ */
    InterruptIn *_gpio1Int;
    
	/**
	 * @brief was VL53L0X_Dev_t, Generic device information
	 *
	 * merged with VL53L0X_DevData_t that embeds ST FlightSense devdata
	 * VL53L0X Device device ST private data structure \n
	 * End user should never access any of these field directly \n
	 */
    VL53L0X_DMaxData_t DMaxData;
    /*!< Dmax Data */
    int32_t	 Last_Offset_Cal_um;
    /*!< backed up Offset_Cal value found last time, but never used !!!*/
    int32_t	 NVM_Offset_Cal_um;
    /*!< backed up NVM value representing additional offset adjustment */
    VL53L0X_DeviceParams_t CurrParams;
    /*!< Current Device Parameter */
    TRangeResults LastRangeMeasure;
    /*!< Ranging Data */
    VL53L0X_HistogramMeasurementData_t LastHistogramMeasure;
    /*!< Histogram Data */
    VL53L0X_DeviceSpecificParameters_t DevSpecParams;
    /*!< Parameters specific to the device */
    VL53L0X_SPADData_t SPADData;
    /*!< SPAD Data */
    uint8_t SequenceConfig;
    /*!< Internal value for the sequence config */
    uint8_t RangeFractionalEnable;
    /*!< Enable/Disable fractional part of ranging data */
    VL53L0X_PowerModes PowerMode;
    /*!< Current Power Mode	 */
    uint16_t SigmaEstRefArray;
    /*!< Reference array sigma value in 1/100th of [mm] e.g. 100 = 1mm */
    uint16_t SigmaEstEffPulseWidth;
    /*!< Effective Pulse width for sigma estimate in 1/100th of ns e.g. 900 = 9.0ns */
    uint16_t SigmaEstEffAmbWidth;
    /*!< Effective Ambient width for sigma estimate in 1/100th of ns
    * e.g. 500 = 5.0ns */
    uint8_t StopVariable;
    /*!< StopVariable used during the stop sequence */
    uint16_t targetRefRate;
    /*!< Target Ambient Rate for Ref SPAD management */
    TFP1616 SigmaEstimate;
    /*!< Sigma Estimate - based on ambient & VCSEL rates and signal_total_events */
    TFP1616 SignalEstimate;
    /*!< Signal Estimate - based on ambient & VCSEL rates and cross talk */
    TFP1616 LastSignalRefMcps;
    /*!< Latest Signal ref in Mcps */
    uint8_t *pTuningSettingsPointer;
    /*!< Pointer for Tuning Settings table */
    uint8_t UseInternalTuningSettings;
    /*!< Indicate if we use	 Tuning Settings table */
    uint16_t LinearityCorrectiveGain;
    /*!< Linearity Corrective Gain value in x1000 */
    uint16_t DmaxCalRangeMilliMeter;
    /*!< Dmax Calibration Range millimeter */
    TFP1616 DmaxCalSignalRateRtnMHz;
    /*!< Dmax Calibration Signal Rate Return MHz */    
};

#endif /* _VL53L0X_CLASS_H_ */