ST Expansion SW Team / VL53L1

Dependencies:   X_NUCLEO_COMMON ST_INTERFACES

Dependents:   X_NUCLEO_53L1CB

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers VL53l1CB.cpp Source File

VL53l1CB.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 "VL53L1CB.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 "vl53l1_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 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetSWVersion(VL53L1_Version_t *pVersion)
00069 {
00070     VL53L1CB_ERROR Status = 0;
00071 
00072     pVersion->major  = VL53L1CB_IMPLEMENTATION_VER_MAJOR;
00073     pVersion->minor  = VL53L1CB_IMPLEMENTATION_VER_MINOR;
00074     pVersion->build  = VL53L1CB_IMPLEMENTATION_VER_SUB;
00075     pVersion->revision  = VL53L1CB_IMPLEMENTATION_VER_REVISION;
00076     return Status;
00077 }
00078 
00079 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetI2CAddress(uint8_t new_address)
00080 {
00081     VL53L1CB_ERROR status = 0;
00082   //  status = (VL53L1CB_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 = VL53L1CB_WrByte(Device, VL53L1CB_I2C_SLAVE__DEVICE_ADDRESS, new_address >> 1);   
00089         printf("VL53L1_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 VL53L1CB::init_sensor(uint8_t new_addr)
00097 {
00098     Device->i2c_slave_address = new_addr;
00099     int status = 0;
00100     VL53L1CB_Off();
00101     VL53L1CB_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 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SensorInit()
00113 {
00114     VL53L1CB_ERROR status = 0;
00115     uint8_t Addr = 0x00;
00116 
00117     for (Addr = 0x2D; Addr <= 0x87; Addr++){
00118         status = VL53L1CB_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 = VL53L1CB_StartRanging();
00130     if (status != 0)
00131     {
00132         printf("start ranging failed - %d\r\n", status);
00133     }
00134  
00135     status = VL53L1CB_ClearInterrupt();
00136     status = VL53L1CB_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 VL53L1CB_ERROR VL53L1CB::VL53L1CB_ClearInterrupt()
00144 {
00145     VL53L1CB_ERROR status = 0;
00146 
00147     status = VL53L1CB_WrByte(Device, SYSTEM__INTERRUPT_CLEAR, 0x01);
00148 //    printf("VL53L1CB::VL53L1CBX_ClearInterrupt()\n");
00149     return status;
00150 }
00151 
00152 
00153 
00154 
00155 
00156 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetInterruptPolarity(uint8_t *pInterruptPolarity)
00157 {
00158     uint8_t Temp;
00159     VL53L1CB_ERROR status = 0;
00160 
00161     status = VL53L1CB_RdByte(Device, GPIO_HV_MUX__CTRL, &Temp);
00162     Temp = Temp & 0x10;
00163     *pInterruptPolarity = !(Temp>>4);
00164     return status;
00165 }
00166 
00167 
00168 
00169 VL53L1CB_ERROR VL53L1CB::VL53L1CB_StartRanging()
00170 {
00171     VL53L1CB_ERROR status = 0;
00172 
00173     status = VL53L1CB_WrByte(Device, SYSTEM__MODE_START, 0x40); 
00174     return status;
00175 }
00176 
00177 
00178 VL53L1CB_ERROR VL53L1CB::VL53L1CB_StopRanging()
00179 {
00180     VL53L1CB_ERROR status = 0;
00181 
00182     status = VL53L1CB_WrByte(Device, SYSTEM__MODE_START, 0x00);   
00183     return status;
00184 }
00185 
00186 
00187 
00188 
00189 VL53L1CB_ERROR VL53L1CB::VL53L1CB_BootState(uint8_t *state)
00190 {
00191     VL53L1CB_ERROR status = 0;
00192     uint8_t tmp = 0;
00193 
00194     status = VL53L1CB_RdByte(Device,VL53L1CB_FIRMWARE__SYSTEM_STATUS, &tmp);
00195     *state = tmp;
00196     return status;
00197 }
00198 
00199 
00200 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetDistance(uint16_t *distance)
00201 {
00202     VL53L1CB_ERROR status = 0;
00203     uint16_t tmp;
00204 
00205     status = (VL53L1CB_RdWord(Device,
00206             VL53L1CB_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 VL53L1CB_ERROR VL53L1CB::VL53L1CB_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 = VL53L1CB_I2CWrite(Dev->i2c_slave_address, index, pdata, (uint16_t)count);
00220    return status;
00221 }
00222 
00223 VL53L1CB_ERROR VL53L1CB::VL53L1CB_ReadMulti(VL53L1_DEV Dev, uint16_t index, uint8_t *pdata, uint32_t count)
00224 {
00225     int status;
00226 
00227     status = VL53L1CB_I2CRead(Dev->i2c_slave_address, index, pdata, (uint16_t)count);
00228 
00229     return status;
00230 }
00231 
00232 
00233 VL53L1CB_ERROR VL53L1CB::VL53L1CB_WrByte(VL53L1_DEV Dev, uint16_t index, uint8_t data)
00234 {
00235    int  status;
00236 
00237    status=VL53L1CB_I2CWrite(Dev->i2c_slave_address, index, &data, 1);
00238    return status;
00239 }
00240 
00241 VL53L1CB_ERROR VL53L1CB::VL53L1CB_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=VL53L1CB_I2CWrite(Dev->i2c_slave_address, index, (uint8_t *)buffer, 2);
00249    return status;
00250 }
00251 
00252 VL53L1CB_ERROR VL53L1CB::VL53L1CB_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=VL53L1CB_I2CWrite(Dev->i2c_slave_address, index, (uint8_t *)buffer, 4);
00262    return status;
00263 }
00264 
00265 
00266 VL53L1CB_ERROR VL53L1CB::VL53L1CB_RdByte(VL53L1_DEV Dev, uint16_t index, uint8_t *data)
00267 {
00268    int  status;
00269 
00270    status = VL53L1CB_I2CRead(Dev->i2c_slave_address, index, data, 1);
00271 
00272    if(status)
00273      return -1;
00274 
00275    return 0;
00276 }
00277 
00278 VL53L1CB_ERROR VL53L1CB::VL53L1CB_RdWord(VL53L1_DEV Dev, uint16_t index, uint16_t *data)
00279 {
00280    int  status;
00281    uint8_t buffer[2] = {0,0};
00282 
00283    status = VL53L1CB_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 VL53L1CB_ERROR VL53L1CB::VL53L1CB_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 = VL53L1CB_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 VL53L1CB_ERROR VL53L1CB::VL53L1CB_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 = VL53L1CB_I2CRead(Dev->i2c_slave_address, index, &buffer,1);
00314    if (!status)
00315    {
00316       buffer = (buffer & AndData) | OrData;
00317       status = VL53L1CB_I2CWrite(Dev->i2c_slave_address, index, &buffer, (uint16_t)1);
00318    }
00319    return status;
00320 }
00321 
00322 VL53L1CB_ERROR VL53L1CB::VL53L1CB_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 VL53L1CB_ERROR VL53L1CB::VL53L1CB_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 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetTickCount(
00347     uint32_t *ptick_count_ms)
00348 {
00349 
00350     /* Returns current tick count in [ms] */
00351 
00352     VL53L1CB_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 VL53L1CB_ERROR VL53L1CB::VL53L1CB_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 VL53L1CB_ERROR VL53L1CB::VL53L1CB_WaitMs(VL53L1_Dev_t *pdev, int32_t wait_time)
00371 {
00372     //(void)pdev;
00373 
00374 #if (MBED_VERSION  > 60300) 
00375     thread_sleep_for(wait_time);
00376 #else
00377     wait_ms(wait_time);  // NEEDS A DELAY BETWEEN SENSORS
00378 #endif
00379     return VL53L1_ERROR_NONE;
00380 }
00381 
00382 
00383 VL53L1CB_ERROR VL53L1CB::VL53L1CB_WaitValueMaskEx(
00384     VL53L1_Dev_t *pdev,
00385     uint32_t      timeout_ms,
00386     uint16_t      index,
00387     uint8_t       value,
00388     uint8_t       mask,
00389     uint32_t      poll_delay_ms)
00390 {
00391 
00392     /*
00393      * Platform implementation of WaitValueMaskEx V2WReg script command
00394      *
00395      * WaitValueMaskEx(
00396      *          duration_ms,
00397      *          index,
00398      *          value,
00399      *          mask,
00400      *          poll_delay_ms);
00401      */
00402 
00403 
00404     return VL53L1_WaitValueMaskEx( pdev, timeout_ms,index, value, mask, poll_delay_ms);
00405 }
00406 
00407 
00408 /***************************************************************************/
00409 //VL53L1CB_ERROR VL53L1CB::VL53L1CB_WaitValueMaskEx(
00410 
00411 VL53L1CB_ERROR VL53L1CB::VL53L1CB_WaitDeviceBooted(VL53L1_DEV Dev)
00412 {
00413 
00414     return VL53L1_WaitDeviceBooted(Dev);
00415 }
00416 
00417 
00418 static int32_t BDTable[VL53L1_TUNING_MAX_TUNABLE_KEY] = {
00419         TUNING_VERSION,
00420         TUNING_PROXY_MIN,
00421         TUNING_SINGLE_TARGET_XTALK_TARGET_DISTANCE_MM,
00422         TUNING_SINGLE_TARGET_XTALK_SAMPLE_NUMBER,
00423         TUNING_MIN_AMBIENT_DMAX_VALID,
00424         TUNING_MAX_SIMPLE_OFFSET_CALIBRATION_SAMPLE_NUMBER,
00425         TUNING_XTALK_FULL_ROI_TARGET_DISTANCE_MM,
00426         TUNING_SIMPLE_OFFSET_CALIBRATION_REPEAT,
00427         TUNING_XTALK_FULL_ROI_BIN_SUM_MARGIN,
00428         TUNING_XTALK_FULL_ROI_DEFAULT_OFFSET,
00429         TUNING_ZERO_DISTANCE_OFFSET_NON_LINEAR_FACTOR_DEFAULT,
00430 };
00431 
00432 
00433 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetVersion(VL53L1_Version_t *pVersion)
00434 {
00435 
00436     return VL53L1_GetVersion(pVersion);
00437 }
00438 
00439 
00440 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetProductRevision(
00441     uint8_t *pProductRevisionMajor, uint8_t *pProductRevisionMinor)
00442 {
00443     return VL53L1_GetProductRevision(Device,pProductRevisionMajor,pProductRevisionMinor);
00444 }
00445 
00446 //******************************************************************
00447 
00448 
00449 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetDeviceInfo(
00450     VL53L1_DeviceInfo_t *pVL53L1_DeviceInfo)
00451 {
00452     return VL53L1_GetDeviceInfo(Device,pVL53L1_DeviceInfo);
00453 }
00454 
00455 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetUID( uint64_t *pUid)
00456 {
00457     return VL53L1_GetUID(Device,pUid);
00458 }
00459 
00460 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetRangeStatusString(uint8_t RangeStatus,
00461     char *pRangeStatusString)
00462 {
00463     return VL53L1_GetRangeStatusString(RangeStatus,
00464         pRangeStatusString);
00465 }
00466 
00467 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetPalErrorString(VL53L1CB_ERROR PalErrorCode,
00468     char *pPalErrorString)
00469 {
00470     return VL53L1_GetPalErrorString(PalErrorCode,pPalErrorString);
00471 }
00472 
00473 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetPalStateString(VL53L1_State PalStateCode,
00474     char *pPalStateString)
00475 {
00476     return VL53L1_GetPalStateString(PalStateCode, pPalStateString);
00477 }
00478 
00479 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetPalState(VL53L1_DEV Dev, VL53L1_State *pPalState)
00480 {
00481     return VL53L1_GetPalState(Dev,pPalState);
00482 }
00483 
00484 
00485 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetDeviceAddress(VL53L1_DEV Dev, uint8_t DeviceAddress)
00486 {
00487     VL53L1CB_ERROR Status = VL53L1_ERROR_NONE;
00488 
00489  //   LOG_FUNCTION_START("");
00490 
00491     Status = VL53L1_WrByte(Dev, VL53L1CB_I2C_SLAVE__DEVICE_ADDRESS,
00492             DeviceAddress / 2);
00493 
00494 //    LOG_FUNCTION_END(Status);
00495     return Status;
00496 }
00497 
00498 VL53L1CB_ERROR VL53L1CB::VL53L1CB_DataInit()
00499 {
00500     printf("vl53L1_DataInit %d \n",Device->i2c_slave_address);
00501     return VL53L1_DataInit( Device);
00502 }
00503 
00504 
00505 VL53L1CB_ERROR VL53L1CB::VL53L1CB_StaticInit()
00506 {
00507     return VL53L1_StaticInit( Device);
00508 }
00509 
00510 
00511  VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetPresetMode(VL53L1_PresetModes PresetMode)
00512 {
00513     return VL53L1_SetPresetMode(Device,PresetMode);
00514 }
00515 
00516 
00517  VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetPresetMode( VL53L1_PresetModes *pPresetMode)
00518 {
00519     return VL53L1_GetPresetMode(Device,pPresetMode);
00520 }
00521 
00522 
00523  VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetDistanceMode(VL53L1_DistanceModes DistanceMode)
00524 {
00525     return VL53L1_SetDistanceMode(Device,DistanceMode);
00526 }
00527 
00528 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetDistanceMode(VL53L1_DistanceModes *pDistanceMode)
00529 {
00530     return VL53L1_GetDistanceMode(Device,pDistanceMode);
00531 }
00532 
00533 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetOutputMode(VL53L1_OutputModes OutputMode)
00534 {
00535     return VL53L1_SetOutputMode(Device,OutputMode);
00536 }
00537 
00538 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetOutputMode(VL53L1_OutputModes *pOutputMode)
00539 {
00540     return VL53L1_GetOutputMode(Device,pOutputMode);
00541 }
00542 
00543 
00544 
00545 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetMeasurementTimingBudgetMicroSeconds(
00546                                    uint32_t MeasurementTimingBudgetMicroSeconds)
00547 {
00548     return VL53L1_SetMeasurementTimingBudgetMicroSeconds(Device,
00549                                            MeasurementTimingBudgetMicroSeconds);
00550 }
00551 
00552 
00553 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetMeasurementTimingBudgetMicroSeconds(
00554                                  uint32_t *pMeasurementTimingBudgetMicroSeconds)
00555 {
00556     return VL53L1_GetMeasurementTimingBudgetMicroSeconds(Device,
00557                                         pMeasurementTimingBudgetMicroSeconds);
00558 }
00559 
00560 
00561 
00562 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetInterMeasurementPeriodMilliSeconds(
00563     uint32_t InterMeasurementPeriodMilliSeconds)
00564 {   
00565     return VL53L1_SetInterMeasurementPeriodMilliSeconds(Device,InterMeasurementPeriodMilliSeconds);
00566 }
00567 
00568 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetInterMeasurementPeriodMilliSeconds(
00569     uint32_t *pInterMeasurementPeriodMilliSeconds)
00570 {
00571     return VL53L1_GetInterMeasurementPeriodMilliSeconds(Device,pInterMeasurementPeriodMilliSeconds);
00572 }
00573 
00574 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetDmaxReflectance(FixPoint1616_t DmaxReflectance)
00575 {
00576 
00577     return VL53L1_SetDmaxReflectance(Device,DmaxReflectance);
00578 }
00579 
00580 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetDmaxReflectance(
00581                                            FixPoint1616_t *pDmaxReflectance)
00582 {
00583     return VL53L1_GetDmaxReflectance(Device,pDmaxReflectance);
00584 }
00585 
00586 
00587 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetDmaxMode(VL53L1_DeviceDmaxModes DmaxMode)
00588 {
00589     return VL53L1_SetDmaxMode(Device,DmaxMode);
00590 }
00591 
00592 
00593 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetDmaxMode(
00594     VL53L1_DeviceDmaxModes *pDmaxMode)
00595 {
00596     return VL53L1_GetDmaxMode(Device,pDmaxMode);
00597 }
00598 
00599 
00600 
00601 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetNumberOfLimitCheck(uint16_t *pNumberOfLimitCheck)
00602 {
00603     VL53L1CB_ERROR Status = VL53L1_ERROR_NONE;
00604 
00605   //  LOG_FUNCTION_START("");
00606 
00607     *pNumberOfLimitCheck = VL53L1_CHECKENABLE_NUMBER_OF_CHECKS;
00608 
00609  //   LOG_FUNCTION_END(Status);
00610     return Status;
00611 }
00612 
00613 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetLimitCheckInfo(uint16_t LimitCheckId,
00614     char *pLimitCheckString)
00615 {
00616     return VL53L1_GetLimitCheckInfo(LimitCheckId,
00617         pLimitCheckString);
00618 
00619 }
00620 
00621 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetLimitCheckStatus(uint16_t LimitCheckId,
00622     uint8_t *pLimitCheckStatus)
00623 {
00624     return VL53L1_GetLimitCheckStatus(Device,LimitCheckId,pLimitCheckStatus);
00625 }
00626 
00627 
00628 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetLimitCheckEnable(uint16_t LimitCheckId,
00629     uint8_t LimitCheckEnable)
00630 {
00631 
00632     return VL53L1_SetLimitCheckEnable(Device,LimitCheckId,LimitCheckEnable);
00633 }
00634 
00635 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetLimitCheckEnable(uint16_t LimitCheckId,
00636     uint8_t *pLimitCheckEnable)
00637 {
00638     return VL53L1_GetLimitCheckEnable(Device,LimitCheckId,pLimitCheckEnable);
00639 }
00640 
00641 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetLimitCheckValue( uint16_t LimitCheckId,
00642     FixPoint1616_t LimitCheckValue)
00643 {
00644     return VL53L1_SetLimitCheckValue(Device,LimitCheckId,LimitCheckValue);
00645 }
00646 
00647 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetLimitCheckValue( uint16_t LimitCheckId,
00648     FixPoint1616_t *pLimitCheckValue)
00649 {
00650     return VL53L1_GetLimitCheckValue(Device,LimitCheckId,pLimitCheckValue);
00651 }
00652 
00653 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetLimitCheckCurrent( uint16_t LimitCheckId,
00654     FixPoint1616_t *pLimitCheckCurrent)
00655 {
00656     return VL53L1_GetLimitCheckCurrent(Device,LimitCheckId,pLimitCheckCurrent);
00657 }
00658 
00659 
00660 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetMaxNumberOfROI( uint8_t *pMaxNumberOfROI)
00661 {
00662     return VL53L1_GetMaxNumberOfROI(Device,pMaxNumberOfROI);
00663 }
00664 
00665 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetROI( VL53L1_RoiConfig_t *pRoiConfig)
00666 {
00667 
00668     return VL53L1_SetROI(Device,pRoiConfig);
00669 }
00670 
00671 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetROI(VL53L1_RoiConfig_t *pRoiConfig)
00672 {
00673     return VL53L1_GetROI(Device,pRoiConfig);
00674 }
00675 
00676 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetNumberOfSequenceSteps(uint8_t *pNumberOfSequenceSteps)
00677 {
00678     VL53L1CB_ERROR Status = VL53L1_ERROR_NONE;
00679 
00680  //   SUPPRESS_UNUSED_WARNING(Dev);
00681 
00682  //   LOG_FUNCTION_START("");
00683 
00684     *pNumberOfSequenceSteps = VL53L1_SEQUENCESTEP_NUMBER_OF_ITEMS;
00685 
00686 //    LOG_FUNCTION_END(Status);
00687     return Status;
00688 }
00689 
00690 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetSequenceStepsInfo(VL53L1_SequenceStepId SequenceStepId,
00691     char *pSequenceStepsString)
00692 {
00693     return VL53L1_GetSequenceStepsInfo(SequenceStepId,pSequenceStepsString);
00694 }
00695 
00696 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetSequenceStepEnable(VL53L1_SequenceStepId SequenceStepId,
00697                                                     uint8_t SequenceStepEnabled)
00698 {
00699 
00700     return VL53L1_SetSequenceStepEnable(Device,SequenceStepId,SequenceStepEnabled);
00701 }
00702 
00703 
00704 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetSequenceStepEnable(VL53L1_SequenceStepId SequenceStepId, 
00705                                                     uint8_t *pSequenceStepEnabled)
00706 {
00707     return VL53L1_GetSequenceStepEnable(Device,SequenceStepId,pSequenceStepEnabled);
00708 }
00709 
00710 
00711 
00712 VL53L1CB_ERROR VL53L1CB::VL53L1CB_StartMeasurement()
00713 {
00714     return VL53L1_StartMeasurement(Device);
00715 }
00716 
00717 VL53L1CB_ERROR VL53L1CB::VL53L1CB_StopMeasurement()
00718 {
00719     return VL53L1_StopMeasurement(Device);
00720 }
00721 
00722 
00723 VL53L1CB_ERROR VL53L1CB::VL53L1CB_ClearInterruptAndStartMeasurement()
00724 {
00725 
00726     return VL53L1_ClearInterruptAndStartMeasurement(Device);
00727 }
00728 
00729 
00730 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetMeasurementDataReady(uint8_t *pMeasurementDataReady)
00731 {
00732     return VL53L1_GetMeasurementDataReady(Device, pMeasurementDataReady);
00733 }
00734 
00735 VL53L1CB_ERROR VL53L1CB::VL53L1CB_WaitMeasurementDataReady()
00736 {
00737     return VL53L1_WaitMeasurementDataReady(Device);
00738 }
00739 
00740 
00741 //******************************************************************
00742 
00743 
00744 
00745 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetCalibrationData(
00746         VL53L1_CalibrationData_t  *pCalibrationData)
00747 {
00748     
00749     VL53L1CB_ERROR Status = VL53L1_ERROR_NONE;
00750     Status = VL53L1_GetCalibrationData(Device,pCalibrationData);
00751 
00752     return Status;
00753 }
00754 
00755 
00756 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetRangingMeasurementData(
00757     VL53L1_RangingMeasurementData_t *pRangingMeasurementData)
00758 {
00759 //              printf("   VL53L1_GetRangingMeasurementData 000  \n");  
00760     VL53L1CB_ERROR Status = VL53L1_ERROR_NONE;
00761     Status = VL53L1_GetRangingMeasurementData(Device,pRangingMeasurementData);
00762 
00763     return Status;
00764 }
00765 
00766 
00767 
00768 
00769 
00770 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetMultiRangingData(
00771         VL53L1_MultiRangingData_t *pMultiRangingData)
00772 {
00773     return VL53L1_GetMultiRangingData(Device,pMultiRangingData);
00774 }
00775 
00776 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetAdditionalData(
00777         VL53L1_AdditionalData_t *pAdditionalData)
00778 {
00779     return VL53L1_GetAdditionalData(Device, pAdditionalData);
00780 }
00781 
00782 
00783 
00784 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetTuningParameter(
00785         uint16_t TuningParameterId, int32_t TuningParameterValue)
00786 {
00787     return VL53L1_SetTuningParameter(Device,TuningParameterId,TuningParameterValue);
00788 }
00789 
00790 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetTuningParameter(
00791         uint16_t TuningParameterId, int32_t *pTuningParameterValue)
00792 {
00793 
00794     return VL53L1_GetTuningParameter(Device,TuningParameterId,pTuningParameterValue);
00795 }
00796 
00797 
00798 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetXTalkCompensationEnable(
00799     uint8_t XTalkCompensationEnable)
00800 {
00801 
00802     return  VL53L1_SetXTalkCompensationEnable(Device,XTalkCompensationEnable);
00803 }
00804 
00805 
00806 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetXTalkCompensationEnable(
00807     uint8_t *pXTalkCompensationEnable)
00808 {
00809     VL53L1CB_ERROR Status = VL53L1_ERROR_NONE;
00810 
00811   //  LOG_FUNCTION_START("");
00812 
00813     VL53L1_GetXTalkCompensationEnable(
00814         Device,
00815         pXTalkCompensationEnable);
00816 
00817   //  LOG_FUNCTION_END(Status);
00818     return Status;
00819 }
00820 
00821 
00822 VL53L1CB_ERROR VL53L1CB::VL53L1CB_PerformXTalkCalibration(
00823         uint8_t CalibrationOption)
00824 {
00825 
00826     return VL53L1_PerformXTalkCalibration(Device,CalibrationOption);
00827 }
00828 
00829 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetOffsetCalibrationMode(
00830         VL53L1_OffsetCalibrationModes OffsetCalibrationMode)
00831 {
00832     return VL53L1_SetOffsetCalibrationMode(Device,OffsetCalibrationMode);
00833 }
00834 
00835 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetOffsetCorrectionMode(
00836         VL53L1_OffsetCorrectionModes OffsetCorrectionMode)
00837 {
00838     return  VL53L1_SetOffsetCorrectionMode(Device,OffsetCorrectionMode);
00839 }
00840 
00841 VL53L1CB_ERROR VL53L1CB::VL53L1CB_PerformOffsetCalibration(
00842     int32_t CalDistanceMilliMeter, FixPoint1616_t CalReflectancePercent)
00843 {
00844     return VL53L1_PerformOffsetCalibration(Device,CalDistanceMilliMeter,CalReflectancePercent);
00845 }
00846 
00847 VL53L1CB_ERROR VL53L1CB::VL53L1CB_PerformOffsetSimpleCalibration(
00848     int32_t CalDistanceMilliMeter)
00849 {
00850     return VL53L1_PerformOffsetSimpleCalibration(Device,CalDistanceMilliMeter);
00851 }
00852 
00853 VL53L1CB_ERROR VL53L1CB::VL53L1CB_PerformOffsetZeroDistanceCalibration()
00854 {
00855     return VL53L1_PerformOffsetZeroDistanceCalibration(Device);
00856 }
00857 
00858 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetCalibrationData(
00859         VL53L1_CalibrationData_t *pCalibrationData)
00860 {
00861     return VL53L1_SetCalibrationData(Device,pCalibrationData);
00862 }
00863 
00864 
00865 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetZoneCalibrationData(
00866         VL53L1_ZoneCalibrationData_t *pZoneCalibrationData)
00867 {
00868     return VL53L1_SetZoneCalibrationData(Device, pZoneCalibrationData);
00869 }
00870 
00871 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetZoneCalibrationData(
00872         VL53L1_ZoneCalibrationData_t  *pZoneCalibrationData)
00873 {
00874     return VL53L1_GetZoneCalibrationData(Device, pZoneCalibrationData);
00875 }
00876 
00877 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SmudgeCorrectionEnable(
00878         VL53L1_SmudgeCorrectionModes Mode)
00879         
00880 {
00881     return VL53L1_SmudgeCorrectionEnable(Device, Mode);
00882 }
00883 
00884 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetOpticalCenter(
00885         FixPoint1616_t *pOpticalCenterX,
00886         FixPoint1616_t *pOpticalCenterY)
00887 {
00888     return VL53L1_GetOpticalCenter(Device,pOpticalCenterX,pOpticalCenterY);
00889 }
00890 
00891 VL53L1CB_ERROR VL53L1CB::VL53L1CB_SetThresholdConfig(VL53L1_DetectionConfig_t *pConfig)
00892 {
00893     return VL53L1_SetThresholdConfig(Device,pConfig);
00894 }
00895 
00896 
00897 VL53L1CB_ERROR VL53L1CB::VL53L1CB_GetThresholdConfig(VL53L1_DetectionConfig_t *pConfig)
00898 {
00899     return VL53L1_GetThresholdConfig(Device,pConfig);
00900 }
00901 
00902 VL53L1CB_ERROR VL53L1CB::VL53L1CB_PerformOffsetPerVcselCalibration(int32_t CalDistanceMilliMeter)
00903 {
00904     return VL53L1_PerformOffsetPerVcselCalibration(Device,CalDistanceMilliMeter);
00905 }
00906 
00907 
00908 
00909 // from vl53l1_api_debug.c
00910 
00911 
00912 VL53L1CB_ERROR VL53L1CB::VL53L1CB_get_additional_data(
00913     VL53L1_DEV                      Dev,
00914     VL53L1_additional_data_t        *pdata)
00915 {
00916     return VL53L1_get_additional_data(Dev,pdata);
00917 }
00918 
00919 
00920 
00921 int VL53L1CB::handle_irq(uint16_t *distance)
00922 {
00923     int status;
00924     status = get_measurement(distance);
00925     enable_interrupt_measure_detection_irq();
00926     return status;
00927 }
00928 
00929 int VL53L1CB::get_measurement(uint16_t *distance)
00930 {
00931     int status = 0;
00932 
00933     status = VL53L1CB_GetDistance(distance);
00934     status = VL53L1CB_ClearInterrupt();
00935 
00936     return status;
00937 }
00938 
00939 int VL53L1CB::start_measurement(void (*fptr)(void))
00940 {
00941     int status = 0;
00942 
00943     if (_gpio1Int == NULL) {
00944         printf("GPIO1 Error\r\n");
00945         return 1;
00946     }
00947 
00948     status = VL53L1CB_StopRanging(); // it is safer to do this while sensor is stopped
00949 
00950     if (status == 0) {
00951         attach_interrupt_measure_detection_irq(fptr);
00952         enable_interrupt_measure_detection_irq();
00953     }
00954 
00955     if (status == 0) {
00956         status = VL53L1CB_StartRanging();
00957     }
00958 
00959     return status;
00960 }
00961 
00962 int VL53L1CB::stop_measurement()
00963 {
00964     int status = 0;
00965 
00966     if (status == 0) {
00967         printf("Call of VL53L1_StopMeasurement\n");
00968         status = VL53L1CB_StopRanging();
00969     }
00970 
00971     if (status == 0)
00972         status = VL53L1CB_ClearInterrupt();
00973 
00974     return status;
00975 }
00976 
00977