ST / VL53L1X

Dependencies:   X_NUCLEO_COMMON ST_INTERFACES

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers vl53l1x_class.h Source File

vl53l1x_class.h

00001 /*******************************************************************************
00002  * @file    vl53l1x_class.h
00003  * @author  JS
00004  * @version V0.0.1
00005  * @date    15-January-2019
00006  * @brief   Header file for VL53L1 sensor component
00007  ******************************************************************************
00008  Copyright © 2019, STMicroelectronics International N.V.
00009  All rights reserved.
00010  Redistribution and use in source and binary forms, with or without
00011  modification, are permitted provided that the following conditions are met:
00012  * Redistributions of source code must retain the above copyright
00013  notice, this list of conditions and the following disclaimer.
00014  * Redistributions in binary form must reproduce the above copyright
00015  notice, this list of conditions and the following disclaimer in the
00016  documentation and/or other materials provided with the distribution.
00017  * Neither the name of STMicroelectronics nor the
00018  names of its contributors may be used to endorse or promote products
00019  derived from this software without specific prior written permission.
00020  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00021  ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00022  WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
00023  NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
00024  IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
00025  DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00026  (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00028  ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00029  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00030  SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00031  *****************************************************************************/
00032 
00033 #ifndef __VL53L1X_CLASS_H
00034 #define __VL53L1X_CLASS_H
00035 
00036 
00037 #ifdef _MSC_VER
00038 #   ifdef VL53L1X_API_EXPORTS
00039 #       define VL53L1X_API  __declspec(dllexport)
00040 #   else
00041 #       define VL53L1X_API
00042 #   endif
00043 #else
00044 #   define VL53L1X_API
00045 #endif
00046 
00047 
00048 /* Includes ------------------------------------------------------------------*/
00049 #include "mbed.h"
00050 #include "PinNames.h"
00051 #include "RangeSensor.h"
00052 #include "vl53l1x_error_codes.h"
00053 #include "vl53L1x_I2c.h"
00054 #include "Stmpe1600.h"
00055 
00056 
00057 #define VL53L1X_IMPLEMENTATION_VER_MAJOR       1
00058 #define VL53L1X_IMPLEMENTATION_VER_MINOR       0
00059 #define VL53L1X_IMPLEMENTATION_VER_SUB         1
00060 #define VL53L1X_IMPLEMENTATION_VER_REVISION  0000
00061 
00062 typedef int8_t VL53L1X_ERROR;
00063 
00064 #define VL53L1_I2C_SLAVE__DEVICE_ADDRESS                    0x0001
00065 #define VL53L1_VHV_CONFIG__TIMEOUT_MACROP_LOOP_BOUND        0x0008
00066 #define ALGO__CROSSTALK_COMPENSATION_PLANE_OFFSET_KCPS      0x0016
00067 #define ALGO__CROSSTALK_COMPENSATION_X_PLANE_GRADIENT_KCPS  0x0018
00068 #define ALGO__CROSSTALK_COMPENSATION_Y_PLANE_GRADIENT_KCPS  0x001A
00069 #define ALGO__PART_TO_PART_RANGE_OFFSET_MM                  0x001E
00070 #define MM_CONFIG__INNER_OFFSET_MM                          0x0020
00071 #define MM_CONFIG__OUTER_OFFSET_MM                          0x0022
00072 #define GPIO_HV_MUX__CTRL                                   0x0030
00073 #define GPIO__TIO_HV_STATUS                                 0x0031
00074 #define SYSTEM__INTERRUPT_CONFIG_GPIO                       0x0046
00075 #define PHASECAL_CONFIG__TIMEOUT_MACROP                     0x004B
00076 #define RANGE_CONFIG__TIMEOUT_MACROP_A_HI                   0x005E
00077 #define RANGE_CONFIG__VCSEL_PERIOD_A                        0x0060
00078 #define RANGE_CONFIG__VCSEL_PERIOD_B                        0x0063
00079 #define RANGE_CONFIG__TIMEOUT_MACROP_B_HI                   0x0061
00080 #define RANGE_CONFIG__TIMEOUT_MACROP_B_LO                   0x0062
00081 #define RANGE_CONFIG__SIGMA_THRESH                          0x0064
00082 #define RANGE_CONFIG__MIN_COUNT_RATE_RTN_LIMIT_MCPS         0x0066
00083 #define RANGE_CONFIG__VALID_PHASE_HIGH                      0x0069
00084 #define VL53L1_SYSTEM__INTERMEASUREMENT_PERIOD              0x006C
00085 #define SYSTEM__THRESH_HIGH                                 0x0072
00086 #define SYSTEM__THRESH_LOW                                  0x0074
00087 #define SD_CONFIG__WOI_SD0                                  0x0078
00088 #define SD_CONFIG__INITIAL_PHASE_SD0                        0x007A
00089 #define ROI_CONFIG__USER_ROI_CENTRE_SPAD                    0x007F
00090 #define ROI_CONFIG__USER_ROI_REQUESTED_GLOBAL_XY_SIZE       0x0080
00091 #define SYSTEM__SEQUENCE_CONFIG                             0x0081
00092 #define VL53L1_SYSTEM__GROUPED_PARAMETER_HOLD               0x0082
00093 #define SYSTEM__INTERRUPT_CLEAR                             0x0086
00094 #define SYSTEM__MODE_START                                  0x0087
00095 #define VL53L1_RESULT__RANGE_STATUS                         0x0089
00096 #define VL53L1_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0       0x008C
00097 #define RESULT__AMBIENT_COUNT_RATE_MCPS_SD                  0x0090
00098 #define VL53L1_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0               0x0096
00099 #define VL53L1_RESULT__PEAK_SIGNAL_COUNT_RATE_CROSSTALK_CORRECTED_MCPS_SD0  0x0098
00100 #define VL53L1_RESULT__OSC_CALIBRATE_VAL                    0x00DE
00101 #define VL53L1_FIRMWARE__SYSTEM_STATUS                      0x00E5
00102 #define VL53L1_IDENTIFICATION__MODEL_ID                     0x010F
00103 #define VL53L1_ROI_CONFIG__MODE_ROI_CENTRE_SPAD             0x013E
00104 
00105 
00106 #define VL53L1X_DEFAULT_DEVICE_ADDRESS                      0x52
00107 
00108 #define VL53L1X_REG_IDENTIFICATION_MODEL_ID                 0x010F
00109 /****************************************
00110  * PRIVATE define do not edit
00111  ****************************************/
00112 
00113 /**
00114  *  @brief defines SW Version
00115  */
00116 typedef struct {
00117     uint8_t      major ;    /*!< major number */
00118     uint8_t      minor ;    /*!< minor number */
00119     uint8_t      build ;    /*!< build number */
00120     uint32_t     revision ; /*!< revision number */
00121 } VL53L1X_Version_t;
00122 
00123 
00124 typedef struct {
00125 
00126     uint8_t   I2cDevAddr;
00127 
00128 } VL53L1_Dev_t;
00129 
00130 typedef VL53L1_Dev_t *VL53L1_DEV;
00131 
00132 
00133 /* Classes -------------------------------------------------------------------*/
00134 /** Class representing a VL53L1 sensor component
00135  */
00136 class VL53L1X : public RangeSensor
00137 {
00138  public:
00139     /** Constructor
00140      * @param[in] &i2c device I2C to be used for communication
00141      * @param[in] &pin_gpio1 pin Mbed InterruptIn PinName to be used as component GPIO_1 INT
00142      * @param[in] DevAddr device address, 0x52 by default
00143      */
00144     VL53L1X(vl53L1X_DevI2C *i2c, DigitalOut *pin, PinName pin_gpio1, uint8_t dev_addr = VL53L1X_DEFAULT_DEVICE_ADDRESS) 
00145     : RangeSensor(), dev_i2c(i2c), _gpio0(pin)
00146     {
00147         MyDevice.I2cDevAddr=dev_addr;
00148         Device = &MyDevice;
00149                
00150         _expgpio0 = NULL;
00151         if (pin_gpio1 != NC) {
00152             _gpio1Int = new InterruptIn(pin_gpio1);
00153         } else {
00154             _gpio1Int = NULL;
00155         }
00156     }
00157     
00158     /** Constructor 2 (STMPE1600DigiOut)
00159      * @param[in] i2c device I2C to be used for communication
00160      * @param[in] &pin Gpio Expander STMPE1600DigiOut pin to be used as component GPIO_0 CE
00161      * @param[in] pin_gpio1 pin Mbed InterruptIn PinName to be used as component GPIO_1 INT
00162      * @param[in] device address, 0x29 by default
00163      */
00164     VL53L1X(vl53L1X_DevI2C *i2c, Stmpe1600DigiOut *pin, PinName pin_gpio1,
00165             uint8_t dev_addr = VL53L1X_DEFAULT_DEVICE_ADDRESS) 
00166             : dev_i2c(i2c), _expgpio0(pin)
00167     {
00168         MyDevice.I2cDevAddr=dev_addr;
00169         Device = &MyDevice;
00170                
00171         _gpio0 = NULL;
00172         if (pin_gpio1 != NC) {
00173             _gpio1Int = new InterruptIn(pin_gpio1);
00174         } else {
00175             _gpio1Int = NULL;
00176         }
00177     }    
00178     
00179    /** Destructor
00180     */
00181     virtual ~VL53L1X()
00182     {        
00183         if (_gpio1Int != NULL) {
00184             delete _gpio1Int;
00185         }
00186     }
00187     
00188         
00189     
00190     VL53L1_DEV getDevicePtr() { return Device; }
00191 
00192     
00193     /* warning: VL53L1 class inherits from GenericSensor, RangeSensor and LightSensor, that haven`t a destructor.
00194        The warning should request to introduce a virtual destructor to make sure to delete the object */
00195 
00196     /*** Interface Methods ***/
00197     /*** High level API ***/
00198     /**
00199      * @brief       PowerOn the sensor
00200      * @return      void
00201      */
00202     /* turns on the sensor */
00203     virtual void VL53L1_On(void)
00204     {
00205         printf("VL53L1_On\r\n");
00206         if (_gpio0) {
00207             *_gpio0 = 1;
00208         } else {
00209             if (_expgpio0) {
00210                 *_expgpio0 = 1;
00211             }
00212         }
00213         wait_ms(10);
00214     }
00215 
00216     /**
00217      * @brief       PowerOff the sensor
00218      * @return      void
00219      */
00220     /* turns off the sensor */
00221     virtual void VL53L1_Off(void)
00222     {
00223         printf("VL53L1_Off\r\n");
00224         if (_gpio0) {
00225             *_gpio0 = 0;
00226         } else {
00227             if (_expgpio0) {
00228                 *_expgpio0 = 0;
00229             }
00230         }
00231         wait_ms(10);
00232     }
00233     
00234     int is_present()
00235     {
00236         int status;
00237         uint8_t id = 0;
00238 
00239         status = read_id(&id);
00240         if (status) {
00241             printf("Failed to read ID device. Device not present!\n\r");
00242         }
00243         return status;
00244     }
00245 
00246     /**
00247      * @brief       Initialize the sensor with default values
00248      * @return      0 on Success
00249      */
00250      
00251      VL53L1X_ERROR InitSensor(uint8_t address){
00252         VL53L1X_ERROR status = 0;
00253         uint8_t sensorState = 0;
00254         VL53L1_Off();
00255         VL53L1_On();
00256         status = VL53L1X_SetI2CAddress(address);
00257         
00258         if(!status){
00259             status = VL53L1X_SensorInit();
00260         }      
00261         
00262         while(!status && !sensorState) {
00263             status = VL53L1X_BootState(&sensorState);
00264             wait_ms(2);
00265         }
00266         
00267         return status;
00268      }
00269 
00270 
00271 
00272     /**
00273      *
00274      * @brief One time device initialization
00275      * @param void
00276      * @return     0 on success,  @a #CALIBRATION_WARNING if failed
00277      */
00278     virtual int init(void *init)
00279     {
00280        return VL53L1X_SensorInit();
00281 
00282     }
00283 
00284     /**
00285      * @brief       Initialize the sensor with default values
00286      * @return      "0" on success
00287      */
00288     int init_sensor(uint8_t new_addr);
00289 
00290     /* Read function of the ID device */
00291     virtual int read_id(uint8_t *id){
00292         int status = 0;
00293         uint16_t rl_id = 0;
00294     
00295         uint8_t ExpanderData[2];
00296     
00297         ExpanderData[0] = 0;
00298         ExpanderData[1] = 0;
00299         rl_id = 0;
00300         dev_i2c->v53l1x_i2c_read(&ExpanderData[0], Device->I2cDevAddr, VL53L1X_REG_IDENTIFICATION_MODEL_ID, 2);
00301     
00302         rl_id = (ExpanderData[0] << 8) + ExpanderData[1];
00303         printf("Model ID is: %d (%X)  \r\n",rl_id, rl_id);
00304     
00305         uint8_t tmp = 0;
00306         ExpanderData[0] = VL53L1_FIRMWARE__SYSTEM_STATUS >> 8;
00307         ExpanderData[1] = VL53L1_FIRMWARE__SYSTEM_STATUS & 0x0FF;
00308         dev_i2c->v53l1x_i2c_read(&tmp, Device->I2cDevAddr, VL53L1_FIRMWARE__SYSTEM_STATUS, 1);
00309 
00310         printf("Firmware system is: %d\r\n",tmp);
00311     
00312         if (rl_id == 0xEACC) {
00313             printf("Device is present %d:\r\n", rl_id);
00314             return status;
00315         }
00316         return -1;
00317     }
00318 
00319     /**
00320      * @brief       Interrupt handling func to be called by user after an INT is occurred
00321      * @param[out]  Data pointer to the distance to read data in to
00322      * @return      0 on Success
00323      */
00324     int handle_irq(uint16_t *distance);
00325 
00326     /**
00327      * @brief       Start the measure indicated by operating mode
00328      * @param[in]   fptr specifies call back function must be !NULL in case of interrupt measure
00329      * @return      0 on Success
00330      */
00331     int start_measurement(void (*fptr)(void));
00332     /**
00333      * @brief       Stop the currently running measure indicate by operating_mode
00334      * @return      0 on Success
00335      */
00336     int stop_measurement();
00337     /**
00338      * @brief       Get results for the measure
00339      * @param[out]  Data pointer to the distance_data to read data in to
00340      * @return      0 on Success
00341      */
00342     int get_measurement(uint16_t *distance);
00343     /**
00344      * @brief       Enable interrupt measure IRQ
00345      * @return      0 on Success
00346      */
00347     void enable_interrupt_measure_detection_irq(void)
00348     {
00349         if (_gpio1Int != NULL)
00350             _gpio1Int->enable_irq();
00351     }
00352 
00353     /**
00354      * @brief       Disable interrupt measure IRQ
00355      * @return      0 on Success
00356      */
00357     void disable_interrupt_measure_detection_irq(void)
00358     {
00359         if (_gpio1Int != NULL)
00360             _gpio1Int->disable_irq();
00361     }
00362     /**
00363      * @brief       Attach a function to call when an interrupt is detected, i.e. measurement is ready
00364      * @param[in]   fptr pointer to call back function to be called whenever an interrupt occours
00365      * @return      0 on Success
00366      */
00367     void attach_interrupt_measure_detection_irq(void (*fptr)(void))
00368     {
00369         if (_gpio1Int != NULL)
00370             _gpio1Int->rise(fptr);
00371     }
00372     /**
00373      * @brief Get ranging result and only that
00374      * @param pRange_mm  Pointer to range distance
00375      * @return           0 on success
00376      */
00377     virtual int get_distance(uint32_t *piData)
00378     {
00379     int status;
00380     uint16_t distance;
00381     status = VL53L1X_GetDistance(&distance);
00382     *piData = (uint32_t) distance;
00383     return status;
00384     }
00385 
00386 
00387     /* VL53L1X_api.h functions */
00388 
00389     /**
00390      * @brief This function returns the SW driver version
00391      */
00392     VL53L1X_ERROR VL53L1X_GetSWVersion(VL53L1X_Version_t *pVersion);
00393 
00394     /**
00395      * @brief This function sets the sensor I2C address used in case multiple devices application, default address 0x52
00396      */
00397     VL53L1X_ERROR VL53L1X_SetI2CAddress(uint8_t new_address);
00398 
00399     /**
00400      * @brief This function loads the 135 bytes default values to initialize the sensor.
00401      * @param dev Device address
00402      * @return 0:success, != 0:failed
00403      */
00404     VL53L1X_ERROR VL53L1X_SensorInit();
00405 
00406     /**
00407      * @brief This function clears the interrupt, to be called after a ranging data reading
00408      * to arm the interrupt for the next data ready event.
00409      */
00410     VL53L1X_ERROR VL53L1X_ClearInterrupt();
00411 
00412     /**
00413      * @brief This function programs the interrupt polarity\n
00414      * 1=active high (default), 0=active low
00415      */
00416     VL53L1X_ERROR VL53L1X_SetInterruptPolarity(uint8_t IntPol);
00417 
00418     /**
00419      * @brief This function returns the current interrupt polarity\n
00420      * 1=active high (default), 0=active low
00421      */
00422     VL53L1X_ERROR VL53L1X_GetInterruptPolarity(uint8_t *pIntPol);
00423 
00424     /**
00425      * @brief This function starts the ranging distance operation\n
00426      * The ranging operation is continuous. The clear interrupt has to be done after each get data to allow the interrupt to raise when the next data is ready\n
00427      * 1=active high (default), 0=active low, use SetInterruptPolarity() to change the interrupt polarity if required.
00428      */
00429     VL53L1X_ERROR VL53L1X_StartRanging();
00430 
00431     /**
00432      * @brief This function stops the ranging.
00433      */
00434     VL53L1X_ERROR VL53L1X_StopRanging();
00435 
00436     /**
00437      * @brief This function checks if the new ranging data is available by polling the dedicated register.
00438      * @param : isDataReady==0 -> not ready; isDataReady==1 -> ready
00439      */
00440     VL53L1X_ERROR VL53L1X_CheckForDataReady(uint8_t *isDataReady);
00441     
00442     /**
00443      * @brief This function programs the timing budget in ms.
00444      * Predefined values = 15, 20, 33, 50, 100(default), 200, 500.
00445      */
00446     VL53L1X_ERROR VL53L1X_SetTimingBudgetInMs(uint16_t TimingBudgetInMs);
00447 
00448     /**
00449      * @brief This function returns the current timing budget in ms.
00450      */
00451     VL53L1X_ERROR VL53L1X_GetTimingBudgetInMs(uint16_t *pTimingBudgetInMs);
00452 
00453     /**
00454      * @brief This function programs the distance mode (1=short, 2=long(default)).
00455      * Short mode max distance is limited to 1.3 m but better ambient immunity.\n
00456      * Long mode can range up to 4 m in the dark with 200 ms timing budget.
00457      */
00458     VL53L1X_ERROR VL53L1X_SetDistanceMode(uint16_t DistanceMode);
00459 
00460     /**
00461      * @brief This function returns the current distance mode (1=short, 2=long).
00462      */
00463     VL53L1X_ERROR VL53L1X_GetDistanceMode(uint16_t *pDistanceMode);
00464 
00465     /**
00466      * @brief This function programs the Intermeasurement period in ms\n
00467      * Intermeasurement period must be >/= timing budget. This condition is not checked by the API,
00468      * the customer has the duty to check the condition. Default = 100 ms
00469      */
00470     VL53L1X_ERROR VL53L1X_SetInterMeasurementInMs(uint16_t InterMeasurementInMs);
00471 
00472     /**
00473      * @brief This function returns the Intermeasurement period in ms.
00474      */
00475     VL53L1X_ERROR VL53L1X_GetInterMeasurementInMs(uint16_t * pIM);
00476 
00477     /**
00478      * @brief This function returns the boot state of the device (1:booted, 0:not booted)
00479      */
00480     VL53L1X_ERROR VL53L1X_BootState(uint8_t *state);
00481 
00482     /**
00483      * @brief This function returns the sensor id, sensor Id must be 0xEEAC
00484      */
00485     VL53L1X_ERROR VL53L1X_GetSensorId(uint16_t *id);
00486 
00487     /**
00488      * @brief This function returns the distance measured by the sensor in mm
00489      */
00490     VL53L1X_ERROR VL53L1X_GetDistance(uint16_t *distance);
00491 
00492     /**
00493      * @brief This function returns the returned signal per SPAD in kcps/SPAD.
00494      * With kcps stands for Kilo Count Per Second
00495      */
00496     VL53L1X_ERROR VL53L1X_GetSignalPerSpad(uint16_t *signalPerSp);
00497 
00498     /**
00499      * @brief This function returns the ambient per SPAD in kcps/SPAD
00500      */
00501     VL53L1X_ERROR VL53L1X_GetAmbientPerSpad(uint16_t *amb);
00502 
00503     /**
00504      * @brief This function returns the returned signal in kcps.
00505      */
00506     VL53L1X_ERROR VL53L1X_GetSignalRate(uint16_t *signalRate);
00507 
00508     /**
00509      * @brief This function returns the current number of enabled SPADs
00510      */
00511     VL53L1X_ERROR VL53L1X_GetSpadNb(uint16_t *spNb);
00512 
00513     /**
00514      * @brief This function returns the ambient rate in kcps
00515      */
00516     VL53L1X_ERROR VL53L1X_GetAmbientRate(uint16_t *ambRate);
00517 
00518     /**
00519      * @brief This function returns the ranging status error \n
00520      * (0:no error, 1:sigma failed, 2:signal failed, ..., 7:wrap-around)
00521      */
00522     VL53L1X_ERROR VL53L1X_GetRangeStatus(uint8_t *rangeStatus);
00523 
00524     /**
00525      * @brief This function programs the offset correction in mm
00526      * @param OffsetValue:the offset correction value to program in mm
00527      */
00528     VL53L1X_ERROR VL53L1X_SetOffset(int16_t OffsetValue);
00529 
00530     /**
00531      * @brief This function returns the programmed offset correction value in mm
00532      */
00533     VL53L1X_ERROR VL53L1X_GetOffset(int16_t *Offset);
00534 
00535     /**
00536      * @brief This function programs the xtalk correction value in cps (Count Per Second).\n
00537      * This is the number of photons reflected back from the cover glass in cps.
00538      */
00539     VL53L1X_ERROR VL53L1X_SetXtalk(uint16_t XtalkValue);
00540 
00541     /**
00542      * @brief This function returns the current programmed xtalk correction value in cps
00543      */
00544     VL53L1X_ERROR VL53L1X_GetXtalk(uint16_t *Xtalk);
00545 
00546     /**
00547      * @brief This function programs the threshold detection mode\n
00548      * Example:\n
00549      * VL53L1X_SetDistanceThreshold(dev,100,300,0,1): Below 100 \n
00550      * VL53L1X_SetDistanceThreshold(dev,100,300,1,1): Above 300 \n
00551      * VL53L1X_SetDistanceThreshold(dev,100,300,2,1): Out of window \n
00552      * VL53L1X_SetDistanceThreshold(dev,100,300,3,1): In window \n
00553      * @param   dev : device address
00554      * @param   ThreshLow(in mm) : the threshold under which one the device raises an interrupt if Window = 0
00555      * @param   ThreshHigh(in mm) :  the threshold above which one the device raises an interrupt if Window = 1
00556      * @param   Window detection mode : 0=below, 1=above, 2=out, 3=in
00557      * @param   IntOnNoTarget = 1 (No longer used - just use 1)
00558      */
00559     VL53L1X_ERROR VL53L1X_SetDistanceThreshold(uint16_t ThreshLow,
00560                       uint16_t ThreshHigh, uint8_t Window,
00561                       uint8_t IntOnNoTarget);
00562 
00563     /**
00564      * @brief This function returns the window detection mode (0=below; 1=above; 2=out; 3=in)
00565      */
00566     VL53L1X_ERROR VL53L1X_GetDistanceThresholdWindow(uint16_t *window);
00567 
00568     /**
00569      * @brief This function returns the low threshold in mm
00570      */
00571     VL53L1X_ERROR VL53L1X_GetDistanceThresholdLow(uint16_t *low);
00572 
00573     /**
00574      * @brief This function returns the high threshold in mm
00575      */
00576     VL53L1X_ERROR VL53L1X_GetDistanceThresholdHigh(uint16_t *high);
00577 
00578     /**
00579      * @brief This function programs the ROI (Region of Interest)\n
00580      * The ROI position is centered, only the ROI size can be reprogrammed.\n
00581      * The smallest acceptable ROI size = 4\n
00582      * @param X:ROI Width; Y=ROI Height
00583      */
00584     VL53L1X_ERROR VL53L1X_SetROI(uint16_t X, uint16_t Y);
00585 
00586     /**
00587      *@brief This function returns width X and height Y
00588      */
00589     VL53L1X_ERROR VL53L1X_GetROI_XY(uint16_t *ROI_X, uint16_t *ROI_Y);
00590 
00591     /**
00592      * @brief This function programs a new signal threshold in kcps (default=1024 kcps\n
00593      */
00594     VL53L1X_ERROR VL53L1X_SetSignalThreshold(uint16_t signal);
00595 
00596     /**
00597      * @brief This function returns the current signal threshold in kcps
00598      */
00599     VL53L1X_ERROR VL53L1X_GetSignalThreshold(uint16_t *signal);
00600 
00601     /**
00602      * @brief This function programs a new sigma threshold in mm (default=15 mm)
00603      */
00604     VL53L1X_ERROR VL53L1X_SetSigmaThreshold(uint16_t sigma);
00605 
00606     /**
00607      * @brief This function returns the current sigma threshold in mm
00608      */
00609     VL53L1X_ERROR VL53L1X_GetSigmaThreshold(uint16_t *signal);
00610 
00611     /**
00612      * @brief This function performs the temperature calibration.
00613      * It is recommended to call this function any time the temperature might have changed by more than 8 deg C
00614      * without sensor ranging activity for an extended period.
00615      */
00616     VL53L1X_ERROR VL53L1X_StartTemperatureUpdate();
00617 
00618 
00619     /* VL53L1X_calibration.h functions */
00620     
00621         /**
00622      * @brief This function performs the offset calibration.\n
00623      * The function returns the offset value found and programs the offset compensation into the device.
00624      * @param TargetDistInMm target distance in mm, ST recommended 100 mm
00625      * Target reflectance = grey17%
00626      * @return 0:success, !=0: failed
00627      * @return offset pointer contains the offset found in mm
00628      */
00629     int8_t VL53L1X_CalibrateOffset(uint16_t TargetDistInMm, int16_t *offset);
00630 
00631     /**
00632      * @brief This function performs the xtalk calibration.\n
00633      * The function returns the xtalk value found and programs the xtalk compensation to the device
00634      * @param TargetDistInMm target distance in mm\n
00635      * The target distance : the distance where the sensor start to "under range"\n
00636      * due to the influence of the photons reflected back from the cover glass becoming strong\n
00637      * It's also called inflection point\n
00638      * Target reflectance = grey 17%
00639      * @return 0: success, !=0: failed
00640      * @return xtalk pointer contains the xtalk value found in cps (number of photons in count per second)
00641      */
00642     int8_t VL53L1X_CalibrateXtalk(uint16_t TargetDistInMm, uint16_t *xtalk);
00643     
00644 
00645     /* Write and read functions from I2C */
00646 
00647     VL53L1X_ERROR VL53L1_WrByte(VL53L1_DEV dev, uint16_t index, uint8_t data);
00648     VL53L1X_ERROR VL53L1_WrWord(VL53L1_DEV dev, uint16_t index, uint16_t data);
00649     VL53L1X_ERROR VL53L1_WrDWord(VL53L1_DEV dev, uint16_t index, uint32_t data);
00650     VL53L1X_ERROR VL53L1_RdByte(VL53L1_DEV dev, uint16_t index, uint8_t *data);
00651     VL53L1X_ERROR VL53L1_RdWord(VL53L1_DEV dev, uint16_t index, uint16_t *data);
00652     VL53L1X_ERROR VL53L1_RdDWord(VL53L1_DEV dev, uint16_t index, uint32_t *data);
00653     VL53L1X_ERROR VL53L1_UpdateByte(VL53L1_DEV dev, uint16_t index, uint8_t AndData, uint8_t OrData);
00654 
00655     VL53L1X_ERROR VL53L1_WriteMulti(VL53L1_DEV Dev, uint16_t index, uint8_t *pdata, uint32_t count);
00656     VL53L1X_ERROR VL53L1_ReadMulti(VL53L1_DEV Dev, uint16_t index, uint8_t *pdata, uint32_t count);
00657 
00658     VL53L1X_ERROR VL53L1_I2CWrite(uint8_t dev, uint16_t index, uint8_t *data, uint16_t number_of_bytes);
00659     VL53L1X_ERROR VL53L1_I2CRead(uint8_t dev, uint16_t index, uint8_t *data, uint16_t number_of_bytes);
00660     VL53L1X_ERROR VL53L1_GetTickCount(uint32_t *ptick_count_ms);
00661     VL53L1X_ERROR VL53L1_WaitUs(VL53L1_Dev_t *pdev, int32_t wait_us);
00662     VL53L1X_ERROR VL53L1_WaitMs(VL53L1_Dev_t *pdev, int32_t wait_ms);
00663     
00664     VL53L1X_ERROR VL53L1_WaitValueMaskEx(VL53L1_Dev_t *pdev, uint32_t timeout_ms, uint16_t index, uint8_t value, uint8_t mask, uint32_t poll_delay_ms);
00665 
00666  protected:
00667 
00668     /* IO Device */
00669     vl53L1X_DevI2C *dev_i2c;
00670     
00671     /* Digital out pin */
00672     DigitalOut *_gpio0;
00673     /* GPIO expander */
00674     Stmpe1600DigiOut *_expgpio0;
00675     /* Measure detection IRQ */
00676     InterruptIn *_gpio1Int;
00677  
00678     /* Device data */
00679     VL53L1_Dev_t MyDevice;
00680     VL53L1_DEV Device;
00681 };
00682 
00683 
00684 #endif /* _VL53L1X_CLASS_H_ */