Initial release. Mbed library for VL53L1CB

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers vl53l1x.cpp Source File

vl53l1x.cpp

00001 /**
00002  ******************************************************************************
00003  * @file    vl53l1x_class.cpp
00004  * @author  JS
00005  * @version V0.0.1
00006  * @date    15-January-2019
00007  * @brief   Implementation file for the VL53L1 sensor component driver class
00008  ******************************************************************************
00009  * @attention
00010  *
00011  * <h2><center>&copy; COPYRIGHT(c) 2018 STMicroelectronics</center></h2>
00012  *
00013  * Redistribution and use in source and binary forms, with or without modification,
00014  * are permitted provided that the following conditions are met:
00015  *   1. Redistributions of source code must retain the above copyright notice,
00016  *      this list of conditions and the following disclaimer.
00017  *   2. Redistributions in binary form must reproduce the above copyright notice,
00018  *      this list of conditions and the following disclaimer in the documentation
00019  *      and/or other materials provided with the distribution.
00020  *   3. Neither the name of STMicroelectronics nor the names of its contributors
00021  *      may be used to endorse or promote products derived from this software
00022  *      without specific prior written permission.
00023  *
00024  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00025  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00026  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00027  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00028  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00029  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00030  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00032  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00033  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  ******************************************************************************
00036 */
00037 
00038 /* Includes */
00039 #include <stdlib.h>
00040 #include "vl53l1x.h"
00041 /************************************************/
00042 #include "vl53l1_platform_user_config.h"
00043 #include "vl53l1_def.h"
00044 #include "vl53l1_wait.h"
00045 #include "vl53l1_api.h"
00046 #include "vl53l1_api_debug.h"
00047 #include "vl53l1_api_strings.h"
00048 #include "vl53l1_preset_setup.h"
00049 #include "vl53l1_api_calibration.h"
00050 #include "vl53l1_nvm_structs.h"
00051 #include "vl53l1_nvm.h"
00052 #include "vl53l1_core.h"
00053 #include "vl53l1_register_funcs.h"
00054 /***********************************************************/
00055 #include "vl53l1_api_core.h"
00056 
00057 #include "vl53l1x_configuration.h"
00058 
00059 
00060 #ifndef MIN
00061 #define MIN(v1, v2) ((v1) < (v2) ? (v1) : (v2))
00062 #endif
00063 #ifndef MAX
00064 #define MAX(v1, v2) ((v1) < (v2) ? (v2) : (v1))
00065 #endif
00066 
00067 
00068 VL53L1X_ERROR VL53L1X::VL53L1X_GetSWVersion(VL53L1X_Version_t *pVersion)
00069 {
00070     VL53L1X_ERROR Status = 0;
00071 
00072     pVersion->major  = VL53L1X_IMPLEMENTATION_VER_MAJOR;
00073     pVersion->minor  = VL53L1X_IMPLEMENTATION_VER_MINOR;
00074     pVersion->build  = VL53L1X_IMPLEMENTATION_VER_SUB;
00075     pVersion->revision  = VL53L1X_IMPLEMENTATION_VER_REVISION;
00076     return Status;
00077 }
00078 
00079 VL53L1X_ERROR VL53L1X::vl53L1X_SetI2CAddress(uint8_t new_address)
00080 {
00081     VL53L1X_ERROR status = 0;
00082   //  status = (VL53L1X_ERROR)VL53L1_SetDeviceAddress(Device,new_address);
00083     
00084 
00085   //  Device->i2c_slave_address = new_address;  //~~ was
00086     if ( Device->i2c_slave_address != new_address)
00087     {
00088         status = VL53L1_WrByte(Device, VL53L1_I2C_SLAVE__DEVICE_ADDRESS, new_address >> 1);   
00089         printf("VL53L1X_SetI2CAddress %d to %d status = %d\n", Device->i2c_slave_address,new_address,status);
00090                 Device->i2c_slave_address = new_address; 
00091 
00092     }
00093     return status;
00094 }
00095 
00096 int VL53L1X::init_sensor(uint8_t new_addr)
00097 {
00098     Device->i2c_slave_address = new_addr;
00099     int status = 0;
00100     VL53L1_Off();
00101     VL53L1_On();
00102 
00103     status = is_present();
00104     if (!status) {
00105         printf("Failed to init VL53L0X sensor!\n\r");
00106         return status;
00107     }
00108     return status;
00109 }
00110 
00111 
00112 VL53L1X_ERROR VL53L1X::VL53L1X_SensorInit()
00113 {
00114     VL53L1X_ERROR status = 0;
00115     uint8_t Addr = 0x00;
00116 
00117     for (Addr = 0x2D; Addr <= 0x87; Addr++){
00118         status = VL53L1_WrByte(Device, Addr, VL51L1X_DEFAULT_CONFIGURATION[Addr - 0x2D]);
00119         if (status != 0)
00120         {
00121             printf("Writing config failed - %d\r\n", status);
00122         }
00123     }
00124     
00125  //   uint16_t sensorID= 0;
00126 //    status = VL53L1X_GetSensorId(&sensorID);
00127  //   printf("Sensor id is - %d (%X)\r\n", sensorID, sensorID);
00128     
00129     status = VL53L1X_StartRanging();
00130     if (status != 0)
00131     {
00132         printf("start ranging failed - %d\r\n", status);
00133     }
00134  
00135     status = VL53L1X_ClearInterrupt();
00136     status = VL53L1X_StopRanging();
00137     status = VL53L1_WrByte(Device, VL53L1_VHV_CONFIG__TIMEOUT_MACROP_LOOP_BOUND, 0x09); // two bounds VHV 
00138     status = VL53L1_WrByte(Device, 0x0B, 0); // start VHV from the previous temperature 
00139     return status;
00140 }
00141 
00142 
00143 VL53L1X_ERROR VL53L1X::VL53L1X_ClearInterrupt()
00144 {
00145     VL53L1X_ERROR status = 0;
00146 
00147     status = VL53L1_WrByte(Device, SYSTEM__INTERRUPT_CLEAR, 0x01);
00148     printf("VL53L1X::VL53L1X_ClearInterrupt()\n");
00149     return status;
00150 }
00151 
00152 
00153 
00154 
00155 
00156 VL53L1X_ERROR VL53L1X::VL53L1X_GetInterruptPolarity(uint8_t *pInterruptPolarity)
00157 {
00158     uint8_t Temp;
00159     VL53L1X_ERROR status = 0;
00160 
00161     status = VL53L1_RdByte(Device, GPIO_HV_MUX__CTRL, &Temp);
00162     Temp = Temp & 0x10;
00163     *pInterruptPolarity = !(Temp>>4);
00164     return status;
00165 }
00166 
00167 
00168 
00169 VL53L1X_ERROR VL53L1X::VL53L1X_StartRanging()
00170 {
00171     VL53L1X_ERROR status = 0;
00172 
00173     status = VL53L1_WrByte(Device, SYSTEM__MODE_START, 0x40); 
00174     return status;
00175 }
00176 
00177 
00178 VL53L1X_ERROR VL53L1X::VL53L1X_StopRanging()
00179 {
00180     VL53L1X_ERROR status = 0;
00181 
00182     status = VL53L1_WrByte(Device, SYSTEM__MODE_START, 0x00);   
00183     return status;
00184 }
00185 
00186 
00187 
00188 
00189 VL53L1X_ERROR VL53L1X::vl53L1X_BootState(uint8_t *state)
00190 {
00191     VL53L1X_ERROR status = 0;
00192     uint8_t tmp = 0;
00193 
00194     status = VL53L1_RdByte(Device,VL53L1_FIRMWARE__SYSTEM_STATUS, &tmp);
00195     *state = tmp;
00196     return status;
00197 }
00198 
00199 
00200 VL53L1X_ERROR VL53L1X::VL53L1X_GetDistance(uint16_t *distance)
00201 {
00202     VL53L1X_ERROR status = 0;
00203     uint16_t tmp;
00204 
00205     status = (VL53L1_RdWord(Device,
00206             VL53L1_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0, &tmp));
00207     *distance = tmp;
00208     return status;
00209 }
00210 
00211 
00212     /* Write and read functions from I2C */
00213 
00214 
00215 VL53L1X_ERROR VL53L1X::VL53L1_WriteMulti(VL53L1_DEV Dev, uint16_t index, uint8_t *pdata, uint32_t count)
00216 {
00217    int  status;
00218 //printf(" class VL53L1_WriteMulti \n");
00219    status = VL53L1_I2CWrite(Dev->i2c_slave_address, index, pdata, (uint16_t)count);
00220    return status;
00221 }
00222 
00223 VL53L1X_ERROR VL53L1X::VL53L1_ReadMulti(VL53L1_DEV Dev, uint16_t index, uint8_t *pdata, uint32_t count)
00224 {
00225     int status;
00226 
00227     status = VL53L1_I2CRead(Dev->i2c_slave_address, index, pdata, (uint16_t)count);
00228 
00229     return status;
00230 }
00231 
00232 
00233 VL53L1X_ERROR VL53L1X::VL53L1_WrByte(VL53L1_DEV Dev, uint16_t index, uint8_t data)
00234 {
00235    int  status;
00236 
00237    status=VL53L1_I2CWrite(Dev->i2c_slave_address, index, &data, 1);
00238    return status;
00239 }
00240 
00241 VL53L1X_ERROR VL53L1X::VL53L1_WrWord(VL53L1_DEV Dev, uint16_t index, uint16_t data)
00242 {
00243    int  status;
00244    uint8_t buffer[2];
00245 
00246      buffer[0] = data >> 8;
00247      buffer[1] = data & 0x00FF;
00248    status=VL53L1_I2CWrite(Dev->i2c_slave_address, index, (uint8_t *)buffer, 2);
00249    return status;
00250 }
00251 
00252 VL53L1X_ERROR VL53L1X::VL53L1_WrDWord(VL53L1_DEV Dev, uint16_t index, uint32_t data)
00253 {
00254    int  status;
00255    uint8_t buffer[4];
00256 
00257      buffer[0] = (data >> 24) & 0xFF;
00258      buffer[1] = (data >> 16) & 0xFF;
00259      buffer[2] = (data >>  8) & 0xFF;
00260      buffer[3] = (data >>  0) & 0xFF;
00261    status=VL53L1_I2CWrite(Dev->i2c_slave_address, index, (uint8_t *)buffer, 4);
00262    return status;
00263 }
00264 
00265 
00266 VL53L1X_ERROR VL53L1X::VL53L1_RdByte(VL53L1_DEV Dev, uint16_t index, uint8_t *data)
00267 {
00268    int  status;
00269 
00270    status = VL53L1_I2CRead(Dev->i2c_slave_address, index, data, 1);
00271 
00272    if(status)
00273      return -1;
00274 
00275    return 0;
00276 }
00277 
00278 VL53L1X_ERROR VL53L1X::VL53L1_RdWord(VL53L1_DEV Dev, uint16_t index, uint16_t *data)
00279 {
00280    int  status;
00281    uint8_t buffer[2] = {0,0};
00282 
00283    status = VL53L1_I2CRead(Dev->i2c_slave_address, index, buffer, 2);
00284    if (!status)
00285    {
00286        *data = (buffer[0] << 8) + buffer[1];
00287    }
00288  //  printf("VL53L1_RdWord %d %d %d \n",Dev->i2c_slave_address,index,status);
00289    return status;
00290 
00291 }
00292 
00293 VL53L1X_ERROR VL53L1X::VL53L1_RdDWord(VL53L1_DEV Dev, uint16_t index, uint32_t *data)
00294 {
00295    int status;
00296    uint8_t buffer[4] = {0,0,0,0};
00297 
00298    status = VL53L1_I2CRead(Dev->i2c_slave_address, index, buffer, 4);
00299    if(!status)
00300    {
00301        *data = (buffer[0] << 24) + (buffer[1] << 16) + (buffer[2] << 8) + buffer[3];
00302    }
00303    return status;
00304 
00305 }
00306 
00307 VL53L1X_ERROR VL53L1X::VL53L1_UpdateByte(VL53L1_DEV Dev, uint16_t index, uint8_t AndData, uint8_t OrData)
00308 {
00309    int  status;
00310    uint8_t buffer = 0;
00311 
00312    /* read data direct onto buffer */
00313    status = VL53L1_I2CRead(Dev->i2c_slave_address, index, &buffer,1);
00314    if (!status)
00315    {
00316       buffer = (buffer & AndData) | OrData;
00317       status = VL53L1_I2CWrite(Dev->i2c_slave_address, index, &buffer, (uint16_t)1);
00318    }
00319    return status;
00320 }
00321 
00322 VL53L1X_ERROR VL53L1X::VL53L1_I2CWrite(uint8_t DeviceAddr, uint16_t RegisterAddr, uint8_t* pBuffer, uint16_t NumByteToWrite)
00323 {
00324     int ret;
00325     ret = dev_i2c->ToF_i2c_write(pBuffer, DeviceAddr, RegisterAddr, NumByteToWrite);
00326     if (ret) {
00327         return -1;
00328     }
00329     return 0;
00330 
00331 }
00332 
00333 VL53L1X_ERROR VL53L1X::VL53L1_I2CRead(uint8_t DeviceAddr, uint16_t RegisterAddr, uint8_t* pBuffer, uint16_t NumByteToRead)
00334 {
00335     int ret;
00336 
00337     ret = dev_i2c->ToF_i2c_read(pBuffer, DeviceAddr, RegisterAddr, NumByteToRead);
00338     //ret = dev_i2c->i2c_read(pBuffer, DeviceAddr, RegisterAddr, NumByteToRead);
00339     if (ret) {
00340         return -1;
00341     }
00342     return 0;
00343 }
00344 
00345 
00346 VL53L1X_ERROR VL53L1X::VL53L1_GetTickCount(
00347     uint32_t *ptick_count_ms)
00348 {
00349 
00350     /* Returns current tick count in [ms] */
00351 
00352     VL53L1X_ERROR status  = VL53L1_ERROR_NONE;
00353 
00354     //*ptick_count_ms = timeGetTime();
00355     *ptick_count_ms = us_ticker_read() / 1000;
00356 
00357     return status;
00358 }
00359 
00360 
00361 
00362 VL53L1X_ERROR VL53L1X::VL53L1_WaitUs(VL53L1_Dev_t *pdev, int32_t wait_time)
00363 {
00364     //(void)pdev;
00365       wait_us(wait_time);
00366     return VL53L1_ERROR_NONE;
00367 }
00368 
00369 
00370 VL53L1X_ERROR VL53L1X::VL53L1_WaitMs(VL53L1_Dev_t *pdev, int32_t wait_time)
00371 {
00372     //(void)pdev;
00373     wait_ms(wait_time);
00374     return VL53L1_ERROR_NONE;
00375 }
00376 
00377 
00378 VL53L1X_ERROR VL53L1X::vl53L1_WaitValueMaskEx(
00379     VL53L1_Dev_t *pdev,
00380     uint32_t      timeout_ms,
00381     uint16_t      index,
00382     uint8_t       value,
00383     uint8_t       mask,
00384     uint32_t      poll_delay_ms)
00385 {
00386 
00387     /*
00388      * Platform implementation of WaitValueMaskEx V2WReg script command
00389      *
00390      * WaitValueMaskEx(
00391      *          duration_ms,
00392      *          index,
00393      *          value,
00394      *          mask,
00395      *          poll_delay_ms);
00396      */
00397 
00398 
00399     return VL53L1_WaitValueMaskEx( pdev, timeout_ms,index, value, mask, poll_delay_ms);
00400 }
00401 
00402 
00403 /***************************************************************************/
00404 //VL53L1X_ERROR VL53L1X::VL53L1_WaitValueMaskEx(
00405 
00406 VL53L1X_ERROR VL53L1X::vl53L1_WaitDeviceBooted(VL53L1_DEV Dev)
00407 {
00408 
00409     return VL53L1_WaitDeviceBooted(Dev);
00410 }
00411 
00412 
00413 static int32_t BDTable[VL53L1_TUNING_MAX_TUNABLE_KEY] = {
00414         TUNING_VERSION,
00415         TUNING_PROXY_MIN,
00416         TUNING_SINGLE_TARGET_XTALK_TARGET_DISTANCE_MM,
00417         TUNING_SINGLE_TARGET_XTALK_SAMPLE_NUMBER,
00418         TUNING_MIN_AMBIENT_DMAX_VALID,
00419         TUNING_MAX_SIMPLE_OFFSET_CALIBRATION_SAMPLE_NUMBER,
00420         TUNING_XTALK_FULL_ROI_TARGET_DISTANCE_MM,
00421         TUNING_SIMPLE_OFFSET_CALIBRATION_REPEAT,
00422         TUNING_XTALK_FULL_ROI_BIN_SUM_MARGIN,
00423         TUNING_XTALK_FULL_ROI_DEFAULT_OFFSET,
00424         TUNING_ZERO_DISTANCE_OFFSET_NON_LINEAR_FACTOR_DEFAULT,
00425 };
00426 
00427 
00428 VL53L1X_ERROR VL53L1X::vl53L1_GetVersion(VL53L1_Version_t *pVersion)
00429 {
00430 
00431     return VL53L1_GetVersion(pVersion);
00432 }
00433 
00434 
00435 VL53L1X_ERROR VL53L1X::vl53L1_GetProductRevision(
00436     uint8_t *pProductRevisionMajor, uint8_t *pProductRevisionMinor)
00437 {
00438     return VL53L1_GetProductRevision(Device,pProductRevisionMajor,pProductRevisionMinor);
00439 }
00440 
00441 //******************************************************************
00442 
00443 
00444 VL53L1X_ERROR VL53L1X::vl53L1_GetDeviceInfo(
00445     VL53L1_DeviceInfo_t *pVL53L1_DeviceInfo)
00446 {
00447     return VL53L1_GetDeviceInfo(Device,pVL53L1_DeviceInfo);
00448 }
00449 
00450 VL53L1X_ERROR VL53L1X::vl53L1_GetUID( uint64_t *pUid)
00451 {
00452     return VL53L1_GetUID(Device,pUid);
00453 }
00454 
00455 VL53L1X_ERROR VL53L1X::vl53L1_GetRangeStatusString(uint8_t RangeStatus,
00456     char *pRangeStatusString)
00457 {
00458     return VL53L1_GetRangeStatusString(RangeStatus,
00459         pRangeStatusString);
00460 }
00461 
00462 VL53L1X_ERROR VL53L1X::vl53L1_GetPalErrorString(VL53L1_Error PalErrorCode,
00463     char *pPalErrorString)
00464 {
00465     return VL53L1_GetPalErrorString(PalErrorCode,pPalErrorString);
00466 }
00467 
00468 VL53L1X_ERROR VL53L1X::vl53L1_GetPalStateString(VL53L1_State PalStateCode,
00469     char *pPalStateString)
00470 {
00471     return VL53L1_GetPalStateString(PalStateCode, pPalStateString);
00472 }
00473 
00474 VL53L1X_ERROR VL53L1X::vl53L1_GetPalState(VL53L1_DEV Dev, VL53L1_State *pPalState)
00475 {
00476     return VL53L1_GetPalState(Dev,pPalState);
00477 }
00478 
00479 
00480 VL53L1X_ERROR VL53L1X::VL53L1_SetDeviceAddress(VL53L1_DEV Dev, uint8_t DeviceAddress)
00481 {
00482     VL53L1_Error Status = VL53L1_ERROR_NONE;
00483 
00484  //   LOG_FUNCTION_START("");
00485 
00486     Status = VL53L1_WrByte(Dev, VL53L1_I2C_SLAVE__DEVICE_ADDRESS,
00487             DeviceAddress / 2);
00488 
00489 //    LOG_FUNCTION_END(Status);
00490     return Status;
00491 }
00492 
00493 VL53L1X_ERROR VL53L1X::vl53L1_DataInit()
00494 {
00495     printf("vl53L1_DataInit %d \n",Device->i2c_slave_address);
00496     return VL53L1_DataInit( Device);
00497 }
00498 
00499 
00500 VL53L1X_ERROR VL53L1X::vl53L1_StaticInit()
00501 {
00502     return VL53L1_StaticInit( Device);
00503 }
00504 
00505 
00506  VL53L1X_ERROR VL53L1X::vl53L1_SetPresetMode(VL53L1_PresetModes PresetMode)
00507 {
00508     return VL53L1_SetPresetMode(Device,PresetMode);
00509 }
00510 
00511 
00512  VL53L1X_ERROR VL53L1X::vl53L1_GetPresetMode( VL53L1_PresetModes *pPresetMode)
00513 {
00514     return VL53L1_GetPresetMode(Device,pPresetMode);
00515 }
00516 
00517 
00518  VL53L1X_ERROR VL53L1X::vl53L1_SetDistanceMode(VL53L1_DistanceModes DistanceMode)
00519 {
00520     return VL53L1_SetDistanceMode(Device,DistanceMode);
00521 }
00522 
00523 VL53L1X_ERROR VL53L1X::vl53L1_GetDistanceMode(VL53L1_DistanceModes *pDistanceMode)
00524 {
00525     return VL53L1_GetDistanceMode(Device,pDistanceMode);
00526 }
00527 
00528 VL53L1X_ERROR VL53L1X::vl53L1_SetOutputMode(VL53L1_OutputModes OutputMode)
00529 {
00530     return VL53L1_SetOutputMode(Device,OutputMode);
00531 }
00532 
00533 VL53L1X_ERROR VL53L1X::vl53L1_GetOutputMode(VL53L1_OutputModes *pOutputMode)
00534 {
00535     return VL53L1_GetOutputMode(Device,pOutputMode);
00536 }
00537 
00538 
00539 
00540 VL53L1X_ERROR VL53L1X::vl53L1_SetMeasurementTimingBudgetMicroSeconds(
00541                                    uint32_t MeasurementTimingBudgetMicroSeconds)
00542 {
00543     return VL53L1_SetMeasurementTimingBudgetMicroSeconds(Device,
00544                                            MeasurementTimingBudgetMicroSeconds);
00545 }
00546 
00547 
00548 VL53L1X_ERROR VL53L1X::vl53L1_GetMeasurementTimingBudgetMicroSeconds(
00549                                  uint32_t *pMeasurementTimingBudgetMicroSeconds)
00550 {
00551     return VL53L1_GetMeasurementTimingBudgetMicroSeconds(Device,
00552                                         pMeasurementTimingBudgetMicroSeconds);
00553 }
00554 
00555 
00556 
00557 VL53L1X_ERROR VL53L1X::vl53L1_SetInterMeasurementPeriodMilliSeconds(
00558     uint32_t InterMeasurementPeriodMilliSeconds)
00559 {   
00560     return VL53L1_SetInterMeasurementPeriodMilliSeconds(Device,InterMeasurementPeriodMilliSeconds);
00561 }
00562 
00563 VL53L1X_ERROR VL53L1X::vl53L1_GetInterMeasurementPeriodMilliSeconds(
00564     uint32_t *pInterMeasurementPeriodMilliSeconds)
00565 {
00566     return VL53L1_GetInterMeasurementPeriodMilliSeconds(Device,pInterMeasurementPeriodMilliSeconds);
00567 }
00568 
00569 VL53L1X_ERROR VL53L1X::vl53L1_SetDmaxReflectance(FixPoint1616_t DmaxReflectance)
00570 {
00571 
00572     return VL53L1_SetDmaxReflectance(Device,DmaxReflectance);
00573 }
00574 
00575 VL53L1X_ERROR VL53L1X::vl53L1_GetDmaxReflectance(
00576                                            FixPoint1616_t *pDmaxReflectance)
00577 {
00578     return VL53L1_GetDmaxReflectance(Device,pDmaxReflectance);
00579 }
00580 
00581 
00582 VL53L1X_ERROR VL53L1X::vl53L1_SetDmaxMode(VL53L1_DeviceDmaxModes DmaxMode)
00583 {
00584     return VL53L1_SetDmaxMode(Device,DmaxMode);
00585 }
00586 
00587 
00588 VL53L1X_ERROR VL53L1X::vl53L1_GetDmaxMode(
00589     VL53L1_DeviceDmaxModes *pDmaxMode)
00590 {
00591     return VL53L1_GetDmaxMode(Device,pDmaxMode);
00592 }
00593 
00594 
00595 
00596 VL53L1X_ERROR VL53L1X::vl53L1_GetNumberOfLimitCheck(uint16_t *pNumberOfLimitCheck)
00597 {
00598     VL53L1_Error Status = VL53L1_ERROR_NONE;
00599 
00600   //  LOG_FUNCTION_START("");
00601 
00602     *pNumberOfLimitCheck = VL53L1_CHECKENABLE_NUMBER_OF_CHECKS;
00603 
00604  //   LOG_FUNCTION_END(Status);
00605     return Status;
00606 }
00607 
00608 VL53L1X_ERROR VL53L1X::vl53L1_GetLimitCheckInfo(uint16_t LimitCheckId,
00609     char *pLimitCheckString)
00610 {
00611     return VL53L1_GetLimitCheckInfo(LimitCheckId,
00612         pLimitCheckString);
00613 
00614 }
00615 
00616 VL53L1X_ERROR VL53L1X::vl53L1_GetLimitCheckStatus(uint16_t LimitCheckId,
00617     uint8_t *pLimitCheckStatus)
00618 {
00619     return VL53L1_GetLimitCheckStatus(Device,LimitCheckId,pLimitCheckStatus);
00620 }
00621 
00622 
00623 VL53L1X_ERROR VL53L1X::vl53L1_SetLimitCheckEnable(uint16_t LimitCheckId,
00624     uint8_t LimitCheckEnable)
00625 {
00626 
00627     return VL53L1_SetLimitCheckEnable(Device,LimitCheckId,LimitCheckEnable);
00628 }
00629 
00630 VL53L1X_ERROR VL53L1X::vl53L1_GetLimitCheckEnable(uint16_t LimitCheckId,
00631     uint8_t *pLimitCheckEnable)
00632 {
00633     return VL53L1_GetLimitCheckEnable(Device,LimitCheckId,pLimitCheckEnable);
00634 }
00635 
00636 VL53L1X_ERROR VL53L1X::vl53L1_SetLimitCheckValue( uint16_t LimitCheckId,
00637     FixPoint1616_t LimitCheckValue)
00638 {
00639     return VL53L1_SetLimitCheckValue(Device,LimitCheckId,LimitCheckValue);
00640 }
00641 
00642 VL53L1X_ERROR VL53L1X::vl53L1_GetLimitCheckValue( uint16_t LimitCheckId,
00643     FixPoint1616_t *pLimitCheckValue)
00644 {
00645     return VL53L1_GetLimitCheckValue(Device,LimitCheckId,pLimitCheckValue);
00646 }
00647 
00648 VL53L1X_ERROR VL53L1X::vl53L1_GetLimitCheckCurrent( uint16_t LimitCheckId,
00649     FixPoint1616_t *pLimitCheckCurrent)
00650 {
00651     return VL53L1_GetLimitCheckCurrent(Device,LimitCheckId,pLimitCheckCurrent);
00652 }
00653 
00654 
00655 VL53L1X_ERROR VL53L1X::vl53L1_GetMaxNumberOfROI( uint8_t *pMaxNumberOfROI)
00656 {
00657     return VL53L1_GetMaxNumberOfROI(Device,pMaxNumberOfROI);
00658 }
00659 
00660 VL53L1X_ERROR VL53L1X::vl53L1_SetROI( VL53L1_RoiConfig_t *pRoiConfig)
00661 {
00662 
00663     return VL53L1_SetROI(Device,pRoiConfig);
00664 }
00665 
00666 VL53L1X_ERROR VL53L1X::vl53L1_GetROI(VL53L1_RoiConfig_t *pRoiConfig)
00667 {
00668     return VL53L1_GetROI(Device,pRoiConfig);
00669 }
00670 
00671 
00672 
00673 
00674 VL53L1X_ERROR VL53L1X::vl53L1_GetNumberOfSequenceSteps(uint8_t *pNumberOfSequenceSteps)
00675 {
00676     VL53L1_Error Status = VL53L1_ERROR_NONE;
00677 
00678  //   SUPPRESS_UNUSED_WARNING(Dev);
00679 
00680  //   LOG_FUNCTION_START("");
00681 
00682     *pNumberOfSequenceSteps = VL53L1_SEQUENCESTEP_NUMBER_OF_ITEMS;
00683 
00684 //    LOG_FUNCTION_END(Status);
00685     return Status;
00686 }
00687 
00688 VL53L1X_ERROR VL53L1X::vl53L1_GetSequenceStepsInfo(VL53L1_SequenceStepId SequenceStepId,
00689     char *pSequenceStepsString)
00690 {
00691     return VL53L1_GetSequenceStepsInfo(SequenceStepId,pSequenceStepsString);
00692 }
00693 
00694 VL53L1X_ERROR VL53L1X::vl53L1_SetSequenceStepEnable(VL53L1_SequenceStepId SequenceStepId,
00695                                                     uint8_t SequenceStepEnabled)
00696 {
00697 
00698     return VL53L1_SetSequenceStepEnable(Device,SequenceStepId,SequenceStepEnabled);
00699 }
00700 
00701 
00702 VL53L1X_ERROR VL53L1X::vl53L1_GetSequenceStepEnable(VL53L1_SequenceStepId SequenceStepId, 
00703                                                     uint8_t *pSequenceStepEnabled)
00704 {
00705     return VL53L1_GetSequenceStepEnable(Device,SequenceStepId,pSequenceStepEnabled);
00706 }
00707 
00708 
00709 
00710 VL53L1X_ERROR VL53L1X::vl53L1_StartMeasurement()
00711 {
00712     return VL53L1_StartMeasurement(Device);
00713 }
00714 
00715 VL53L1X_ERROR VL53L1X::vl53L1_StopMeasurement()
00716 {
00717     return VL53L1_StopMeasurement(Device);
00718 }
00719 
00720 
00721 VL53L1X_ERROR VL53L1X::vl53L1_ClearInterruptAndStartMeasurement()
00722 {
00723 
00724     return VL53L1_ClearInterruptAndStartMeasurement(Device);
00725 }
00726 
00727 
00728 VL53L1X_ERROR VL53L1X::vl53L1_GetMeasurementDataReady(uint8_t *pMeasurementDataReady)
00729 {
00730     return VL53L1_GetMeasurementDataReady(Device, pMeasurementDataReady);
00731 }
00732 
00733 VL53L1X_ERROR VL53L1X::vl53L1_WaitMeasurementDataReady()
00734 {
00735     return VL53L1_WaitMeasurementDataReady(Device);
00736 }
00737 
00738 
00739 //******************************************************************
00740 
00741 
00742 
00743 VL53L1X_ERROR VL53L1X::vl53L1_GetCalibrationData(
00744         VL53L1_CalibrationData_t  *pCalibrationData)
00745 {
00746     
00747     VL53L1_Error Status = VL53L1_ERROR_NONE;
00748     Status = VL53L1_GetCalibrationData(Device,pCalibrationData);
00749 
00750     return Status;
00751 }
00752 
00753 
00754 VL53L1X_ERROR VL53L1X::vl53L1_GetRangingMeasurementData(
00755     VL53L1_RangingMeasurementData_t *pRangingMeasurementData)
00756 {
00757 //              printf("   VL53L1_GetRangingMeasurementData 000  \n");  
00758     VL53L1_Error Status = VL53L1_ERROR_NONE;
00759     Status = VL53L1_GetRangingMeasurementData(Device,pRangingMeasurementData);
00760 
00761     return Status;
00762 }
00763 
00764 
00765 
00766 
00767 
00768 VL53L1X_ERROR VL53L1X::vl53L1_GetMultiRangingData(
00769         VL53L1_MultiRangingData_t *pMultiRangingData)
00770 {
00771     return VL53L1_GetMultiRangingData(Device,pMultiRangingData);
00772 }
00773 
00774 VL53L1X_ERROR VL53L1X::vl53L1_GetAdditionalData(
00775         VL53L1_AdditionalData_t *pAdditionalData)
00776 {
00777     return VL53L1_GetAdditionalData(Device, pAdditionalData);
00778 }
00779 
00780 
00781 
00782 VL53L1X_ERROR VL53L1X::vl53L1_SetTuningParameter(
00783         uint16_t TuningParameterId, int32_t TuningParameterValue)
00784 {
00785     return VL53L1_SetTuningParameter(Device,TuningParameterId,TuningParameterValue);
00786 }
00787 
00788 VL53L1X_ERROR VL53L1X::vl53L1_GetTuningParameter(
00789         uint16_t TuningParameterId, int32_t *pTuningParameterValue)
00790 {
00791 
00792     return VL53L1_GetTuningParameter(Device,TuningParameterId,pTuningParameterValue);
00793 }
00794 
00795 
00796 VL53L1X_ERROR VL53L1X::vl53L1_SetXTalkCompensationEnable(
00797     uint8_t XTalkCompensationEnable)
00798 {
00799 
00800     return  VL53L1_SetXTalkCompensationEnable(Device,XTalkCompensationEnable);
00801 }
00802 
00803 
00804 VL53L1X_ERROR VL53L1X::vl53L1_GetXTalkCompensationEnable(
00805     uint8_t *pXTalkCompensationEnable)
00806 {
00807     VL53L1_Error Status = VL53L1_ERROR_NONE;
00808 
00809   //  LOG_FUNCTION_START("");
00810 
00811     VL53L1_GetXTalkCompensationEnable(
00812         Device,
00813         pXTalkCompensationEnable);
00814 
00815   //  LOG_FUNCTION_END(Status);
00816     return Status;
00817 }
00818 
00819 
00820 VL53L1X_ERROR VL53L1X::vl53L1_PerformXTalkCalibration(
00821         uint8_t CalibrationOption)
00822 {
00823 
00824     return VL53L1_PerformXTalkCalibration(Device,CalibrationOption);
00825 }
00826 
00827 VL53L1X_ERROR VL53L1X::vl53L1_SetOffsetCalibrationMode(
00828         VL53L1_OffsetCalibrationModes OffsetCalibrationMode)
00829 {
00830     return VL53L1_SetOffsetCalibrationMode(Device,OffsetCalibrationMode);
00831 }
00832 
00833 VL53L1X_ERROR VL53L1X::vl53L1_SetOffsetCorrectionMode(
00834         VL53L1_OffsetCorrectionModes OffsetCorrectionMode)
00835 {
00836     return  VL53L1_SetOffsetCorrectionMode(Device,OffsetCorrectionMode);
00837 }
00838 
00839 VL53L1X_ERROR VL53L1X::vl53L1_PerformOffsetCalibration(
00840     int32_t CalDistanceMilliMeter, FixPoint1616_t CalReflectancePercent)
00841 {
00842     return VL53L1_PerformOffsetCalibration(Device,CalDistanceMilliMeter,CalReflectancePercent);
00843 }
00844 
00845 VL53L1X_ERROR VL53L1X::vl53L1_PerformOffsetSimpleCalibration(
00846     int32_t CalDistanceMilliMeter)
00847 {
00848     return VL53L1_PerformOffsetSimpleCalibration(Device,CalDistanceMilliMeter);
00849 }
00850 
00851 VL53L1X_ERROR VL53L1X::vl53L1_PerformOffsetZeroDistanceCalibration()
00852 {
00853     return VL53L1_PerformOffsetZeroDistanceCalibration(Device);
00854 }
00855 
00856 VL53L1X_ERROR VL53L1X::vl53L1_SetCalibrationData(
00857         VL53L1_CalibrationData_t *pCalibrationData)
00858 {
00859     return VL53L1_SetCalibrationData(Device,pCalibrationData);
00860 }
00861 
00862 
00863 VL53L1X_ERROR VL53L1X::vl53L1_SetZoneCalibrationData(
00864         VL53L1_ZoneCalibrationData_t *pZoneCalibrationData)
00865 {
00866     return VL53L1_SetZoneCalibrationData(Device, pZoneCalibrationData);
00867 }
00868 
00869 VL53L1X_ERROR VL53L1X::vl53L1_GetZoneCalibrationData(
00870         VL53L1_ZoneCalibrationData_t  *pZoneCalibrationData)
00871 {
00872     return VL53L1_GetZoneCalibrationData(Device, pZoneCalibrationData);
00873 }
00874 
00875 VL53L1_Error VL53L1X::vl53L1_SmudgeCorrectionEnable(
00876         VL53L1_SmudgeCorrectionModes Mode)
00877         
00878 {
00879     return VL53L1_SmudgeCorrectionEnable(Device, Mode);
00880 }
00881 
00882 VL53L1X_ERROR VL53L1X::vl53L1_GetOpticalCenter(
00883         FixPoint1616_t *pOpticalCenterX,
00884         FixPoint1616_t *pOpticalCenterY)
00885 {
00886     return VL53L1_GetOpticalCenter(Device,pOpticalCenterX,pOpticalCenterY);
00887 }
00888 
00889 
00890 
00891 
00892 
00893 
00894 VL53L1X_ERROR VL53L1X::vl53L1_SetThresholdConfig(VL53L1_DetectionConfig_t *pConfig)
00895 {
00896     return VL53L1_SetThresholdConfig(Device,pConfig);
00897 }
00898 
00899 
00900 VL53L1X_ERROR VL53L1X::vl53L1_GetThresholdConfig(VL53L1_DetectionConfig_t *pConfig)
00901 {
00902     return VL53L1_GetThresholdConfig(Device,pConfig);
00903 }
00904 
00905 
00906 
00907 
00908 VL53L1X_ERROR VL53L1X::vl53L1_PerformOffsetPerVcselCalibration(int32_t CalDistanceMilliMeter)
00909 {
00910     return VL53L1_PerformOffsetPerVcselCalibration(Device,CalDistanceMilliMeter);
00911 }
00912 
00913 
00914 
00915 // from vl53l1_api_debug.c
00916 
00917 
00918 VL53L1X_ERROR VL53L1X::vl53L1_get_additional_data(
00919     VL53L1_DEV                      Dev,
00920     VL53L1_additional_data_t        *pdata)
00921 {
00922     return VL53L1_get_additional_data(Dev,pdata);
00923 }
00924 
00925