charles macneill / VL53L1CB
Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers vl53l1x.h Source File

vl53l1x.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 
00050 #include "mbed.h"
00051 #include "PinNames.h"
00052 #include "RangeSensor.h"
00053 #include "vl53l1x_error_codes.h"
00054 #include "vl53l1_platform_user_data.h"
00055 //#include "DevI2C.h"
00056 #include "ToF_I2C.h"
00057 #include "Stmpe1600.h"
00058 /**********************************************************/
00059 #include "vl53l1_def.h"
00060 /***********************************************************/
00061 
00062 
00063 #define VL53L1X_IMPLEMENTATION_VER_MAJOR       1
00064 #define VL53L1X_IMPLEMENTATION_VER_MINOR       0
00065 #define VL53L1X_IMPLEMENTATION_VER_SUB         1
00066 #define VL53L1X_IMPLEMENTATION_VER_REVISION  0000
00067 
00068 typedef int8_t VL53L1X_ERROR;
00069 
00070 //#define SOFT_RESET                                          0x0000
00071 #define VL53L1_I2C_SLAVE__DEVICE_ADDRESS                    0x0001
00072 #define VL53L1_VHV_CONFIG__TIMEOUT_MACROP_LOOP_BOUND        0x0008
00073 #define ALGO__CROSSTALK_COMPENSATION_PLANE_OFFSET_KCPS      0x0016
00074 #define ALGO__CROSSTALK_COMPENSATION_X_PLANE_GRADIENT_KCPS  0x0018
00075 #define ALGO__CROSSTALK_COMPENSATION_Y_PLANE_GRADIENT_KCPS  0x001A
00076 #define ALGO__PART_TO_PART_RANGE_OFFSET_MM                  0x001E
00077 #define MM_CONFIG__INNER_OFFSET_MM                          0x0020
00078 #define MM_CONFIG__OUTER_OFFSET_MM                          0x0022
00079 #define GPIO_HV_MUX__CTRL                                   0x0030
00080 #define GPIO__TIO_HV_STATUS                                 0x0031
00081 #define SYSTEM__INTERRUPT_CONFIG_GPIO                       0x0046
00082 #define PHASECAL_CONFIG__TIMEOUT_MACROP                     0x004B
00083 #define RANGE_CONFIG__TIMEOUT_MACROP_A_HI                   0x005E
00084 #define RANGE_CONFIG__VCSEL_PERIOD_A                        0x0060
00085 #define RANGE_CONFIG__VCSEL_PERIOD_B                        0x0063
00086 #define RANGE_CONFIG__TIMEOUT_MACROP_B_HI                   0x0061
00087 #define RANGE_CONFIG__TIMEOUT_MACROP_B_LO                   0x0062
00088 #define RANGE_CONFIG__SIGMA_THRESH                          0x0064
00089 #define RANGE_CONFIG__MIN_COUNT_RATE_RTN_LIMIT_MCPS         0x0066
00090 #define RANGE_CONFIG__VALID_PHASE_HIGH                      0x0069
00091 #define VL53L1_SYSTEM__INTERMEASUREMENT_PERIOD              0x006C
00092 #define SYSTEM__THRESH_HIGH                                 0x0072
00093 #define SYSTEM__THRESH_LOW                                  0x0074
00094 #define SD_CONFIG__WOI_SD0                                  0x0078
00095 #define SD_CONFIG__INITIAL_PHASE_SD0                        0x007A
00096 #define ROI_CONFIG__USER_ROI_CENTRE_SPAD                    0x007F
00097 #define ROI_CONFIG__USER_ROI_REQUESTED_GLOBAL_XY_SIZE       0x0080
00098 #define SYSTEM__SEQUENCE_CONFIG                             0x0081
00099 #define VL53L1_SYSTEM__GROUPED_PARAMETER_HOLD               0x0082
00100 #define SYSTEM__INTERRUPT_CLEAR                             0x0086
00101 #define SYSTEM__MODE_START                                  0x0087
00102 #define VL53L1_RESULT__RANGE_STATUS                         0x0089
00103 #define VL53L1_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0       0x008C
00104 #define RESULT__AMBIENT_COUNT_RATE_MCPS_SD                  0x0090
00105 #define VL53L1_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0               0x0096
00106 #define VL53L1_RESULT__PEAK_SIGNAL_COUNT_RATE_CROSSTALK_CORRECTED_MCPS_SD0  0x0098
00107 #define VL53L1_RESULT__OSC_CALIBRATE_VAL                    0x00DE
00108 #define VL53L1_FIRMWARE__SYSTEM_STATUS                      0x00E5
00109 #define VL53L1_IDENTIFICATION__MODEL_ID                     0x010F
00110 #define VL53L1_ROI_CONFIG__MODE_ROI_CENTRE_SPAD             0x013E
00111 
00112 
00113 #define VL53L1X_DEFAULT_DEVICE_ADDRESS                      0x52
00114 
00115 #define VL53L1X_REG_IDENTIFICATION_MODEL_ID                 0x010F
00116 
00117 /****************************************
00118  * PRIVATE define do not edit
00119  ****************************************/
00120 
00121 /**
00122  *  @brief defines SW Version
00123  */
00124 typedef struct {
00125     uint8_t      major ;    /*!< major number */
00126     uint8_t      minor ;    /*!< minor number */
00127     uint8_t      build ;    /*!< build number */
00128     uint32_t     revision ; /*!< revision number */
00129 } VL53L1X_Version_t;
00130 
00131 
00132 /* Classes -------------------------------------------------------------------*/
00133 /** Class representing a VL53L1 sensor component
00134  */
00135 class VL53L1X : public RangeSensor
00136 {
00137  
00138 
00139  
00140  public:
00141  
00142  
00143  #define VL53L1DevStructGetLLDriverHandle(Dev) (&Dev->Data.LLData)
00144     /** Constructor
00145      * @param[in] &i2c device I2C to be used for communication
00146      * @param[in] &pin_gpio1 pin Mbed InterruptIn PinName to be used as component GPIO_1 INT
00147      * @param[in] DevAddr device address, 0x52 by default
00148      */
00149 
00150     VL53L1X(ToF_DevI2C *i2c, DigitalOut *pin, PinName pin_gpio1, uint8_t dev_addr = VL53L1X_DEFAULT_DEVICE_ADDRESS) 
00151     : RangeSensor(), dev_i2c(i2c), _gpio0(pin)
00152     {
00153         MyDevice.i2c_slave_address=dev_addr;
00154         Device = &MyDevice;
00155                
00156         _expgpio0 = NULL;
00157         if (pin_gpio1 != NC) {
00158             _gpio1Int = new InterruptIn(pin_gpio1);
00159         } else {
00160             _gpio1Int = NULL;
00161         }
00162     }
00163 
00164     
00165     /** Constructor 2 (STMPE1600DigiOut)
00166      * @param[in] i2c device I2C to be used for communication
00167      * @param[in] &pin Gpio Expander STMPE1600DigiOut pin to be used as component GPIO_0 CE
00168      * @param[in] pin_gpio1 pin Mbed InterruptIn PinName to be used as component GPIO_1 INT
00169      * @param[in] device address, 0x29 by default
00170      */
00171     VL53L1X(ToF_DevI2C *i2c, Stmpe1600DigiOut *pin, PinName pin_gpio1,
00172             uint8_t dev_addr = VL53L1X_DEFAULT_DEVICE_ADDRESS) 
00173             : dev_i2c(i2c), _expgpio0(pin)
00174     {
00175         MyDevice.i2c_slave_address=dev_addr;
00176         Device = &MyDevice;
00177                
00178         _gpio0 = NULL;
00179         if (pin_gpio1 != NC) {
00180             _gpio1Int = new InterruptIn(pin_gpio1);
00181         } else {
00182             _gpio1Int = NULL;
00183         }
00184     }    
00185     
00186    /** Destructor
00187     */
00188     virtual ~VL53L1X()
00189     {        
00190         if (_gpio1Int != NULL) {
00191             delete _gpio1Int;
00192         }
00193     }
00194     
00195         
00196     
00197     VL53L1_DEV getDevicePtr() { return Device; }
00198 
00199     
00200     /* warning: VL53L1 class inherits from GenericSensor, RangeSensor and LightSensor, that haven`t a destructor.
00201        The warning should request to introduce a virtual destructor to make sure to delete the object */
00202 
00203     /*** Interface Methods ***/
00204     /*** High level API ***/
00205     /**
00206      * @brief       PowerOn the sensor
00207      * @return      void
00208      */
00209     /* turns on the sensor */
00210     virtual void VL53L1_On(void)
00211     {
00212         printf("VL53L1_On\r\n");
00213         if (_gpio0) {
00214             *_gpio0 = 1;
00215         } else {
00216             if (_expgpio0) {
00217                 *_expgpio0 = 1;
00218             }
00219         }
00220         wait_ms(100);
00221     }
00222 
00223     /**
00224      * @brief       PowerOff the sensor
00225      * @return      void
00226      */
00227     /* turns off the sensor */
00228     virtual void VL53L1_Off(void)
00229     {
00230         printf("VL53L1_Off\r\n");
00231         if (_gpio0) {
00232             *_gpio0 = 0;
00233         } else {
00234             if (_expgpio0) {
00235                 *_expgpio0 = 0;
00236             }
00237         }
00238         wait_ms(100);
00239     }
00240     
00241     int is_present()
00242     {
00243         int status;
00244         uint8_t id = 0;
00245 
00246         status = read_id(&id);
00247         if (status) {
00248             printf("Failed to read ID device. Device not present!\n\r");
00249         }
00250         return status;
00251     }
00252 
00253     /**
00254      * @brief       Initialize the sensor with default values
00255      * @return      0 on Success
00256      */
00257      
00258      VL53L1X_ERROR InitSensor(uint8_t address){
00259         VL53L1X_ERROR status = 0;
00260         uint8_t sensorState = 0;
00261         VL53L1_Off();
00262         VL53L1_On();
00263         status = vl53L1X_SetI2CAddress(address);
00264         if(!status){
00265             status = VL53L1X_SensorInit();
00266         }      
00267      
00268         while(!status && !sensorState) {
00269             status = vl53L1X_BootState(&sensorState);
00270             wait_ms(2);
00271         }           
00272         return status;
00273      }
00274 
00275 
00276 
00277 /**
00278  *
00279  * @brief One time device initialization
00280  * @param void
00281  * @return     0 on success,  @a #CALIBRATION_WARNING if failed
00282  */
00283     virtual int init(void *init)
00284     {
00285          return VL53L1X_SensorInit();
00286          return 0;
00287     }
00288 
00289 
00290     /**
00291      * @brief       Initialize the sensor with default values
00292      * @return      "0" on success
00293      */
00294     int init_sensor(uint8_t new_addr);
00295 
00296     /* Read function of the ID device */
00297     virtual int read_id(uint8_t *id){
00298         int status = 0;
00299         uint16_t rl_id = 0;
00300     
00301         uint8_t ExpanderData[2];
00302     
00303         ExpanderData[0] = 0;
00304         ExpanderData[1] = 0;
00305         rl_id = 0;
00306         dev_i2c->ToF_i2c_read(&ExpanderData[0], Device->i2c_slave_address, VL53L1X_REG_IDENTIFICATION_MODEL_ID, 2);
00307     
00308         rl_id = (ExpanderData[0] << 8) + ExpanderData[1];
00309         printf("Model ID is: %d (%X)  \r\n",rl_id, rl_id);
00310     
00311         uint8_t tmp = 0;
00312         ExpanderData[0] = VL53L1_FIRMWARE__SYSTEM_STATUS >> 8;
00313         ExpanderData[1] = VL53L1_FIRMWARE__SYSTEM_STATUS & 0x0FF;
00314         dev_i2c->ToF_i2c_read(&tmp, Device->i2c_slave_address, VL53L1_FIRMWARE__SYSTEM_STATUS, 1);
00315 
00316         printf("Firmware system is: %d\r\n",tmp);
00317     
00318         if (rl_id == 0xEACC) {
00319             printf("Device is present %d:\r\n", rl_id);
00320             return status;
00321         }
00322         return -1;
00323     }
00324 
00325 
00326 
00327 /**
00328  * @brief Get ranging result and only that
00329  * @param pRange_mm  Pointer to range distance
00330  * @return           0 on success
00331  */
00332     virtual int get_distance(uint32_t *piData)
00333     {
00334     int status;
00335     uint16_t distance;
00336     status = VL53L1X_GetDistance(&distance);
00337     *piData = (uint32_t) distance;
00338     return status;
00339     }
00340 
00341 
00342 /* VL53L1X_api.h functions */
00343 
00344 
00345 
00346     /**
00347      * @brief This function returns the SW driver version
00348      */
00349     VL53L1X_ERROR VL53L1X_GetSWVersion(VL53L1X_Version_t *pVersion);
00350 
00351     /**
00352      * @brief This function sets the sensor I2C address used in case multiple devices application, default address 0x52
00353      */
00354     VL53L1X_ERROR vl53L1X_SetI2CAddress(uint8_t new_address);
00355 
00356     /**
00357      * @brief This function loads the 135 bytes default values to initialize the sensor.
00358      * @param dev Device address
00359      * @return 0:success, != 0:failed
00360      */
00361     VL53L1X_ERROR VL53L1X_SensorInit();
00362 
00363     /**
00364      * @brief This function clears the interrupt, to be called after a ranging data reading
00365      * to arm the interrupt for the next data ready event.
00366      */
00367     VL53L1X_ERROR VL53L1X_ClearInterrupt();
00368 
00369 
00370     /**
00371      * @brief This function returns the current interrupt polarity\n
00372      * 1=active high (default), 0=active low
00373      */
00374     VL53L1X_ERROR VL53L1X_GetInterruptPolarity(uint8_t *pIntPol);
00375 
00376     /**
00377      * @brief This function starts the ranging distance operation\n
00378      * 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
00379      * 1=active high (default), 0=active low, use SetInterruptPolarity() to change the interrupt polarity if required.
00380      */
00381     VL53L1X_ERROR VL53L1X_StartRanging();
00382 
00383     /**
00384      * @brief This function stops the ranging.
00385      */
00386     VL53L1X_ERROR VL53L1X_StopRanging();
00387 
00388 
00389 
00390     /**
00391      * @brief This function returns the boot state of the device (1:booted, 0:not booted)
00392      */
00393     VL53L1X_ERROR vl53L1X_BootState(uint8_t *state);
00394 
00395     /**
00396      * @brief This function returns the sensor id, sensor Id must be 0xEEAC
00397      */
00398   //  VL53L1X_ERROR VL53L1X_GetSensorId(uint16_t *id);
00399 
00400     /**
00401      * @brief This function returns the distance measured by the sensor in mm
00402      */
00403     VL53L1X_ERROR VL53L1X_GetDistance(uint16_t *distance);
00404 
00405 
00406     
00407     
00408     /**************************************************************************/
00409     VL53L1X_ERROR vl53L1_WaitDeviceBooted(VL53L1_DEV Dev);
00410     
00411     
00412     VL53L1X_ERROR vl53L1_GetCalibrationData(VL53L1_CalibrationData_t  *pCalibrationData);
00413         
00414     
00415     
00416     VL53L1_GPIO_Interrupt_Mode ConvertModeToLLD(VL53L1_Error *pStatus,
00417         VL53L1_ThresholdMode CrossMode);
00418       
00419     VL53L1X_ERROR vl53L1_GetVersion(VL53L1_Version_t *pVersion);
00420     
00421     VL53L1X_ERROR vl53L1_GetProductRevision(
00422     uint8_t *pProductRevisionMajor, uint8_t *pProductRevisionMinor);
00423     
00424     
00425     VL53L1X_ERROR vl53L1_GetDeviceInfo(
00426     VL53L1_DeviceInfo_t *pVL53L1_DeviceInfo);
00427     
00428     VL53L1X_ERROR vl53L1_GetUID( uint64_t *pUid);
00429     
00430     VL53L1X_ERROR vl53L1_GetRangeStatusString(uint8_t RangeStatus,
00431     char *pRangeStatusString);
00432     
00433     
00434     VL53L1X_ERROR vl53L1_GetPalErrorString(VL53L1_Error PalErrorCode,
00435     char *pPalErrorString);
00436     
00437     
00438     VL53L1X_ERROR vl53L1_GetPalStateString(VL53L1_State PalStateCode,
00439     char *pPalStateString);
00440     
00441     
00442     VL53L1X_ERROR vl53L1_GetPalState(VL53L1_DEV Dev, VL53L1_State *pPalState);
00443     
00444     VL53L1X_ERROR vl53L1_DataInit();
00445     
00446     VL53L1X_ERROR vl53L1_StaticInit();
00447         
00448     VL53L1_Error vl53L1_ClearInterruptAndStartMeasurement();
00449     
00450     VL53L1X_ERROR vl53L1_GetRangingMeasurementData(
00451         VL53L1_RangingMeasurementData_t *pRangingMeasurementData);
00452 
00453     VL53L1X_ERROR vl53L1_GetMultiRangingData(
00454         VL53L1_MultiRangingData_t *pMultiRangingData);   
00455         
00456     VL53L1X_ERROR vl53L1_GetAdditionalData(
00457                 VL53L1_AdditionalData_t *pAdditionalData);
00458                 
00459     VL53L1X_ERROR vl53L1_SetTuningParameter(
00460         uint16_t TuningParameterId, int32_t TuningParameterValue);
00461         
00462     VL53L1X_ERROR vl53L1_GetTuningParameter(
00463         uint16_t TuningParameterId, int32_t *pTuningParameterValue);
00464   
00465     VL53L1X_ERROR vl53L1_SetXTalkCompensationEnable(
00466          uint8_t XTalkCompensationEnable);
00467          
00468          
00469     VL53L1X_ERROR vl53L1_GetXTalkCompensationEnable(
00470             uint8_t *pXTalkCompensationEnable);
00471                        
00472     VL53L1X_ERROR vl53L1_PerformXTalkCalibration(
00473     uint8_t CalibrationOption);
00474     
00475     VL53L1X_ERROR vl53L1_SetOffsetCalibrationMode(
00476             VL53L1_OffsetCalibrationModes OffsetCalibrationMode);
00477             
00478 
00479     VL53L1X_ERROR vl53L1_SetOffsetCorrectionMode(
00480             VL53L1_OffsetCorrectionModes OffsetCorrectionMode);
00481         
00482     VL53L1X_ERROR vl53L1_PerformOffsetCalibration(
00483             int32_t CalDistanceMilliMeter, FixPoint1616_t CalReflectancePercent);
00484             
00485     VL53L1X_ERROR vl53L1_PerformOffsetSimpleCalibration(
00486              int32_t CalDistanceMilliMeter);
00487     
00488     VL53L1X_ERROR vl53L1_PerformOffsetZeroDistanceCalibration();
00489     
00490     VL53L1X_ERROR vl53L1_SetCalibrationData(
00491         VL53L1_CalibrationData_t *pCalibrationData);
00492         
00493     VL53L1X_ERROR vl53L1_SetZoneCalibrationData(
00494         VL53L1_ZoneCalibrationData_t *pZoneCalibrationData);
00495         
00496     VL53L1X_ERROR vl53L1_GetZoneCalibrationData(
00497         VL53L1_ZoneCalibrationData_t  *pZoneCalibrationData);
00498         
00499     VL53L1X_ERROR vl53L1_GetOpticalCenter(
00500         FixPoint1616_t *pOpticalCenterX,
00501         FixPoint1616_t *pOpticalCenterY);
00502         
00503     VL53L1X_ERROR vl53L1_SetThresholdConfig(VL53L1_DetectionConfig_t *pConfig);
00504     
00505     
00506      VL53L1X_ERROR vl53L1_GetLimitCheckStatus( uint16_t LimitCheckId,
00507                                               uint8_t *pLimitCheckStatus);    
00508                                               
00509         
00510     VL53L1X_ERROR vl53L1_SetLimitCheckEnable( uint16_t LimitCheckId,
00511                                              uint8_t LimitCheckEnable);
00512         
00513     VL53L1X_ERROR vl53L1_GetLimitCheckEnable(uint16_t LimitCheckId,
00514                                              uint8_t *pLimitCheckEnable);
00515     
00516     VL53L1X_ERROR vl53L1_GetThresholdConfig(VL53L1_DetectionConfig_t *pConfig);
00517         
00518         
00519     VL53L1X_ERROR vl53L1_PerformOffsetPerVcselCalibration(int32_t CalDistanceMilliMeter);
00520   
00521     VL53L1X_ERROR vl53L1_GetNumberOfLimitCheck(uint16_t *pNumberOfLimitCheck);      
00522     
00523     VL53L1X_ERROR vl53L1_GetLimitCheckInfo(uint16_t LimitCheckId,
00524                                            char *pLimitCheckString);       
00525         
00526     VL53L1X_ERROR vl53L1_SetPresetMode(VL53L1_PresetModes PresetMode);
00527         
00528     VL53L1X_ERROR vl53L1_GetPresetMode( VL53L1_PresetModes *pPresetMode);
00529                                     
00530     VL53L1X_ERROR vl53L1_SetDistanceMode( VL53L1_DistanceModes DistanceMode);
00531                                                                                     
00532     VL53L1X_ERROR vl53L1_GetDistanceMode(VL53L1_DistanceModes *pDistanceMode);
00533                                              
00534     VL53L1X_ERROR vl53L1_SetOutputMode(VL53L1_OutputModes OutputMode);
00535                                            
00536     VL53L1X_ERROR vl53L1_GetOutputMode(VL53L1_OutputModes *pOutputMode);
00537                                         
00538     VL53L1X_ERROR vl53L1_SetMeasurementTimingBudgetMicroSeconds(uint32_t MeasurementTimingBudgetMicroSeconds);
00539                                     
00540     VL53L1X_ERROR vl53L1_SetInterMeasurementPeriodMilliSeconds(uint32_t InterMeasurementPeriodMilliSeconds);
00541                                    
00542     
00543     VL53L1X_ERROR vl53L1_GetInterMeasurementPeriodMilliSeconds(
00544             uint32_t *pInterMeasurementPeriodMilliSeconds);
00545         
00546         
00547     VL53L1X_ERROR vl53L1_SetDmaxReflectance( FixPoint1616_t DmaxReflectance);
00548                                                 
00549     VL53L1X_ERROR vl53L1_GetDmaxReflectance(FixPoint1616_t *pDmaxReflectance);
00550                                                 
00551                                                 
00552     VL53L1X_ERROR vl53L1_GetDmaxMode( VL53L1_DeviceDmaxModes *pDmaxMode);    
00553                                     
00554     VL53L1X_ERROR vl53L1_GetMeasurementTimingBudgetMicroSeconds(
00555                                  uint32_t *pMeasurementTimingBudgetMicroSeconds);  
00556                                  
00557     VL53L1X_ERROR vl53L1_SetDmaxMode(VL53L1_DeviceDmaxModes DmaxMode);    
00558                                      
00559     VL53L1X_ERROR vl53L1_SetLimitCheckValue( uint16_t LimitCheckId,
00560                                             FixPoint1616_t LimitCheckValue);
00561                                             
00562     VL53L1X_ERROR vl53L1_GetLimitCheckValue(uint16_t LimitCheckId,
00563                                             FixPoint1616_t *pLimitCheckValue);   
00564                                             
00565     VL53L1X_ERROR vl53L1_GetLimitCheckCurrent( uint16_t LimitCheckId,
00566                                               FixPoint1616_t *pLimitCheckCurrent);   
00567                                             
00568     VL53L1X_ERROR vl53L1_GetMaxNumberOfROI( uint8_t *pMaxNumberOfROI);    
00569                                            
00570     VL53L1X_ERROR vl53L1_SetROI(VL53L1_RoiConfig_t *pRoiConfig);
00571                                 
00572      VL53L1X_ERROR vl53L1_GetROI(VL53L1_RoiConfig_t *pRoiConfig);
00573                                  
00574     VL53L1X_ERROR vl53L1_GetNumberOfSequenceSteps(uint8_t *pNumberOfSequenceSteps);          
00575     
00576     VL53L1X_ERROR vl53L1_GetSequenceStepsInfo(VL53L1_SequenceStepId SequenceStepId,
00577                                               char *pSequenceStepsString);   
00578                                               
00579                                               
00580     VL53L1X_ERROR vl53L1_SetSequenceStepEnable(VL53L1_SequenceStepId SequenceStepId, uint8_t SequenceStepEnabled);    
00581         
00582         
00583     VL53L1X_ERROR vl53L1_GetSequenceStepEnable(VL53L1_SequenceStepId SequenceStepId, uint8_t *pSequenceStepEnabled); 
00584            
00585     
00586     VL53L1X_ERROR vl53L1_StartMeasurement();
00587     
00588     VL53L1X_ERROR vl53L1_StopMeasurement();
00589     
00590     
00591     VL53L1X_ERROR vl53L1_GetMeasurementDataReady(uint8_t *pMeasurementDataReady); 
00592                                                  
00593     VL53L1X_ERROR vl53L1_WaitMeasurementDataReady();        
00594     
00595     VL53L1_Error vl53L1_SmudgeCorrectionEnable(VL53L1_SmudgeCorrectionModes Mode);                                                                                                                                                    
00596     /***************************************************************************/
00597     
00598 
00599     /* Write and read functions from I2C */
00600 
00601     VL53L1X_ERROR VL53L1_WrByte(VL53L1_DEV dev, uint16_t index, uint8_t data);
00602     VL53L1X_ERROR VL53L1_WrWord(VL53L1_DEV dev, uint16_t index, uint16_t data);
00603     VL53L1X_ERROR VL53L1_WrDWord(VL53L1_DEV dev, uint16_t index, uint32_t data);
00604     VL53L1X_ERROR VL53L1_RdByte(VL53L1_DEV dev, uint16_t index, uint8_t *data);
00605     VL53L1X_ERROR VL53L1_RdWord(VL53L1_DEV dev, uint16_t index, uint16_t *data);
00606     VL53L1X_ERROR VL53L1_RdDWord(VL53L1_DEV dev, uint16_t index, uint32_t *data);
00607     VL53L1X_ERROR VL53L1_UpdateByte(VL53L1_DEV dev, uint16_t index, uint8_t AndData, uint8_t OrData);
00608 
00609     VL53L1X_ERROR VL53L1_WriteMulti(VL53L1_DEV Dev, uint16_t index, uint8_t *pdata, uint32_t count);
00610     VL53L1X_ERROR VL53L1_ReadMulti(VL53L1_DEV Dev, uint16_t index, uint8_t *pdata, uint32_t count);
00611 
00612     VL53L1X_ERROR VL53L1_I2CWrite(uint8_t dev, uint16_t index, uint8_t *data, uint16_t number_of_bytes);
00613     VL53L1X_ERROR VL53L1_I2CRead(uint8_t dev, uint16_t index, uint8_t *data, uint16_t number_of_bytes);
00614     VL53L1X_ERROR VL53L1_GetTickCount(uint32_t *ptick_count_ms);
00615     VL53L1X_ERROR VL53L1_WaitUs(VL53L1_Dev_t *pdev, int32_t wait_us);
00616     VL53L1X_ERROR VL53L1_WaitMs(VL53L1_Dev_t *pdev, int32_t wait_ms);
00617     
00618     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);
00619     VL53L1X_ERROR VL53L1_SetDeviceAddress(VL53L1_DEV Dev, uint8_t DeviceAddress);
00620     
00621     // from vl53l1_api_debug.c
00622 
00623     VL53L1_Error vl53L1_get_additional_data(
00624         VL53L1_DEV                       Dev,
00625         VL53L1_additional_data_t        *pdata);
00626 
00627 
00628  protected:
00629 
00630     /* IO Device */
00631     ToF_DevI2C *dev_i2c;
00632     
00633     /* Digital out pin */
00634     DigitalOut *_gpio0;
00635     /* GPIO expander */
00636     Stmpe1600DigiOut *_expgpio0;
00637     /* Measure detection IRQ */
00638     InterruptIn *_gpio1Int;
00639  
00640     ///* Digital out pin */
00641     //int gpio0;
00642     //int gpio1Int;
00643     /* Device data */
00644     VL53L1_Dev_t MyDevice;
00645     VL53L1_DEV Device;
00646 };
00647 
00648 
00649 #endif /* _VL53L1X_CLASS_H_ */