Condensed Version of Public VL53L0X

Dependents:   ToF-Only-Tryout

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers VL53L0X.h Source File

VL53L0X.h

00001 /*******************************************************************************
00002  Copyright © 2016, STMicroelectronics International N.V.
00003  All rights reserved.
00004 
00005  Redistribution and use in source and binary forms, with or without
00006  modification, are permitted provided that the following conditions are met:
00007  * Redistributions of source code must retain the above copyright
00008  notice, this list of conditions and the following disclaimer.
00009  * Redistributions in binary form must reproduce the above copyright
00010  notice, this list of conditions and the following disclaimer in the
00011  documentation and/or other materials provided with the distribution.
00012  * Neither the name of STMicroelectronics nor the
00013  names of its contributors may be used to endorse or promote products
00014  derived from this software without specific prior written permission.
00015 
00016  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017  ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018  WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
00019  NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
00020  IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
00021  DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022  (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024  ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026  SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027  *****************************************************************************/
00028 
00029 #ifndef __VL53L0X_CLASS_H
00030 #define __VL53L0X_CLASS_H
00031 
00032 /* Includes ------------------------------------------------------------------*/
00033 #include "mbed.h"
00034 #include "pinmap.h"
00035 #include "PinNames.h"
00036 #include "VL53L0X_def.h"
00037 
00038 /* Classes -------------------------------------------------------------------*/
00039 /** Class representing a VL53L0 sensor component
00040  */
00041 class VL53L0X 
00042 {
00043 public:
00044     /* Device data made accessible for further usage */
00045     TVL53L0X_DeviceInfo Device_Info;
00046 
00047     /* all the fields previously hidden under DevSpecParams 
00048        of type struct VL53L0X_DeviceSpecificParameters_t   */
00049     TFP1616 OscFrequencyMHz; 
00050     /* Frequency used */
00051     uint16_t LastEncodedTimeout;
00052     /* last encoded Time out used for timing budget*/
00053     TGPIO_Func  GpioFunctionality;
00054     /* store the functionality of the GPIO: pin0 */
00055     uint32_t FinalRangeTimeoutMicroSecs ;
00056     /*!< Execution time of the final range*/
00057     uint8_t FinalRangeVcselPPeriod ;
00058     /*!< Vcsel pulse period (pll clocks) for the final range measurement*/
00059     uint32_t PreRangeTimeoutMicroSecs ;
00060     /*!< Execution time of the final range*/
00061     uint8_t PreRangeVcselPPeriod ;
00062     /*!< Vcsel pulse period (pll clocks) for the pre-range measurement*/
00063     uint16_t SigmaEstRefArray ;
00064     /*!< Reference array sigma value in 1/100th of [mm] e.g. 100 = 1mm */
00065     uint16_t SigmaEstEffPulseWidth ;
00066     /*!< Effective Pulse width for sigma estimate in 1/100th of ns e.g. 900 = 9.0ns */
00067     uint16_t SigmaEstEffAmbWidth ;
00068     /*!< Effective Ambient width for sigma estimate in 1/100th of ns e.g. 500 = 5.0ns */
00069     uint8_t ModuleId; /* Module ID */
00070     uint8_t Revision; /* test Revision */
00071     char ProductId[VL53L0X_MAX_STRING_LENGTH]; /* Product Identifier String  */
00072     uint8_t ReferenceSPADType;  /* used for ref SPAD management */
00073     uint8_t RefSPADSInitialised; /* reports if ref SPADS are initialised. */
00074     uint32_t PartUIDUpper ; /*!< Unique Part ID Upper */
00075     uint32_t PartUIDLower ; /*!< Unique Part ID Lower */
00076     TFP1616 SignalRateMeasFixed400mm ; /*!< Peek Signal rate at 400 mm*/
00077 
00078 public: 
00079     /******************************************************************************/
00080     /****************** Public Initialization Methods     *************************/
00081     /******************************************************************************/
00082 
00083     /** Constructor
00084      * @param[in] &i2c device I2C to be used for communication
00085      * @param[in] &pin_gpio1 pin Mbed InterruptIn PinName to be used as component GPIO_1 INT
00086      * @param[in] dev_addr device address, 0x29 by default
00087      */
00088     VL53L0X(I2C *i2c, DigitalOut *pin, PinName pin_gpio1, 
00089         uint8_t dev_addr = VL53L0X_DEFAULT_ADDRESS) : _dev_i2c(i2c), _gpio0(pin)
00090     {   I2cDevAddr = dev_addr;
00091         if (pin_gpio1 != NC) { _gpio1Int = new InterruptIn(pin_gpio1); } 
00092            else { _gpio1Int = NULL;  }
00093     }
00094 
00095     /**
00096      * @brief       Turns on, checks the ID, Set new device address, 
00097      *              Initialize the calss, and the sensor with default values
00098      *
00099      * After completion the device will answer to the address new_addr.
00100      * This new_addr should be set to individual values when several devices are used in parallel
00101      * before using the individual sensors.
00102      * When a single device us used, there is no need to set new_addr.
00103      * @return      VL53L0X_Error       = 0 on success
00104      */
00105     VL53L0X_Error Start_Sensor(uint8_t new_addr = VL53L0X_DEFAULT_ADDRESS);
00106 
00107     /**
00108      * @brief       PowerOff the sensor with the XShutdown Pin
00109      */
00110     void Power_Off(void)
00111     {   if (_gpio0) { *_gpio0 = 0; }   wait_ms(1); }
00112 
00113 
00114     /** Destructor  */
00115     virtual ~VL53L0X()
00116     {  if (_gpio1Int != NULL) { delete _gpio1Int; } }
00117 
00118 
00119 private: 
00120     /******************************************************************************/
00121     /****************** Private Initialization Methods    *************************/
00122     /******************************************************************************/
00123 
00124     /**
00125      * @brief One time device initialization
00126      *
00127      * To be called once and only once after device is brought out of reset
00128      * (Chip enable) and booted see @a void WaitDeviceBooted()
00129      *
00130      * @par Function Description
00131      * When not used after a fresh device "power up" or reset, it may return
00132      * @a #VL53L0X_ERROR_CALIBRATION_WARNING meaning wrong calibration data
00133      * may have been fetched from device that can result in ranging offset error\n
00134      * If application cannot execute device reset or need to run VL53L0X_DataInit
00135      * multiple time then it  must ensure proper offset calibration saving and
00136      * restore on its own by using @a VL53L0X_GetOffsetCalibrationData() on first
00137      * power up and then @a VL53L0X_SetOffsetCalibrationData() in all subsequent init
00138      * This function will change the VL53L0X_State from VL53L0X_STATE_POWERDOWN to
00139      * VL53L0X_STATE_WAIT_STATICINIT.
00140      *
00141      * @return  None; instead check class Field "ErrState"
00142      */
00143     void Data_init();
00144  
00145     /**
00146      * @brief Reads the Device information for given Device
00147      *
00148      * @note This function is called once at Sensor Init, then all device info
00149      *    available in the Device_Info Structure
00150      * 
00151      * @return   Device_Info  Structure is filled with device info for the Device
00152      *           Also check and fix errors reported Field "ErrState"   */
00153     void Fill_device_info();
00154     
00155     /* api_core.h functions */
00156     void Get_all_NVM_info_from_device( uint8_t option);
00157 
00158     /* All the data that is read from the NVM and stored internally */
00159     uint8_t ReadNVMDataFromDeviceDone; /* Indicate if read from device has been done (==1-4-7) or not (==0) */
00160     uint8_t ReferenceSPADCount; /* used for ref SPAD management */
00161 
00162 public:
00163     /**
00164      * @brief       Start the measure indicated by operating mode
00165      * @param[in]   operating_mode specifies requested measure
00166      * @param[in]   fptr specifies call back function must be !NULL in case of interrupt measure
00167      */
00168     VL53L0X_Error Start_Measurement(TOperatingMode operating_mode, 
00169                    void (*fptr)(void));
00170 
00171     /**
00172      * @brief       Get results for the measure indicated by operating mode
00173      * @param[in]   operating_mode specifies requested measure results
00174      * @result       TRangeResults The MeasureData_t structure with all results
00175      */
00176     TRangeResults Get_Measurement(TOperatingMode operating_mode);
00177 
00178     /**
00179      * @brief       Stop the currently running measure indicate by operating_mode
00180      * @param[in]   operating_mode specifies requested measure to stop
00181      "0" on success
00182      */
00183     VL53L0X_Error Stop_Measurement(TOperatingMode operating_mode);
00184 
00185     /**
00186      * @brief     Interrupt handling func to be called by user after an INT is occourred
00187      * @param[in] operating_mode  Opeating_mode indicating the in progress measure
00188      * @result    TRangeResults   The Measurement Data structure given back
00189      */
00190     TRangeResults Handle_irq(TOperatingMode operating_mode);
00191 
00192     /**
00193      * @brief       Enable interrupt measure IRQ
00194      */
00195     void Enable_interrupt_measure_detection_irq(void)
00196     {  if (_gpio1Int != NULL) { _gpio1Int->enable_irq(); }  }
00197 
00198     /**
00199      * @brief       Disable interrupt measure IRQ
00200      "0" on success
00201      */
00202     void Disable_interrupt_measure_detection_irq(void)
00203     {  if (_gpio1Int != NULL) { _gpio1Int->disable_irq(); }  }
00204 
00205     /**
00206      * @brief       Attach a function to call when an interrupt is detected, i.e. measurement is ready
00207      * @param[in]   fptr pointer to call back function to be called whenever an interrupt occours
00208      "0" on success
00209      */
00210     void Attach_interrupt_measure_detection_irq(void (*fptr)(void))
00211     {   if (_gpio1Int != NULL) { _gpio1Int->rise(fptr);  }    }
00212 
00213     /** Wrapper functions */
00214     /** @defgroup api_init Init functions
00215      *  @brief    API init functions
00216      *  @ingroup  api_hl
00217      *  @{
00218      */
00219 
00220     /**
00221       * @brief  Prepare device for operation
00222       * @par Function Description
00223       * Does static initialization and reprogram common default settings \n
00224       * Device is prepared for new measure, ready single shot ranging or ALS typical polling operation\n
00225       * After prepare user can : \n
00226       * @li Call other API function to set other settings\n
00227       * @li Configure the interrupt pins, etc... \n
00228       * @li Then start ranging or ALS operations in single shot or continuous mode
00229       *
00230       * @param void
00231       * @return  "0" on success
00232       */
00233     VL53L0X_Error Prepare();
00234 
00235     /**
00236     * @brief Start continuous ranging mode
00237     *
00238     * @details End user should ensure device is in idle state and not already running
00239     * @return  "0" on success
00240     */
00241     void Range_start_continuous_mode()
00242     {   Set_device_mode( VL53L0X_DEVICEMODE_CONTINUOUS_RANGING);
00243         if (ErrState == VL53L0X_OK) {  Start_Measurement();  }
00244     }
00245 
00246     /**
00247      * @brief Get ranging result and only that
00248      *
00249      * @par Function Description
00250      * Unlike @a Get_ranging_results() this function only retrieves the range in millimeter \n
00251      * It does any required up-scale translation\n
00252      * It can be called after success ErrState polling or in interrupt mode \n
00253      * @warning these function is not doing wrap around filtering \n
00254      * This function doesn't perform any data ready check!
00255      *
00256      * @param p_data  Pointer to range distance
00257        "0" on success
00258      */
00259     uint32_t Get_distance();
00260 
00261     /** @}  */
00262 
00263 
00264 
00265     /**
00266      * @brief Do basic device init (and eventually patch loading)
00267      * This function will change the VL53L0X_State from
00268      * VL53L0X_STATE_WAIT_STATICINIT to VL53L0X_STATE_IDLE.
00269      * In this stage all default setting will be applied.
00270      *
00271      * @note This function Access to the device
00272      *
00273      * 
00274      * @return  None; instead check class Field "ErrState"
00275      */
00276     void Static_init();
00277 
00278     /**
00279      * @brief Perform Reference Calibration
00280      *
00281      * @details Perform a reference calibration of the Device.
00282      * This function should be run from time to time before doing
00283      * a ranging measurement.
00284      * This function will launch a special ranging measurement, so
00285      * if interrupt are enable an interrupt will be done.
00286      * This function will clear the interrupt generated automatically.
00287      *
00288      * @warning This function is a blocking function
00289      *
00290      * @note This function Access to the device
00291      *
00292      * 
00293      * @param   p_vhv_settings       Pointer to vhv settings parameter.
00294      * @param   p_phase_cal          Pointer to PhaseCal parameter.
00295      * @param   get_data_enable      1 to enable to get the data
00296      * @return  None; instead check class Field "ErrState"
00297      */
00298     void Perf_Ref_calibration(
00299             uint8_t *p_vhv_settings, uint8_t *p_phase_cal, uint8_t get_data_enable);
00300 
00301     /**
00302      * @brief Get Reference Calibration Parameters
00303      *
00304      * @par Function Description
00305      * Get Reference Calibration Parameters.
00306      *
00307      * @note This function Access to the device
00308      *
00309      * 
00310      * @param   p_vhv_settings                 Pointer to VHV parameter
00311      * @param   p_phase_cal                    Pointer to PhaseCal Parameter
00312      * @return  None; instead check class Field "ErrState"            
00313      */
00314     void Get_Ref_calibration(
00315             uint8_t *p_vhv_settings, uint8_t *p_phase_cal);
00316 
00317     void Set_Ref_calibration(
00318             uint8_t vhv_settings, uint8_t phase_cal);
00319 
00320     /**
00321      * @brief Performs Reference SPAD Management
00322      *
00323      * @par Function Description
00324      * The reference SPAD initialization procedure determines the minimum amount
00325      * of reference SPADS to be enables to achieve a target reference signal rate
00326      * and should be performed once during initialization.
00327      *
00328      * @note This function Access to the device
00329      *
00330      * @note This function change the device mode to
00331      * VL53L0X_DEVICEMODE_SINGLE_RANGING
00332      *
00333      * 
00334      * @param   ref_SPAD_count               Reports ref SPAD Count
00335      * @param   is_aperture_SPADS            Reports if SPADS are of type
00336      *                                       aperture or non-aperture.
00337      *                                       1:=aperture, 0:=Non-Aperture
00338      * @return  None; instead check class Field "ErrState"       
00339      * @return  VL53L0X_ERROR_REF_SPAD_INIT  Error in the Ref SPAD procedure.
00340      */
00341     void Perf_Ref_SPAD_management(
00342             uint32_t *ref_SPAD_count, uint8_t *is_aperture_SPADS);
00343 
00344     /**
00345      * @brief Applies Reference SPAD configuration
00346      *
00347      * @par Function Description
00348      * This function applies a given number of reference SPADS, identified as
00349      * either Aperture or Non-Aperture.
00350      * The requested SPAD count and type are stored within the device specific
00351      * parameters data for access by the host.
00352      *
00353      * @note This function Access to the device
00354      *
00355      * 
00356      * @param   refSPADCount                 Number of ref SPADS.
00357      * @param   is_aperture_SPADS            Defines if SPADS are of type
00358      *                                       aperture or non-aperture.
00359      *                                       1:=aperture, 0:=Non-Aperture
00360      * @return  None; instead check class Field "ErrState"       
00361      * @return  VL53L0X_ERROR_REF_SPAD_INIT  Error in the in the reference
00362      *                                       SPAD configuration.
00363      */
00364     void Set_Reference_SPADS(
00365             uint32_t refSPADCount, uint8_t is_aperture_SPADS);
00366 
00367     /**
00368      * @brief Retrieves SPAD configuration
00369      *
00370      * @par Function Description
00371      * This function retrieves the current number of applied reference SPADS
00372      * and also their type : Aperture or Non-Aperture.
00373      *
00374      * @note This function Access to the device
00375      *
00376      * 
00377      * @param   p_SPAD_count                 Number ref SPAD Count
00378      * @param   p_is_aperture_SPADS          Reports if SPADS are of type
00379      *                                       aperture or non-aperture.
00380      *                                       1:=aperture, 0:=Non-Aperture
00381      * @return  None; instead check class Field "ErrState"       
00382      * @return  VL53L0X_ERROR_REF_SPAD_INIT  Error in the in the reference
00383      *                                       SPAD configuration.
00384      */
00385     void Get_Reference_SPADS(
00386             uint32_t *p_SPAD_count, uint8_t *p_is_aperture_SPADS);
00387 
00388     /**
00389      * @brief Get part to part calibration offset
00390      *
00391      * @par Function Description
00392      * Should only be used after a successful call to @a VL53L0X_DataInit to backup
00393      * device NVM value
00394      *
00395      * @note This function Access to the device
00396      *
00397      * @param   p_Offset_Cal_um   
00398      * @return  int32_t; Return part to part calibration offset from device (microns), also check class Field "ErrState"                           
00399      */
00400     int32_t Get_Offset_Cal_um();
00401     /**
00402      * Set or over-hide part to part calibration offset
00403      * \sa VL53L0X_DataInit()   VL53L0X_GetOffsetCalibrationData_um()
00404      *
00405      * @note This function Access to the device
00406      *
00407      * @param   p_Offset_Cal_um    Offset (microns)
00408      * @return  None; instead check class Field "ErrState"                           
00409      */
00410     void Set_Offset_Cal_um(  int32_t Offset_Cal_um  );
00411 
00412     void Perf_offset_calibration( TFP1616 cal_distance_milli_meter,
00413             int32_t *p_offset_um);
00414 
00415     void Perf_xtalk_calibration(  TFP1616 xtalk_cal_distance,
00416             TFP1616 *p_Xtalk_CompRate_MHz);
00417 
00418     /**
00419      * @brief Perform XTalk Measurement
00420      *
00421      * @details Measures the current cross talk from glass in front
00422      * of the sensor.
00423      * This functions performs a histogram measurement and uses the results
00424      * to measure the crosstalk. For the function to be successful, there
00425      * must be no target in front of the sensor.
00426      *
00427      * @warning This function is a blocking function
00428      *
00429      * @warning This function is not supported when the final range
00430      * vcsel clock period is set below 10 PCLKS.
00431      *
00432      * @note This function Access to the device
00433      *
00434      * 
00435      * @param   timeout_ms             Histogram measurement duration.
00436      * @param   p_xtalk_per_SPAD       Output parameter containing the crosstalk
00437      *                                 measurement result, in MHz/SPAD.
00438      *                                 Format fixpoint 16:16.
00439      * @param   p_ambient_too_high     Output parameter which indicate that
00440      *                                 pXtalkPerSPAD is not good if the Ambient
00441      *                                 is too high.
00442      * @return  None; instead check class Field "ErrState" 
00443      * @return  VL53L0X_ERROR_INVALID_PARAMS vcsel clock period not supported
00444      *                                 for this operation.
00445      *                                 Must not be less than 10PCLKS.
00446      */
00447     void Perf_xtalk_measurement(
00448             uint32_t timeout_ms, TFP1616 *p_xtalk_per_SPAD,
00449             uint8_t *p_ambient_too_high);
00450 
00451     /**
00452      * @brief Enable/Disable Cross talk compensation feature
00453      *
00454      * @note This function is not Implemented.
00455      * Enable/Disable Cross Talk by set to zero the Cross Talk value
00456      * by using @a VL53L0X_SetXtalk_CompRate_MHz().
00457      *
00458      * 
00459      * @param  xtalk_compensation_enable    Cross talk compensation
00460      *                                       to be set 0=disabled else = enabled
00461      * @return VL53L0X_ERROR_NOT_IMPLEMENTED Not implemented
00462      */
00463     void Set_xtalk_compensation_enable(
00464             uint8_t xtalk_compensation_enable);
00465 
00466      /**
00467      * @brief Set Cross talk compensation rate
00468      *
00469      * @par Function Description
00470      * Set Cross talk compensation rate.
00471      *
00472      * @note This function Access to the device
00473      *
00474      * 
00475      * @param   Xtalk_CompRate_MHz   Compensation rate in
00476      *                                              Mega counts per second
00477      *                                              (16.16 fix point) see
00478      *                                              datasheet for details
00479      * @return  None; instead check class Field "ErrState"              
00480      */
00481     void Set_Xtalk_CompRate_MHz(  TFP1616 Xtalk_CompRate_MHz );
00482 
00483     /**
00484      * @brief Get Cross talk compensation rate
00485      *
00486      * @par Function Description 
00487      * Get Cross talk compensation rate.
00488      *
00489      * @note This function Access to the device
00490      *
00491      * 
00492      * @param   p_Xtalk_CompRate_MHz  Pointer to Compensation rate
00493      *                                              in Mega counts per second
00494      *                                              (16.16 fix point) see
00495      *                                              datasheet for details
00496      * @return  None; instead check class Field "ErrState"                
00497      */
00498      
00499     void Get_Xtalk_CompRate_MHz(
00500             TFP1616 *p_Xtalk_CompRate_MHz);
00501 
00502     /**
00503      * @brief  Set a new device mode
00504      * @par Function Description
00505      * Set device to a new mode (ranging, histogram ...)
00506      *
00507      * @note This function doesn't Access to the device
00508      *
00509      * 
00510      * @param   device_mode           New device mode to apply
00511      *                                Valid values are:
00512      *                                VL53L0X_DEVICEMODE_SINGLE_RANGING
00513      *                                VL53L0X_DEVICEMODE_CONTINUOUS_RANGING
00514      *                                VL53L0X_DEVICEMODE_CONTINUOUS_TIMED_RANGING
00515      *                                VL53L0X_DEVICEMODE_SINGLE_HISTOGRAM
00516      *                                VL53L0X_HISTOGRAMMODE_REFERENCE_ONLY
00517      *                                VL53L0X_HISTOGRAMMODE_RETURN_ONLY
00518      *                                VL53L0X_HISTOGRAMMODE_BOTH
00519      *
00520      *
00521      * @return  None; instead check class Field "ErrState"           
00522      * @return  VL53L0X_ERROR_MODE_NOT_SUPPORTED This error occurs when
00523      *                                           DeviceMode is not in the
00524      *                                           supported list
00525      */
00526     void Set_device_mode( VL53L0X_DeviceModes device_mode);
00527 
00528     /**
00529     * @brief Get current configuration for GPIO pin for a given device
00530     *
00531     * @note This function Access to the device
00532     *
00533     * 
00534     * @param   pin                   ID of the GPIO Pin
00535     * @param   p_device_mode         Pointer to Device Mode associated to the Gpio.
00536     * @param   p_functionality       Pointer to Pin functionality.
00537     *                                Refer to ::TGPIO_Func
00538     * @param   p_polarity            Pointer to interrupt polarity.
00539     *                                Active high or active low see
00540     *                                ::VL53L0X_InterruptPolarity
00541     * @return  None; instead check class Field "ErrState"
00542     * @return  VL53L0X_ERROR_GPIO_NOT_EXISTING           Only Pin=0 is accepted.
00543     * @return  VL53L0X_ERROR_GPIO_FUNC_NOT_SUPPORTED
00544     *          This error occurs
00545     *          when Funcionality programmed is not in the supported list:
00546     *                      Supported value are:
00547     *                      GPIO_FUNC_OFF,
00548     *                      GPIO_FUNC_THRESHOLD_CROSSED_LOW,
00549     *                      GPIO_FUNC_THRESHOLD_CROSSED_HIGH,
00550     *                      GPIO_FUNC_THRESHOLD_CROSSED_OUT,
00551     *                      GPIO_FUNC_NEW_MEASURE_READY
00552     */
00553     void Get_gpio_config( uint8_t pin, VL53L0X_DeviceModes *p_device_mode,
00554                                           TGPIO_Func  *p_functionality,
00555                                           VL53L0X_InterruptPolarity *p_polarity);
00556 
00557     /**
00558      * @brief Set the configuration of GPIO pin for a given device
00559      *
00560      * @note This function Access to the device
00561      * 
00562      * @param   pin                   ID of the GPIO Pin
00563      * @param   functionality         Select Pin functionality.
00564      *  Refer to ::TGPIO_Func
00565      * @param   device_mode            Device Mode associated to the Gpio.
00566      * @param   polarity              Set interrupt polarity. Active high
00567      *   or active low see ::VL53L0X_InterruptPolarity
00568      * @return  None; instead check class Field "ErrState"                        
00569      * @return  VL53L0X_ERROR_GPIO_NOT_EXISTING               Only Pin=0 is accepted.
00570      * @return  VL53L0X_ERROR_GPIO_FUNC_NOT_SUPPORTED    This error occurs
00571      * when Functionality programmed is not in the supported list:
00572      *                             Supported value are:
00573      *                              GPIO_FUNC_OFF,
00574      *                              GPIO_FUNC_THRESHOLD_CROSSED_LOW,
00575      *                              GPIO_FUNC_THRESHOLD_CROSSED_HIGH,
00576      *                              GPIO_FUNC_THRESHOLD_CROSSED_OUT,
00577      *                              GPIO_FUNC_NEW_MEASURE_READY
00578      */
00579     void Set_GPIO_config( VL53L0X_DeviceModes device_mode, 
00580          TGPIO_Func  functionality,  VL53L0X_InterruptPolarity polarity);
00581 
00582     /**
00583      * @brief Start device measurement
00584      *
00585      * @details Started measurement will depend on device parameters set through
00586      * @a VL53L0X_SetParameters()
00587      * This is a non-blocking function.
00588      * This function will change the VL53L0X_State from VL53L0X_STATE_IDLE to
00589      * VL53L0X_STATE_RUNNING.
00590      *
00591      * @note This function Access to the device
00592      *
00593 
00594      * 
00595      * @return  None; instead check class Field "ErrState"              
00596      * @return  VL53L0X_ERROR_MODE_NOT_SUPPORTED    This error occurs when
00597      * DeviceMode programmed with @a VL53L0X_SetDeviceMode is not in the supported
00598      * list:
00599      *                                   Supported mode are:
00600      *                                   VL53L0X_DEVICEMODE_SINGLE_RANGING,
00601      *                                   VL53L0X_DEVICEMODE_CONTINUOUS_RANGING,
00602      *                                   VL53L0X_DEVICEMODE_CONTINUOUS_TIMED_RANGING
00603      * @return  VL53L0X_ERROR_TIME_OUT    Time out on start measurement
00604      */
00605     void Start_Measurement();
00606 
00607     /**
00608      * @brief Stop device measurement
00609      *
00610      * @details Will set the device in standby mode at end of current measurement\n
00611      *          Not necessary in single mode as device shall return automatically
00612      *          in standby mode at end of measurement.
00613      *          This function will change the VL53L0X_State from VL53L0X_STATE_RUNNING
00614      *          to VL53L0X_STATE_IDLE.
00615      *
00616      * @note This function Access to the device
00617      *
00618      * 
00619      * @return  None; instead check class Field "ErrState"
00620      */
00621     void Stop_Measurement();
00622 
00623     /**
00624      * @brief Return device stop completion ErrState
00625      *
00626      * @par Function Description
00627      * Returns stop completiob ErrState.
00628      * User shall call this function after a stop command
00629      *
00630      * @note This function Access to the device
00631      *
00632      * 
00633      * @return   p_stop_status            Pointer to ErrState variable to update
00634      *                                    Also instead check class Field "ErrState"  
00635      */
00636     uint8_t Get_Stop_Completed( );
00637 
00638     /**
00639      * @brief Return Measurement is Ready
00640      *
00641      * @par Function Description
00642      * This function indicate that a measurement data is ready.
00643      * This function check if interrupt mode is used then check is done accordingly.
00644      * If perform function clear the interrupt, this function will not work,
00645      * like in case of @a VL53L0X_PerformSingleRangingMeasurement().
00646      * The previous function is blocking function, VL53L0X_GetMeasurementDataReady
00647      * is used for non-blocking capture.
00648      *
00649      * @note This function Access to the device
00650      *
00651      * 
00652      * @return   uint8_t     Is Measurement Ready 0= not ready, 1 = ready
00653      *                       Also check class Field "ErrState"  
00654      */
00655     uint8_t Get_Measurement_Ready();
00656 
00657     /**
00658      * @brief Retrieve the measurements from device for a given setup
00659      *
00660      * @par Function Description
00661      * Get data from last successful Ranging measurement
00662      * @warning USER should take care about  @a VL53L0X_GetNumberOfROIZones()
00663      * before get data.
00664      * Device will fill a NumberOfROIZones times the corresponding data
00665      * structure used in the measurement function.
00666      *
00667      * @note This function Access to the device
00668      *
00669      * 
00670      * @param   p_ranging_results  Pointer to the data structure to fill up.
00671      * @return  None; instead check class Field "ErrState"    
00672      */
00673     void Get_ranging_results(
00674             TRangeResults *p_ranging_results);
00675 
00676     /**
00677      * @brief Clear given system interrupt condition
00678      *
00679      * @par Function Description
00680      * Clear given interrupt(s) cause by writing into register #SYSINT_CLEAR register.
00681      *
00682      * @note   This function Access to the device
00683      * 
00684      * @param   interrupt_mask        Which interrupt source to clear. Use any combinations of #INTERRUPT_CLEAR_RANGING , #INTERRUPT_CLEAR_ALS , #INTERRUPT_CLEAR_ERROR.
00685      * @return  None; instead check class Field "ErrState"
00686      * @return  VL53L0X_ERROR_INTERRUPT_NOT_CLEARED    Cannot clear interrupts
00687      */
00688      void Clear_interrupt_mask( uint32_t interrupt_mask);
00689 
00690     /**
00691      * @brief Return device interrupt ErrState
00692      *
00693      * @par Function Description
00694      * Returns currently raised interrupts by the device.
00695      * User shall be able to activate/deactivate interrupts through
00696      * @a VL53L0X_SetGpioConfig()
00697      *
00698      * @note This function Access to the device
00699      *
00700      * 
00701      * @param   p_interrupt_mask_status   Pointer to ErrState variable to update
00702      * @return  None; instead check class Field "ErrState"
00703      */
00704     void Get_interrupt_mask_status(  uint32_t *p_interrupt_mask_status);
00705 
00706     /**
00707      * @brief Performs a single ranging measurement and retrieve the ranging
00708      * measurement data
00709      *
00710      * @par Function Description
00711      * This function will change the device mode to VL53L0X_DEVICEMODE_SINGLE_RANGING
00712      * with @a VL53L0X_SetDeviceMode(),
00713      * It performs measurement with @a VL53L0X_PerformSingleMeasurement()
00714      * It get data from last successful Ranging measurement with
00715      * @a VL53L0X_GetRangingMeasurementData.
00716      * Finally it clear the interrupt with @a VL53L0X_ClearInterruptMask().
00717      *
00718      * @note This function Access to the device
00719      *
00720      * @note This function change the device mode to
00721      * VL53L0X_DEVICEMODE_SINGLE_RANGING
00722      *
00723      * 
00724      * @param   p_ranging_results   Pointer to the data structure to fill up.
00725      * @return  None; instead check class Field "ErrState"     
00726      */
00727     void Perf_single_ranging_measurement(
00728             TRangeResults *p_ranging_results);
00729 
00730     /**
00731      * @brief Single shot measurement.
00732      *
00733      * @par Function Description
00734      * Perform simple measurement sequence (Start measure, Wait measure to end,
00735      * and returns when measurement is done).
00736      * Once function returns, user can get valid data by calling
00737      * VL53L0X_GetRangingMeasurement or VL53L0X_GetHistogramMeasurement
00738      * depending on defined measurement mode
00739      * User should Clear the interrupt in case this are enabled by using the
00740      * function VL53L0X_ClearInterruptMask().
00741      *
00742      * @warning This function is a blocking function
00743      *
00744      * @note This function Access to the device
00745      *
00746      * 
00747      * @return  None; instead check class Field "ErrState"
00748      */
00749     void Perf_single_measurement();
00750 
00751     /**
00752     * @brief Read current ErrState of the error register for the selected device
00753     *
00754     * @note This function Access to the device
00755     *
00756     * @param   p_device_error_status    Pointer to current error code of the device
00757     * @return  None; instead check class Field "ErrState" 
00758     */
00759     void Get_device_error_status(TDevError *p_device_error_status);
00760 
00761     /**
00762     * @brief Human readable error string for a given Error Code
00763     *
00764     * @note This function doesn't access to the device
00765     *
00766     * @param   error_code           The error code as stored on ::TDevError
00767     * @param   p_device_error_string  The error string corresponding to the ErrorCode
00768     * @return  None; instead check class Field "ErrState"
00769     */
00770     void Get_device_error_string(TDevError error_code, char *p_device_error_string);
00771 
00772     void Get_total_SIG_rate( TRangeResults *p_ranging_results,
00773             TFP1616 *p_total_SIG_rate_mcps);
00774 
00775     TFP1616 Get_total_xtalk_rate( TRangeResults *p_ranging_results);
00776             
00777     /**
00778      * @brief Get Ranging Timing Budget in microseconds
00779      *
00780      * @par Function Description
00781      * Returns the programmed the maximum time allowed by the user to the
00782      * device to run a full ranging sequence for the current mode
00783      * (ranging, histogram, ASL ...)
00784      *
00785      * @note This function Access to the device
00786      *
00787      * 
00788      * @return   uint32_t   Max measurement time in microseconds.
00789      *                                   Valid values are:
00790      *                                   >= 17000 microsecs when wraparound enabled
00791      *                                   >= 12000 microsecs when wraparound disabled
00792      *                          Also check class Field "ErrState"                            
00793      */
00794     uint32_t Get_Measure_Time_Budget_us();
00795 
00796     /**
00797      * @brief Set Ranging Timing Budget in microseconds
00798      *
00799      * @par Function Description
00800      * Defines the maximum time allowed by the user to the device to run a
00801      * full ranging sequence for the current mode (ranging, histogram, ASL ...)
00802      *
00803      * @note This function Access to the device
00804      *
00805      * 
00806      * @param Measure_Time_Budget_us  Max measurement time in
00807      * microseconds.
00808      *                                   Valid values are:
00809      *                                   >= 17000 microsecs when wraparound enabled
00810      *                                   >= 12000 microsecs when wraparound disabled
00811      * @return  None; instead check class Field "ErrState"         
00812      * @return  VL53L0X_ERROR_INVALID_PARAMS   This error is returned if
00813      MeasurementTimingBudgetMicroSeconds out of range
00814      */
00815     void Set_Measure_Time_Budget_us( uint32_t Measure_Time_Budget_us);
00816 
00817     /**
00818      * @brief  Get specific limit check enable state
00819      *
00820      * @par Function Description
00821      * This function get the enable state of a specific limit check.
00822      * The limit check is identified with the limit_check_id.
00823      *
00824      * @note This function Access to the device
00825      *
00826      * 
00827      * @param   limit_check_id                  Limit Check ID
00828      *  (0<= limit_check_id < VL53L0X_GetNumberOfLimitCheck() ).
00829      * @return   uint8_t      Check limit enable value.
00830      *  if 1 the check limit
00831      *        corresponding to limit_check_id is Enabled
00832      *  if 0 the check limit
00833      *        corresponding to limit_check_id is disabled
00834      * @return  also check class Field "ErrState"         
00835      * @return  VL53L0X_ERROR_INVALID_PARAMS   This error is returned when limit_check_id value is out of range.
00836      */
00837     uint8_t Get_limit_chk_en( uint16_t limit_check_id);
00838 
00839     /**
00840      * @brief  Enable/Disable a specific limit check
00841      *
00842      * @par Function Description
00843      * This function Enable/Disable a specific limit check.
00844      * The limit check is identified with the limit_check_id.
00845      *
00846      * @note This function doesn't Access to the device
00847      * 
00848      * @param   limit_check_id         Limit Check ID
00849      *  (0<= limit_check_id < VL53L0X_GetNumberOfLimitCheck() ).
00850      * @param   limit_chk_en           if 1 the check limit corresponding to limit_check_id is Enabled
00851      *                                 if 0 the check limit corresponding to limit_check_id is disabled
00852      * @return  None; instead check class Field "ErrState"         
00853      * @return  VL53L0X_ERROR_INVALID_PARAMS   This error is returned
00854      *  when limit_check_id value is out of range.
00855      */
00856     void Set_limit_chk_en( uint16_t limit_check_id, uint8_t limit_chk_en);
00857 
00858     /**
00859      * @brief  Get a specific limit check value
00860      *
00861      * @par Function Description
00862      * This function get a specific limit check value from device then it updates
00863      * internal values and check enables.
00864      * The limit check is identified with the limit_check_id.
00865      *
00866      * @note This function Access to the device
00867      *
00868      * 
00869      * @param   limit_check_id                  Limit Check ID
00870      *  (0<= limit_check_id < VL53L0X_GetNumberOfLimitCheck() ).
00871      * @return  TFP1616         Limit  check Value for a given limit_check_id.
00872      * @return  Also check class Field "ErrState";returned VL53L0X_ERROR_INVALID_PARAMS
00873      *          when limit_check_id value is out of range.  
00874      */
00875     TFP1616 Get_limit_chk_val( uint16_t limit_check_id);
00876 
00877     /**
00878      * @brief  Set a specific limit check value
00879      *
00880      * @par Function Description
00881      * This function set a specific limit check value.
00882      * The limit check is identified with the limit_check_id.
00883      *
00884      * @note This function Access to the device
00885      * 
00886      * @param   limit_check_id                  Limit Check ID
00887      *  (0<= limit_check_id < VL53L0X_GetNumberOfLimitCheck() ).
00888      * @param   limit_chk_val               Limit check Value for a given
00889      * limit_check_id
00890      * @return  None; instead check class Field "ErrState"         
00891      * @return  VL53L0X_ERROR_INVALID_PARAMS   This error is returned when either
00892      *  limit_check_id or LimitCheckValue value is out of range.
00893      */
00894     void Set_limit_chk_val( uint16_t limit_check_id, TFP1616 limit_chk_val);
00895 
00896     /**
00897      * @brief  Get the current value of the signal used for the limit check
00898      *
00899      * @par Function Description
00900      * This function get a the current value of the signal used for the limit check.
00901      * To obtain the latest value you should run a ranging before.
00902      * The value reported is linked to the limit check identified with the
00903      * limit_check_id.
00904      *
00905      * @note This function Access to the device
00906      * 
00907      * @param   limit_check_id                  Limit Check ID
00908      *  (0<= limit_check_id < VL53L0X_GetNumberOfLimitCheck() ).
00909      * @param   p_limit_check_current            Pointer to current Value for a
00910      * given limit_check_id.
00911      * @return  None; instead check class Field "ErrState"         
00912      * @return  VL53L0X_ERROR_INVALID_PARAMS   This error is returned when
00913      * limit_check_id value is out of range.
00914      */
00915     void Get_limit_check_current( uint16_t limit_check_id, 
00916                                   TFP1616 *p_limit_check_current);
00917 
00918     /**
00919      * @brief  Return a the Status of the specified check limit
00920      *
00921      * @par Function Description
00922      * This function returns the Status of the specified check limit.
00923      * The value indicate if the check is fail or not.
00924      * The limit check is identified with the limit_check_id.
00925      *
00926      * @note This function doesn't Access to the device
00927      * 
00928      * @param   limit_check_id                  Limit Check ID
00929      (0<= limit_check_id < VL53L0X_GetNumberOfLimitCheck() ).
00930      * @param   p_limit_check_status             Pointer to the
00931      Limit Check Status of the given check limit.
00932      * LimitCheckStatus :
00933      * 0 the check is not fail
00934      * 1 the check if fail or not enabled
00935      *
00936      * @return  None; instead check class Field "ErrState"         
00937      * @return  VL53L0X_ERROR_INVALID_PARAMS   This error is
00938      returned when limit_check_id value is out of range.             
00939      */
00940     void Get_limit_check_status(uint16_t limit_check_id, uint8_t *p_limit_check_status);
00941 
00942     /**
00943      * Get continuous mode Inter-Measurement period in milliseconds
00944      *
00945      * @par Function Description
00946      * When trying to set too short time return  INVALID_PARAMS minimal value
00947      *
00948      * @note This function Access to the device
00949      * 
00950      * @param   p_measure_period_ms  Pointer to programmed
00951      *  Inter-Measurement Period in milliseconds.
00952      * @return  None; instead check class Field "ErrState"                               
00953      */
00954     void Get_measure_period_ms(uint32_t *p_measure_period_ms);
00955 
00956     /**
00957      * Program continuous mode Inter-Measurement period in milliseconds
00958      *
00959      * @par Function Description
00960      * When trying to set too short time return  INVALID_PARAMS minimal value
00961      *
00962      * @note This function Access to the device
00963      * 
00964      * @param   measure_period_ms   Inter-Measurement Period in ms.
00965      * @return  None; instead check class Field "ErrState"                         
00966      */
00967     void Set_measure_period_ms( uint32_t measure_period_ms );
00968 
00969     /**
00970      * @brief Do an hard reset or soft reset (depending on implementation) of the
00971      * device \nAfter call of this function, device must be in same state as right
00972      * after a power-up sequence.This function will change the VL53L0X_State to
00973      * VL53L0X_STATE_POWERDOWN.
00974      *
00975      * @note This function Access to the device
00976      * 
00977      * @return  None; instead check class Field "ErrState" 
00978      */
00979     void Reset_device();
00980 
00981     /**
00982      * @brief  Get setup of Wrap around Check
00983      *
00984      * @par Function Description
00985      * This function get the wrapAround check enable parameters
00986      *
00987      * @note This function Access to the device
00988      * 
00989      * @return  uint8_t  Wrap around Check state 0=disabled or 1 = enabled
00990      * @return  None       Also check class Field "ErrState"   
00991      */
00992     uint8_t Get_Wrap_Around_Chk_En();
00993 
00994     /**
00995      * @brief  Enable (or disable) Wrap around Check
00996      *
00997      * @note This function Access to the device
00998      *
00999      * 
01000      * @param   wrap_around_Chk_En  Wrap around Check to be set
01001      *                                 0=disabled, other = enabled
01002      * @return  None; instead check class Field "ErrState"  
01003      */
01004     void Set_wrap_around_Chk_En( uint8_t wrap_around_Chk_En);
01005 
01006     /**
01007      * @brief Sets the VCSEL pulse period.
01008      *
01009      * @par Function Description
01010      * This function retrieves the VCSEL pulse period for the given period type.
01011      *
01012      * @note This function Accesses the device
01013      * 
01014      * @param   Vcsel_Range_Phase         VCSEL period identifier (pre-range|final).
01015      * @param   vcsel_PPeriod          VCSEL period value
01016      * @return  None; instead check class Field "ErrState"        
01017      * @return  VL53L0X_ERROR_INVALID_PARAMS  Error VcselPeriodType parameter not
01018      *                                       supported.
01019      */
01020     void Set_vcsel_PPeriod( VL53L0X_Range_Phase Vcsel_Range_Phase, 
01021                                 uint8_t vcsel_PPeriod);
01022 
01023     /**
01024      * @brief Set low and high Interrupt thresholds for a given mode
01025      * (ranging, ALS, ...) for a given device
01026      *
01027      * @par Function Description
01028      * Set low and high Interrupt thresholds for a given mode (ranging, ALS, ...)
01029      * for a given device
01030      *
01031      * @note This function Access to the device
01032      *
01033      * @note DeviceMode is ignored for the current device
01034      * 
01035      * @param   device_mode       Device Mode for which change thresholds
01036      * @param   threshold_low     Low threshold (mm, lux ..., depending on the mode)
01037      * @param   threshold_high    High threshold (mm, lux ..., depending on the mode)
01038      * @return  None; instead check class Field "ErrState"
01039      */
01040     void Set_interrupt_thresholds( VL53L0X_DeviceModes device_mode, 
01041            TFP1616 threshold_low,  TFP1616 threshold_high);
01042 
01043     /**
01044      * @brief  Get high and low Interrupt thresholds for a given mode
01045      *  (ranging, ALS, ...) for a given device
01046      *
01047      * @par Function Description
01048      * Get high and low Interrupt thresholds for a given mode (ranging, ALS, ...)
01049      * for a given device
01050      *
01051      * @note This function Access to the device
01052      *
01053      * @note DeviceMode is ignored for the current device
01054      * 
01055      * @param   device_mode       Device Mode from which read thresholds
01056      * @param   p_threshold_low    Low threshold (mm, lux ..., depending on the mode)
01057      * @param   p_threshold_high   High threshold (mm, lux ..., depending on the mode)
01058      * @return  None; instead check class Field "ErrState"
01059      */
01060     void Get_interrupt_thresholds( VL53L0X_DeviceModes device_mode, 
01061             TFP1616 *p_threshold_low, TFP1616 *p_threshold_high);
01062 
01063     /**
01064      * @brief Gets the (on/off) state of all sequence steps.
01065      *
01066      * @par Function Description
01067      * This function retrieves the state of all sequence step in the scheduler.
01068      *
01069      * @note This function Accesses the device
01070      * 
01071      * @return  VL53L0X_Sequence_Steps_t      Struct containing result.
01072      *                                          Also check class Field "ErrState"        
01073      */
01074     VL53L0X_Sequence_Steps_t Get_sequence_step_enables();
01075 
01076     /**
01077      * @brief Sets the (on/off) state of a requested sequence step.
01078      *
01079      * @par Function Description
01080      * This function enables/disables a requested sequence step.
01081      *
01082      * @note This function Accesses the device
01083      * 
01084      * @param   sequence_step_id             Sequence step identifier.
01085      * @param   sequence_step_enabled          Demanded state {0=Off,1=On}
01086      *                                       is enabled.
01087      * @return  None; instead check class Field "ErrState"        
01088      * @return  VL53L0X_ERROR_INVALID_PARAMS  Error SequenceStepId parameter not
01089      *                                       supported.   
01090      */
01091     void Set_sequence_step_enable(VL53L0X_SequenceStepId sequence_step_id, 
01092                                   uint8_t sequence_step_enabled);
01093 
01094     /**
01095      * @brief  Gets the fraction enable parameter indicating the resolution of
01096      * range measurements.
01097      *
01098      * @par Function Description
01099      * Gets the fraction enable state, which translates to the resolution of
01100      * range measurements as follows :Enabled:=0.25mm resolution,
01101      * Not Enabled:=1mm resolution.
01102      *
01103      * @note This function Accesses the device
01104      * 
01105      * @param   p_enabled           Output Parameter reporting the fraction enable state.
01106      *
01107      * @return  None; instead check class Field "ErrState"                         
01108      */
01109     void Get_fraction_enable( uint8_t *p_enabled);
01110 
01111     /**
01112      * @brief  Sets the resolution of range measurements.
01113      * @par Function Description
01114      * Set resolution of range measurements to either 0.25mm if
01115      * fraction enabled or 1mm if not enabled.
01116      *
01117      * @note This function Accesses the device
01118      * 
01119      * @param   enable            Enable high resolution
01120      *
01121      * @return  None; instead check class Field "ErrState"              
01122      */
01123     void Set_range_fraction_enable(  uint8_t enable);
01124 
01125     /**
01126     * @brief Return the VL53L0X Device Implementation Version
01127     *
01128     * @note This function doesn't access to the device
01129     *
01130     * @param   p_version              Pointer to current Device Implementation Version
01131     * @return  None; instead check class Field "ErrState" 
01132     */
01133     void Get_version(VL53L0X_Version_t *p_version);
01134 
01135     /**
01136      * @brief Reads the Product Revision for a for given Device
01137      * This function can be used to distinguish cut1.0 from cut1.1.
01138      *
01139      * @note This function Access to the device
01140      * 
01141      * @param   p_product_revision_major  Pointer to Product Revision Major
01142      * for a given Device
01143      * @param   p_product_revision_minor  Pointer to Product Revision Minor
01144      * for a given Device
01145      * @return  None; instead check class Field "ErrState"  
01146      */
01147     void Get_product_revision(  uint8_t *p_product_revision_major, 
01148             uint8_t *p_product_revision_minor);
01149 
01150     /**
01151      * @brief  Retrieve current device parameters
01152      * @par Function Description
01153      * Get actual parameters of the device
01154      * @li Then start ranging operation.
01155      *
01156      * @note This function Access to the device
01157      * 
01158      * @return   VL53L0X_DeviceParams_t     Current device parameters.
01159      *                      Also check class Field "ErrState" 
01160      */
01161     VL53L0X_DeviceParams_t Get_device_parameters();
01162 
01163     /**
01164      * @brief Return the Device Specification Version used for the current
01165      * implementation.
01166      *
01167      * @note This function doesn't access to the device
01168      *
01169      * @param   p_Device_spec_version       Pointer to current Device Specification Version
01170      * @return  None; instead check class Field "ErrState"    
01171      */
01172     void Get_Device_spec_version(VL53L0X_Version_t  *p_Device_spec_version);
01173 
01174     /**
01175      * @brief Reads the internal state of the Device for a given Device
01176      *
01177      * @note This function doesn't access to the device
01178      * 
01179      * @param   p_Device_state             Pointer to current state of the Device for a
01180      * given Device
01181      * @return  None; instead check class Field "ErrState" 
01182      */
01183     void Get_Device_state(VL53L0X_State *p_Device_state);
01184 
01185     /* New Strategy, Moving to a global variable to track error states: */
01186     VL53L0X_Error  ErrState;
01187     
01188     VL53L0X_State Current_State ;  /*!< Current state of this device; use Set_Current_State to change it  */
01189 
01190     /*** End High level API ***/
01191 private:
01192     void Wait_read_strobe();
01193 
01194     void Check_and_load_interrupt_settings( uint8_t start_not_stopflag);
01195 
01196     uint32_t Decode_timeout(uint16_t encoded_timeout);
01197 
01198     uint32_t Calc_timeout_us(uint16_t timeout_period_mclks,
01199                                      uint8_t vcsel_period_pclks);
01200 
01201     void Poll_Measure_Completion(); // was Measurement_poll_for_completion
01202 
01203     void Load_tuning_settings( uint8_t *p_tuning_setting_buffer );
01204 
01205     void Get_Device_range_status( uint8_t device_range_status,
01206             TFP1616 signal_rate, uint16_t effective_SPAD_rtn_count,
01207             TRangeResults *p_ranging_results,
01208             uint8_t *p_Device_range_status);
01209 
01210     void Calc_sigma_estimate(
01211             TRangeResults *p_ranging_results,
01212             TFP1616 *p_sigma_estimate, uint32_t *p_dmax_mm);
01213             
01214     uint32_t Calc_timeout_mclks(uint32_t timeout_period_us,
01215                                         uint8_t vcsel_period_pclks);
01216     
01217     void Calc_dmax( TFP1616 total_SIG_rate_mcps,
01218         TFP1616 total_corr_SIG_rate_mcps,
01219         TFP1616 pw_mult, uint32_t sigma_estimate_p1,
01220         TFP1616 sigma_estimate_p2,  uint32_t peak_vcsel_duration_us,
01221         uint32_t *pd_max_mm);
01222         
01223     uint16_t Encode_timeout(uint32_t timeout_macro_clks);
01224 
01225     /* api_calibration.h functions */
01226     void VL53L0X_Apply_Offset_Cal();
01227     
01228     void Perf_vhv_calibration( uint8_t *p_vhv_settings, 
01229             const uint8_t get_data_enable,  const uint8_t restore_config);
01230             
01231     void Perf_single_Ref_calibration( uint8_t vhv_init_byte );
01232     
01233     void Ref_calibration_io( uint8_t read_not_write,
01234             uint8_t vhv_settings, uint8_t phase_cal,
01235             uint8_t *p_vhv_settings, uint8_t *p_phase_cal,
01236             const uint8_t vhv_enable, const uint8_t phase_enable);
01237             
01238     void Perf_phase_calibration( uint8_t *p_phase_cal, const uint8_t get_data_enable,
01239             const uint8_t restore_config);
01240             
01241     void Enable_Ref_SPADS(uint8_t aperture_SPADS, uint8_t good_SPAD_array[],
01242             uint8_t SPAD_array[], uint32_t size, uint32_t start,
01243             uint32_t offset, uint32_t SPAD_count,  uint32_t *p_last_SPAD);
01244                                    
01245     void Get_Next_Good_SPAD(uint8_t good_SPAD_array[], uint32_t size,
01246                             uint32_t curr, int32_t *p_next);
01247                             
01248     void Enable_SPAD_bit( uint8_t SPAD_array[], uint32_t size, uint32_t SPAD_index);
01249                                     
01250     void Get_Ref_SPAD_map( uint8_t *p_Ref_SPAD_array );
01251     
01252     uint16_t Get_Perf_Ref_SIG_measurement();
01253     
01254 
01255     /* Read function of the ID device */
01256     virtual int read_id(uint8_t *id);
01257     
01258     void Wait_Measurement_Ready();
01259 
01260     void Wait_Stop_Completed();
01261 
01262     /**
01263      * @brief execute delay in all polling API call
01264      *
01265      * A typical multi-thread or RTOs implementation is to sleep the task for some 
01266      * 5ms (with 100Hz max rate faster polling is not needed)
01267      * if nothing specific is need you can define it as an empty/void macro
01268      * @code
01269      * #define VL53L0X_PollingDelay(...) (void)0
01270      * @endcode
01271      * 
01272      * @return  None; instead check class Field "ErrState"    
01273      */
01274     void Polling_delay();   /* usually best implemented as a real function */
01275 
01276     ///////////////////////////////////////////////////////////////////////////////////////////////////////
01277     //Added functions                                                                                    //
01278     ///////////////////////////////////////////////////////////////////////////////////////////////////////
01279 
01280     /**
01281      * @brief  Cycle Power to Device
01282      *
01283      * @return ErrState - ErrState 0 = ok, 1 = error
01284      */
01285     int32_t Cycle_power(void);
01286 
01287     void count_enabled_SPADS(uint8_t SPAD_array[],  uint32_t byte_count, 
01288        uint32_t max_SPADS, uint32_t *p_total_SPADS_enabled, uint8_t *p_is_aperture);
01289 
01290         /**
01291      * @brief Gets the name of a given sequence step.
01292      *
01293      * @par Function Description
01294      * This function retrieves the name of sequence steps corresponding to
01295      * SequenceStepId.
01296      *
01297      * @note This function doesn't Accesses the device
01298      *
01299      * @param   sequence_step_id               Sequence step identifier.
01300      * @param   p_sequence_steps_string         Pointer to Info string
01301      *
01302      * @return  None; instead check class Field "ErrState"        
01303      */
01304     void Get_sequence_steps_info(VL53L0X_SequenceStepId sequence_step_id,
01305             char *p_sequence_steps_string);
01306 
01307     /**
01308     * @brief Get the frequency of the timer used for ranging results time stamps
01309     *
01310     * @param[out] p_timer_freq_hz : pointer for timer frequency
01311     *
01312     * @return ErrState : 0 = ok, 1 = error
01313     */
01314     int32_t Get_timer_frequency(int32_t *p_timer_freq_hz);
01315 
01316     /**
01317     * @brief Get the timer value in units of timer_freq_hz (see Get_timestamp_frequency())
01318     *
01319     * @param[out] p_timer_count : pointer for timer count value
01320     *
01321     * @return ErrState : 0 = ok, 1 = error
01322     */
01323     int32_t Get_timer_value(int32_t *p_timer_count);
01324 
01325     /**
01326     * @brief Configure ranging interrupt reported to system
01327     *
01328     * @note This function is not Implemented
01329     * 
01330     * @param   interrupt_mask         Mask of interrupt to Enable/disable
01331     *  (0:interrupt disabled or 1: interrupt enabled)
01332     * @return  VL53L0X_ERROR_NOT_IMPLEMENTED   Not implemented
01333     */
01334     void Enable_interrupt_mask(uint32_t interrupt_mask);
01335 
01336     /**
01337      * @brief  Get Dmax Calibration Parameters for a given device
01338      *
01339      * @note This function Access to the device
01340      * 
01341      * @param   p_range_milli_meter        Pointer to Calibration Distance
01342      * @param   p_SIG_rate_rtn_MHz   Pointer to Signal rate return
01343      * @return  None; instead check class Field "ErrState"   
01344      */
01345     void Get_dmax_cal_parameters(uint16_t *p_range_milli_meter,
01346              TFP1616 *p_SIG_rate_rtn_MHz);
01347 
01348     /**
01349     * @brief   Set Dmax Calibration Parameters for a given device
01350     * When one of the parameter is zero, this function will get parameter
01351     * from NVM.
01352     * @note This function doesn't Access to the device
01353     * 
01354     * @param   range_milli_meter        Calibration Distance
01355     * @param   signal_rate_rtn_MHz   Signal rate return read at CalDistance
01356     * @return  None; instead check class Field "ErrState"  
01357      
01358     */
01359     void Get_dmax_cal_parameters(uint16_t range_milli_meter, 
01360             TFP1616 signal_rate_rtn_MHz);
01361 
01362     /**
01363     * @brief Retrieve the measurements from device for a given setup
01364     *
01365     * @par Function Description
01366     * Get data from last successful Histogram measurement
01367     * @warning USER should take care about  @a VL53L0X_GetNumberOfROIZones()
01368     * before get data.
01369     * Device will fill a NumberOfROIZones times the corresponding data structure
01370     * used in the measurement function.
01371     *
01372     * @note This function is not Implemented
01373     * 
01374     * @param   p_histogram_measurement_data   Pointer to the histogram data structure.
01375     * @return  VL53L0X_ERROR_NOT_IMPLEMENTED   Not implemented
01376     */
01377     void Get_histogram_measurement_data(
01378             VL53L0X_HistogramMeasurementData_t *p_histogram_measurement_data);
01379 
01380     /**
01381     * @brief  Get current new device mode
01382     * @par Function Description
01383     * Get current Histogram mode of a Device
01384     *
01385     * @note This function doesn't Access to the device
01386     * 
01387     * @param   p_histogram_mode        Pointer to current Histogram Mode value
01388     *                                Valid values are:
01389     *                                VL53L0X_HISTOGRAMMODE_DISABLED
01390     *                                VL53L0X_DEVICEMODE_SINGLE_HISTOGRAM
01391     *                                VL53L0X_HISTOGRAMMODE_REFERENCE_ONLY
01392     *                                VL53L0X_HISTOGRAMMODE_RETURN_ONLY
01393     *                                VL53L0X_HISTOGRAMMODE_BOTH
01394     * @return  None; instead check class Field "ErrState" 
01395     */
01396     void Get_histogram_mode(
01397             VL53L0X_HistogramModes *p_histogram_mode);
01398 
01399     /**
01400      * @brief  Set a new Histogram mode
01401      * @par Function Description
01402      * Set device to a new Histogram mode
01403      *
01404      * @note This function doesn't Access to the device
01405      * 
01406      * @param   histogram_mode         New device mode to apply
01407      *                                Valid values are:
01408      *                                VL53L0X_HISTOGRAMMODE_DISABLED
01409      *                                VL53L0X_DEVICEMODE_SINGLE_HISTOGRAM
01410      *                                VL53L0X_HISTOGRAMMODE_REFERENCE_ONLY
01411      *                                VL53L0X_HISTOGRAMMODE_RETURN_ONLY
01412      *                                VL53L0X_HISTOGRAMMODE_BOTH
01413      *
01414      * @return  None; instead check class Field "ErrState"               
01415      * @return  VL53L0X_ERROR_MODE_NOT_SUPPORTED     This error occurs when
01416      * HistogramMode is not in the supported list
01417      */
01418     void Set_histogram_mode(
01419             VL53L0X_HistogramModes histogram_mode);
01420 
01421     /**
01422      * @brief Get the linearity corrective gain
01423      *
01424      * @par Function Description
01425      * Should only be used after a successful call to @a VL53L0X_DataInit to backup
01426      * device NVM value
01427      *
01428      * @note This function Access to the device
01429      * 
01430      * @param   p_linearity_corrective_gain           Pointer to the linearity
01431      * corrective gain in x1000
01432      * if value is 1000 then no modification is applied.
01433      * @return  None; instead check class Field "ErrState"    
01434      */
01435     void Get_linearity_corrective_gain(
01436             uint16_t *p_linearity_corrective_gain);
01437 
01438     /**
01439      * Set the linearity corrective gain
01440      *
01441      * @note This function Access to the device
01442      * 
01443      * @param   linearity_corrective_gain            Linearity corrective
01444      * gain in x1000
01445      * if value is 1000 then no modification is applied.
01446      * @return  None; instead check class Field "ErrState"    
01447      */
01448     void Set_linearity_corrective_gain(
01449             int16_t linearity_corrective_gain);
01450 
01451     /**
01452      * @brief Get the Maximum number of ROI Zones managed by the Device
01453      *
01454      * @par Function Description
01455      * Get Maximum number of ROI Zones managed by the Device.
01456      *
01457      * @note This function doesn't Access to the device
01458      * 
01459      * @param   p_max_number_of_roi_zones   Pointer to the Maximum Number
01460      *  of ROI Zones value.
01461      * @return  None; instead check class Field "ErrState"  
01462      */
01463     void Get_max_number_of_roi_zones(
01464             uint8_t *p_max_number_of_roi_zones);
01465 
01466     /**
01467      * @brief Retrieve the Reference Signal after a measurements
01468      *
01469      * @par Function Description
01470      * Get Reference Signal from last successful Ranging measurement
01471      * This function return a valid value after that you call the
01472      * @a VL53L0X_GetRangingMeasurementData().
01473      *
01474      * @note This function Access to the device
01475      * 
01476      * @param   p_measurement_Ref_signal    Pointer to the Ref Signal to fill up.
01477      * @return  None; instead check class Field "ErrState" 
01478      */
01479     void Get_Measurement_Ref_signal(
01480             TFP1616 *p_measurement_Ref_signal);
01481 
01482     /**
01483      * @brief  Get the number of the check limit managed by a given Device
01484      *
01485      * @par Function Description
01486      * This function give the number of the check limit managed by the Device
01487      *
01488      * @note This function doesn't Access to the device
01489      *
01490      * @param   p_number_of_limit_check           Pointer to the number of check limit.
01491      * @return  None; instead check class Field "ErrState" 
01492      */
01493     void Get_number_of_limit_check(
01494                        uint16_t *p_number_of_limit_check);
01495 
01496     /**
01497      * @brief Get the number of ROI Zones managed by the Device
01498      *
01499      * @par Function Description
01500      * Get number of ROI Zones managed by the Device
01501      * USER should take care about  @a VL53L0X_GetNumberOfROIZones()
01502      * before get data after a perform measurement.
01503      * Device will fill a NumberOfROIZones times the corresponding data
01504      * structure used in the measurement function.
01505      *
01506      * @note This function doesn't Access to the device
01507      *
01508      * 
01509      * @param   p_number_of_roi_zones     Pointer to the Number of ROI Zones value.
01510      * @return  None; instead check class Field "ErrState" 
01511      */
01512     void Get_number_of_roi_zones(
01513             uint8_t *p_number_of_roi_zones);
01514 
01515     /**
01516      * @brief Set the number of ROI Zones to be used for a specific Device
01517      *
01518      * @par Function Description
01519      * Set the number of ROI Zones to be used for a specific Device.
01520      * The programmed value should be less than the max number of ROI Zones given
01521      * with @a VL53L0X_GetMaxNumberOfROIZones().
01522      * This version of API manages only one zone.
01523      * 
01524      * @param   number_of_roi_zones      Number of ROI Zones to be used 
01525      * @return  None; instead check class Field "ErrState"         
01526      * @return  VL53L0X_ERROR_INVALID_PARAMS   This error is returned if NumberOfROIZones != 1
01527      */
01528     void Set_number_of_roi_zones(  uint8_t number_of_roi_zones);
01529 
01530     /**
01531      * @brief Gets number of sequence steps managed by the API.
01532      *
01533      * @par Function Description
01534      * This function retrieves the number of sequence steps currently managed
01535      * by the API
01536      *
01537      * @note This function Accesses the device
01538      * 
01539      * @param   p_number_of_sequence_steps       Out parameter reporting the number of
01540      *                                       sequence steps.
01541      * @return  None; instead check class Field "ErrState"        
01542      */
01543     void Get_number_of_sequence_steps( uint8_t *p_number_of_sequence_steps);
01544     /**
01545      * @brief Get the power mode for a given Device
01546      *
01547      * @note This function Access to the device
01548      * 
01549      * @param   p_power_mode            Pointer to the current value of the power
01550      * mode. see ::VL53L0X_PowerModes
01551      *                                Valid values are:
01552      *                                VL53L0X_POWERMODE_STANDBY_LEVEL1,
01553      *                                VL53L0X_POWERMODE_IDLE_LEVEL1
01554      * @return  None; instead check class Field "ErrState"
01555      */
01556     void Get_power_mode( VL53L0X_PowerModes *p_power_mode);
01557 
01558     /**
01559      * @brief Set the power mode for a given Device
01560      * The power mode can be Standby or Idle. Different level of both Standby and
01561      * Idle can exists.
01562      * This function should not be used when device is in Ranging state.
01563      *
01564      * @note This function Access to the device
01565      * 
01566      * @param   power_mode             The value of the power mode to set.
01567      * see ::VL53L0X_PowerModes
01568      *                                Valid values are:
01569      *                                VL53L0X_POWERMODE_STANDBY_LEVEL1,
01570      *                                VL53L0X_POWERMODE_IDLE_LEVEL1
01571      * @return  None; instead check class Field "ErrState"              
01572      * @return  VL53L0X_ERROR_MODE_NOT_SUPPORTED    This error occurs when PowerMode
01573      * is not in the supported list
01574      */
01575     void Set_power_mode(VL53L0X_PowerModes power_mode);
01576 
01577     /**
01578      * @brief Retrieves SPAD configuration
01579      *
01580      * @par Function Description
01581      * This function retrieves the current number of applied reference SPADS
01582      * and also their type : Aperture or Non-Aperture.
01583      *
01584      * @note This function Access to the device
01585      * 
01586      * @param   p_SPAD_count                 Number ref SPAD Count
01587      * @param   p_is_aperture_SPADS              Reports if SPADS are of type
01588      *                                       aperture or non-aperture.
01589      *                                       1:=aperture, 0:=Non-Aperture
01590      * @return  None; instead check class Field "ErrState"        
01591      * @return  VL53L0X_ERROR_REF_SPAD_INIT   Error in the in the reference
01592      *                                       SPAD configuration.
01593      */
01594     void wrapped_Get_Reference_SPADS(
01595             uint32_t *p_SPAD_count, uint8_t *p_is_aperture_SPADS);
01596 
01597     /**
01598      * @brief Gets the (on/off) state of a requested sequence step.
01599      *
01600      * @par Function Description
01601      * This function retrieves the state of a requested sequence step, i.e. on/off.
01602      *
01603      * @note This function Accesses the device
01604      *
01605      * @param   sequence_step_id         Sequence step identifier.
01606      * @param   p_sequence_step_enabled   Out parameter reporting if the sequence step
01607      *                                 is enabled {0=Off,1=On}.
01608      * @return  None; instead check class Field "ErrState"        
01609      * @return  VL53L0X_ERROR_INVALID_PARAMS  Error SequenceStepId parameter not
01610      *                                        supported.
01611      */
01612     void Get_sequence_step_enable(
01613             VL53L0X_SequenceStepId sequence_step_id, uint8_t *p_sequence_step_enabled);
01614 
01615 
01616     /**
01617      * @brief Gets the timeout of a requested sequence step.
01618      *
01619      * @par Function Description
01620      * This function retrieves the timeout of a requested sequence step.
01621      *
01622      * @note This function Accesses the device
01623      *
01624      * @param   sequence_step_id               Sequence step identifier.
01625      * @param   p_time_out_milli_secs            Timeout value.
01626      * @return  None; instead check class Field "ErrState"        
01627      * @return  VL53L0X_ERROR_INVALID_PARAMS  Error SequenceStepId parameter not
01628      *                                       supported.
01629      */
01630     void Get_Sequence_Step_Timeout(VL53L0X_SequenceStepId sequence_step_id,
01631                                             uint32_t *p_time_out_micro_secs);
01632 
01633     /**
01634      * @brief Sets the timeout of a requested sequence step.
01635      *
01636      * @par Function Description
01637      * This function sets the timeout of a requested sequence step.
01638      *
01639      * @note This function Accesses the device
01640      * 
01641      * @param   sequence_step_id               Sequence step identifier.
01642      * @param   time_out_milli_secs             Demanded timeout
01643      * @return  None; instead check class Field "ErrState"        
01644      * @return  VL53L0X_ERROR_INVALID_PARAMS  Error SequenceStepId parameter not
01645      *                                       supported.
01646      */
01647     void Set_Sequence_Step_Timeout(VL53L0X_SequenceStepId sequence_step_id,
01648                                             uint32_t timeout_micro_secs);
01649 
01650     /**
01651     * @brief  Get the current SPAD Ambient Damper Factor value
01652     *
01653     * @par Function Description
01654     * This function get the SPAD Ambient Damper Factor value
01655     *
01656     * @note This function Access to the device
01657     * 
01658     * @param   p_SPAD_ambient_damper_factor      Pointer to programmed SPAD Ambient
01659     * Damper Factor value
01660     * @return  None; instead check class Field "ErrState"         
01661     */
01662     void Get_SPAD_ambient_damper_factor(
01663             uint16_t *p_SPAD_ambient_damper_factor);
01664     /**
01665     * @brief  Set the SPAD Ambient Damper Factor value
01666     *
01667     * @par Function Description
01668     * This function set the SPAD Ambient Damper Factor value
01669     *
01670     * @note This function Access to the device
01671     * 
01672     * @param   SPAD_ambient_damper_factor       SPAD Ambient Damper Factor value
01673     * @return  None; instead check class Field "ErrState"         
01674     */
01675     void Set_SPAD_ambient_damper_factor(
01676             uint16_t SPAD_ambient_damper_factor);
01677 
01678     /**
01679      * @brief  Get the current SPAD Ambient Damper Threshold value
01680      *
01681      * @par Function Description
01682      * This function get the SPAD Ambient Damper Threshold value
01683      *
01684      * @note This function Access to the device
01685      * 
01686      * @param   p_SPAD_ambient_damper_threshold   Pointer to programmed
01687      *                                        SPAD Ambient Damper Threshold value
01688      * @return  None; instead check class Field "ErrState"         
01689      */
01690     void Get_SPAD_ambient_damper_threshold(
01691             uint16_t *p_SPAD_ambient_damper_threshold);
01692 
01693     /**
01694      * @brief  Set the SPAD Ambient Damper Threshold value
01695      *
01696      * @par Function Description
01697      * This function set the SPAD Ambient Damper Threshold value
01698      *
01699      * @note This function Access to the device
01700      * 
01701      * @param   SPAD_ambient_damper_threshold    SPAD Ambient Damper Threshold value
01702      * @return  None; instead check class Field "ErrState"         
01703      */
01704     void Set_SPAD_ambient_damper_threshold(
01705             uint16_t SPAD_ambient_damper_threshold);
01706 
01707     /**
01708      * @brief Get the maximal distance for actual setup
01709      * @par Function Description
01710      * Device must be initialized through @a VL53L0X_SetParameters() prior calling
01711      * this function.
01712      *
01713      * Any range value more than the value returned is to be considered as
01714      * "no target detected" or
01715      * "no target in detectable range"\n
01716      * @warning The maximal distance depends on the setup
01717      *
01718      * @note This function is not Implemented
01719      * 
01720      * @param   p_upper_limit_milli_meter   The maximal range limit for actual setup
01721      * (in millimeter)
01722      * @return  VL53L0X_ERROR_NOT_IMPLEMENTED        Not implemented
01723      */
01724     void Get_upper_limit_milli_meter(
01725             uint16_t *p_upper_limit_milli_meter);
01726 
01727     /**
01728     * @brief Get the tuning settings pointer and the internal external switch
01729     * value.
01730     *
01731     * This function is used to get the Tuning settings buffer pointer and the
01732     * value.
01733     * of the switch to select either external or internal tuning settings.
01734     *
01735     * @note This function Access to the device
01736     * 
01737     * @param   pp_tuning_setting_buffer      Pointer to tuning settings buffer.
01738     * @param   p_use_internal_tuning_settings Pointer to store Use internal tuning
01739     *                                     settings value.
01740     * @return  None; instead check class Field "ErrState"      
01741     */
01742     void Get_tuning_setting_buffer( uint8_t **pp_tuning_setting_buffer, 
01743                   uint8_t *p_use_internal_tuning_settings);
01744 
01745     /**
01746      * @brief Set the tuning settings pointer
01747      *
01748      * This function is used to specify the Tuning settings buffer to be used
01749      * for a given device. The buffer contains all the necessary data to permit
01750      * the API to write tuning settings.
01751      * This function permit to force the usage of either external or internal
01752      * tuning settings.
01753      *
01754      * @note This function Access to the device
01755      * 
01756      * @param   p_tuning_setting_buffer            Pointer to tuning settings buffer.
01757      * @param   use_internal_tuning_settings       Use internal tuning settings value.
01758      * @return  None; instead check class Field "ErrState" 
01759      */
01760     void Set_tuning_setting_buffer(  uint8_t *p_tuning_setting_buffer, 
01761             uint8_t use_internal_tuning_settings);
01762 
01763     /**
01764      * @defgroup VL53L0X_registerAccess_group Device Register Access Functions
01765      * @brief    Device Register Access Functions
01766      *  @{
01767      */
01768 
01769     /**
01770      * Lock comms interface to serialize all commands to a shared I2C interface for a specific device
01771      * 
01772      * @return  None; instead check class Field "ErrState"    
01773      */
01774     void VL53L0X_lock_sequence_access();
01775 
01776     /**
01777      * Unlock comms interface to serialize all commands to a shared I2C interface for a specific device
01778      * 
01779      * @return  None; instead check class Field "ErrState"    
01780      */
01781     void VL53L0X_unlock_sequence_access();
01782 
01783     /**
01784      * @brief  Prepare device for operation
01785      * @par Function Description
01786      * Update device with provided parameters
01787      * @li Then start ranging operation.
01788      *
01789      * @note This function Access to the device
01790      * 
01791      * @param   pDeviceParameters     Pointer to store current device parameters.
01792      * @return  None; instead check class Field "ErrState" 
01793      */
01794     void VL53L0x_set_device_parameters(
01795             const VL53L0X_DeviceParams_t *pDeviceParameters);
01796 
01797     /**
01798      * Set Group parameter Hold state
01799      *
01800      * @par Function Description
01801      * Set or remove device internal group parameter hold
01802      *
01803      * @note This function is not Implemented
01804      * 
01805      * @param   group_param_hold   Group parameter Hold state to be set (on/off)
01806      * @return  VL53L0X_ERROR_NOT_IMPLEMENTED        Not implemented
01807      */
01808     void Set_group_param_hold(uint8_t group_param_hold);
01809 
01810     /**
01811      * @brief Wait for device ready for a new measurement command.
01812      * Blocking function.
01813      *
01814      * @note This function is not Implemented
01815      * 
01816      * @param   max_loop    Max Number of polling loop (timeout).
01817      * @return  VL53L0X_ERROR_NOT_IMPLEMENTED   Not implemented
01818      */
01819     void Wait_device_ready_for_new_measurement( uint32_t max_loop);
01820 
01821 private:
01822 /******************************************************************************/
01823 /****************** Write and read functions from I2C *************************/
01824 /******************************************************************************/
01825     uint32_t Get_NVM_DWord(uint8_t NVM_Address)
01826     uint16_t Get_NVM_Word (uint8_t NVM_Address)
01827     uint8_t  Get_NVM_Byte (uint8_t NVM_Address)
01828 
01829     /**
01830      * Thread safe Update (read/modify/write) single byte register
01831      *
01832      * Final_reg = (Initial_reg & and_mask) | or_mask
01833      *
01834      * @param   index      The register index
01835      * @param   and_mask    8 bit and data
01836      * @param   or_mask     8 bit or data
01837      * @return  None; instead check class Field "ErrState"    
01838      */
01839     void Register_BitMask(uint8_t index, uint8_t and_mask, uint8_t or_mask);
01840 
01841     /* Write and read functions from I2C */
01842     /**
01843      * Write single byte register
01844      * 
01845      * @param   index     The register index
01846      * @param   data      8 bit register data
01847      * @return  None; instead check class Field "ErrState"    
01848      */
01849     void Write_Byte( uint8_t index, uint8_t data);
01850 
01851     /**
01852      * Write word register
01853      * 
01854      * @param   index     The register index
01855      * @param   data      16 bit register data
01856      * @return  None; instead check class Field "ErrState"    
01857      */
01858     void Write_Word( uint8_t index, uint16_t data);
01859     /**
01860      * Write double word (4 byte) register
01861      * 
01862      * @param   index     The register index
01863      * @param   data      32 bit register data
01864      * @return  None; instead check class Field "ErrState"    
01865      */
01866     void Write_DWord( uint8_t index, uint32_t data);
01867 
01868     /**
01869      * Read single byte register
01870      * 
01871      * @param   index     The register index
01872      * @return  uint8_t  Returned 8 bit data; also check class Field "ErrState"    
01873      */
01874     uint8_t Read_Byte(uint8_t index);
01875     
01876     /**
01877      * Read word (2byte) register
01878      * 
01879      * @param   index     The register index
01880      * @return  uint16_t  Returned 16 bit data; also check class Field "ErrState"    
01881      */
01882     uint16_t Read_Word( uint8_t index);
01883     /**
01884      * Read dword (4byte) register
01885      * 
01886      * @param   index     The register index
01887      * @return  uint32_t  Returned 32 bit data; also check class Field "ErrState"    
01888      */
01889     uint32_t Read_DWord( uint8_t index);
01890     
01891     /**
01892      * @brief  Writes a buffer towards the I2C peripheral device.
01893      * 
01894      * @param  RegisterAddr specifies the internal address register
01895      * @param  p_data pointer to the byte-array data to send
01896      *         where to start writing to (must be correctly masked).
01897      * @param  NumByteToWrite number of bytes to be written.
01898      * @retval VL53L0X_OK  if  ok,
01899      * @retval VL53L0X_ERROR_CONTROL_INTERFACE  if  an  I2C error has occured, or
01900      * @retval VL53L0X_ERROR_I2C_BUF_OVERFLOW on temporary buffer overflow (i.e. NumByteToWrite was too high)
01901      * @note   On some devices if NumByteToWrite is greater
01902      *         than one, the RegisterAddr must be masked correctly!
01903      */
01904     void I2c_Write(uint8_t RegisterAddr, uint8_t *p_data, uint16_t NumByteToWrite);
01905 
01906     /**
01907      * @brief  Reads a buffer from the I2C peripheral device.
01908      * 
01909      * @param  RegisterAddr specifies the internal address register
01910      * @param  p_data pointer to the byte-array data to receive
01911      *         where to start writing to (must be correctly masked).
01912      * @param  NumByteToRead number of bytes to be read; maximum VL53L0X_MAX_I2C_XFER_SIZE
01913      * @retval 0 if ok,
01914      * @retval -1 if an I2C error has occured
01915      * @note   On some devices if NumByteToRead is greater
01916      *         than one, the RegisterAddr must be masked correctly!
01917      */
01918     void I2c_Read(uint8_t RegisterAddr, uint8_t *p_data, uint16_t NumByteToRead);
01919 
01920     /* IO Device */
01921     I2C *_dev_i2c;
01922 
01923     /*!< i2c device address user specific field */
01924     uint8_t   I2cDevAddr;     
01925 
01926 private:
01927     uint8_t Is_ApertureSPAD(uint32_t SPAD_index);
01928     
01929     void Reverse_bytes(uint8_t *data, uint32_t size);
01930 
01931     void Range_meas_int_continuous_mode(void (*fptr)(void));
01932 
01933     uint32_t ISQRT(uint32_t num);
01934 
01935     uint32_t Quadrature_sum(uint32_t a, uint32_t b);
01936     
01937     void Set_Current_State( VL53L0X_State NewState )
01938     {  if (ErrState == VL53L0X_OK) { Current_State  = NewState; }
01939           else { Current_State  = VL53L0X_STATE_ERROR; }
01940     } // end of Set_Current_State
01941     
01942     // NB: it seems that the state SequenceConfig is only written to never read from ;)
01943     void Set_SequenceConfig ( uint8_t NewSequenceConfig ) 
01944     { Write_Byte(REG_SYSTEM_SEQUENCE_CONFIG, NewSequenceConfig);
01945       if (ErrState == VL53L0X_OK) { SequenceConfig = NewSequenceConfig; } } 
01946 
01947 private:
01948     static const unsigned int TEMP_BUF_SIZE = 64;
01949 
01950     /* Digital out pin */
01951     DigitalOut *_gpio0;
01952     
01953     /* Measure detection IRQ */
01954     InterruptIn *_gpio1Int;
01955     
01956     /**
01957      * @brief was VL53L0X_Dev_t, Generic device information
01958      *
01959      * merged with VL53L0X_DevData_t that embeds ST FlightSense devdata
01960      * VL53L0X Device device ST private data structure \n
01961      * End user should never access any of these field directly \n
01962      */
01963     VL53L0X_DMaxData_t DMaxData;
01964     /*!< Dmax Data */
01965     int32_t  Last_Offset_Cal_um;
01966     /*!< backed up Offset_Cal value found last time, but never used !!!*/
01967     int32_t  NVM_Offset_Cal_um;
01968     /*!< backed up NVM value representing additional offset adjustment */
01969     VL53L0X_DeviceParams_t CurrParams;
01970     /*!< Current Device Parameter */
01971     TRangeResults LastRangeMeasure;
01972     /*!< Ranging Data */
01973     VL53L0X_HistogramMeasurementData_t LastHistogramMeasure;
01974     /*!< Histogram Data */
01975     VL53L0X_SPADData_t SPADData;
01976     /*!< SPAD Data */
01977     uint8_t SequenceConfig;
01978     /*!< Internal value for the sequence config */
01979     uint8_t RangeFractionalEnable;
01980     /*!< Enable/Disable fractional part of ranging data */
01981     VL53L0X_PowerModes PowerMode;
01982     /*!< Current Power Mode  */
01983     uint16_t SigmaEstRefArray ;
01984     /*!< Reference array sigma value in 1/100th of [mm] e.g. 100 = 1mm */
01985     uint16_t SigmaEstEffPulseWidth ;
01986     /*!< Effective Pulse width for sigma estimate in 1/100th of ns e.g. 900 = 9.0ns */
01987     uint16_t SigmaEstEffAmbWidth ;
01988     /*!< Effective Ambient width for sigma estimate in 1/100th of ns
01989     * e.g. 500 = 5.0ns */
01990     uint8_t StopVariable;
01991     /*!< StopVariable used during the stop sequence */
01992     uint16_t targetRefRate;
01993     /*!< Target Ambient Rate for Ref SPAD management */
01994     TFP1616 SigmaEstimate;
01995     /*!< Sigma Estimate - based on ambient & VCSEL rates and signal_total_events */
01996     TFP1616 SignalEstimate;
01997     /*!< Signal Estimate - based on ambient & VCSEL rates and cross talk */
01998     TFP1616 LastSignalRefMcps;
01999     /*!< Latest Signal ref in Mcps */
02000     uint8_t *pTuningSettingsPointer;
02001     /*!< Pointer for Tuning Settings table */
02002     uint8_t UseInternalTuningSettings;
02003     /*!< Indicate if we use  Tuning Settings table */
02004     uint16_t LinearityCorrectiveGain;
02005     /*!< Linearity Corrective Gain value in x1000 */
02006     uint16_t DmaxCalRangeMilliMeter;
02007     /*!< Dmax Calibration Range millimeter */
02008     TFP1616 DmaxCalSignalRateRtnMHz;
02009     /*!< Dmax Calibration Signal Rate Return MHz */    
02010 };
02011 
02012 #endif /* _VL53L0X_CLASS_H_ */