ST Expansion SW Team / Vl6180

Dependencies:   VL6180_Board

Dependents:   X_NUCLEO_6180

inc/vl6180_class.h

Committer:
charlesmn
Date:
2020-11-10
Revision:
2:bc1d979ae392
Parent:
VL6180INC/vl6180_class.h@ 0:1da5e4bcb8e5
Child:
3:b01812cb5250

File content as of revision 2:bc1d979ae392:

/*******************************************************************************
 * @file    vl6180_class.h
 * @author  JS
 * @version V0.0.1
 * @date    15-January-2019
 * @brief   Header file for VL53L1 sensor component
 ******************************************************************************
 Copyright © 2019, STMicroelectronics International N.V.
 All rights reserved.
 Redistribution and use in source and binary forms, with or without
 modification, are permitted provided that the following conditions are met:
 * Redistributions of source code must retain the above copyright
 notice, this list of conditions and the following disclaimer.
 * Redistributions in binary form must reproduce the above copyright
 notice, this list of conditions and the following disclaimer in the
 documentation and/or other materials provided with the distribution.
 * Neither the name of STMicroelectronics nor the
 names of its contributors may be used to endorse or promote products
 derived from this software without specific prior written permission.
 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
 WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
 NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
 IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 *****************************************************************************/

#ifndef __VL6180_CLASS_H
#define __VL6180_CLASS_H


/* Includes ------------------------------------------------------------------*/

#include "mbed.h"
#include "PinNames.h"
#include "RangeSensor.h"
#include "vl6180_I2c.h"
#include "Stmpe1600.h"
#include "vl6180_platform.h"
/**********************************************************/

#define VL53L1X_IMPLEMENTATION_VER_MAJOR       1
#define VL53L1X_IMPLEMENTATION_VER_MINOR       0
#define VL53L1X_IMPLEMENTATION_VER_SUB         1
#define VL53L1X_IMPLEMENTATION_VER_REVISION  0000

typedef int8_t VL6180_ERROR;
typedef int8_t VL6180_ERROR;

//#define SOFT_RESET                                          0x0000
#define VL53L1_I2C_SLAVE__DEVICE_ADDRESS                    0x0001
#define VL53L1_VHV_CONFIG__TIMEOUT_MACROP_LOOP_BOUND        0x0008
#define ALGO__CROSSTALK_COMPENSATION_PLANE_OFFSET_KCPS      0x0016
#define ALGO__CROSSTALK_COMPENSATION_X_PLANE_GRADIENT_KCPS  0x0018
#define ALGO__CROSSTALK_COMPENSATION_Y_PLANE_GRADIENT_KCPS  0x001A
#define ALGO__PART_TO_PART_RANGE_OFFSET_MM                  0x001E
#define MM_CONFIG__INNER_OFFSET_MM                          0x0020
#define MM_CONFIG__OUTER_OFFSET_MM                          0x0022
#define GPIO_HV_MUX__CTRL                                   0x0030
#define GPIO__TIO_HV_STATUS                                 0x0031
#define SYSTEM__INTERRUPT_CONFIG_GPIO                       0x0046
#define PHASECAL_CONFIG__TIMEOUT_MACROP                     0x004B
#define RANGE_CONFIG__TIMEOUT_MACROP_A_HI                   0x005E
#define RANGE_CONFIG__VCSEL_PERIOD_A                        0x0060
#define RANGE_CONFIG__VCSEL_PERIOD_B                        0x0063
#define RANGE_CONFIG__TIMEOUT_MACROP_B_HI                   0x0061
#define RANGE_CONFIG__TIMEOUT_MACROP_B_LO                   0x0062
#define RANGE_CONFIG__SIGMA_THRESH                          0x0064
#define RANGE_CONFIG__MIN_COUNT_RATE_RTN_LIMIT_MCPS         0x0066
#define RANGE_CONFIG__VALID_PHASE_HIGH                      0x0069
#define VL53L1_SYSTEM__INTERMEASUREMENT_PERIOD              0x006C
#define SYSTEM__THRESH_HIGH                                 0x0072
#define SYSTEM__THRESH_LOW                                  0x0074
#define SD_CONFIG__WOI_SD0                                  0x0078
#define SD_CONFIG__INITIAL_PHASE_SD0                        0x007A
#define ROI_CONFIG__USER_ROI_CENTRE_SPAD                    0x007F
#define ROI_CONFIG__USER_ROI_REQUESTED_GLOBAL_XY_SIZE       0x0080
#define SYSTEM__SEQUENCE_CONFIG                             0x0081
#define VL53L1_SYSTEM__GROUPED_PARAMETER_HOLD               0x0082
#define SYSTEM__INTERRUPT_CLEAR                             0x0086
#define SYSTEM__MODE_START                                  0x0087
#define VL53L1_RESULT__RANGE_STATUS                         0x0089
#define VL53L1_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0       0x008C
#define RESULT__AMBIENT_COUNT_RATE_MCPS_SD                  0x0090
#define VL53L1_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0               0x0096
#define VL53L1_RESULT__PEAK_SIGNAL_COUNT_RATE_CROSSTALK_CORRECTED_MCPS_SD0  0x0098
#define VL53L1_RESULT__OSC_CALIBRATE_VAL                    0x00DE
#define VL53L1_FIRMWARE__SYSTEM_STATUS                      0x00E5
#define VL53L1_IDENTIFICATION__MODEL_ID                     0x010F
#define VL53L1_ROI_CONFIG__MODE_ROI_CENTRE_SPAD             0x013E


#define VL53L1X_DEFAULT_DEVICE_ADDRESS                      0x52

#define VL53L1X_REG_IDENTIFICATION_MODEL_ID                 0x010F


/****************************************
 * PRIVATE define do not edit
 ****************************************/

/**
 *  @brief defines SW Version
 */
 
typedef struct {
    uint8_t      major;    /*!< major number */
    uint8_t      minor;    /*!< minor number */
    uint8_t      build;    /*!< build number */
    uint32_t     revision; /*!< revision number */
} VL6180_Version_t;


/*
typedef struct {


 //   VL53L1_DevData_t   Data;


  //  uint8_t   i2c_slave_address;
    uint8_t   I2cDevAddr;

    uint8_t   comms_type;

    uint16_t  comms_speed_khz;


    uint32_t  new_data_ready_poll_duration_ms;
 //   I2C_HandleTypeDef *I2cHandle;

} VL53L1_Dev_t;
*/



//typedef VL53L1_Dev_t *VL53L1_DEV;


/* Classes -------------------------------------------------------------------*/
/** Class representing a VL6180 sensor component
 */
class VL6180 : public RangeSensor
{
 

 
 public:
 
 #define VL6180_RangeClearInterrupt(dev) VL6180_ClearInterrupt(dev, INTERRUPT_CLEAR_RANGING)
 #define VL53L1DevStructGetLLDriverHandle(Dev) (&Dev->Data.LLData)
    /** Constructor
     * @param[in] &i2c device I2C to be used for communication
     * @param[in] &pin_gpio1 pin Mbed InterruptIn PinName to be used as component GPIO_1 INT
     * @param[in] DevAddr device address, 0x52 by default
     */
    VL6180(vl6180_DevI2C *i2c, DigitalOut *pin, PinName pin_gpio1, uint8_t dev_addr = VL53L1X_DEFAULT_DEVICE_ADDRESS) 
    : RangeSensor(), dev_i2c(i2c), _gpio0(pin)
    {
        MyDevice->i2c_addr=dev_addr;
 //       Device = &MyDevice;
               
        _expgpio0 = NULL;
        if (pin_gpio1 != NC) {
            _gpio1Int = new InterruptIn(pin_gpio1);
        } else {
            _gpio1Int = NULL;
        }
    }
    
    /** Constructor 2 (STMPE1600DigiOut)
     * @param[in] i2c device I2C to be used for communication
     * @param[in] &pin Gpio Expander STMPE1600DigiOut pin to be used as component GPIO_0 CE
     * @param[in] pin_gpio1 pin Mbed InterruptIn PinName to be used as component GPIO_1 INT
     * @param[in] device address, 0x29 by default
     */
    VL6180(vl6180_DevI2C *i2c, Stmpe1600DigiOut *pin, PinName pin_gpio1,
            uint8_t dev_addr = VL53L1X_DEFAULT_DEVICE_ADDRESS) 
            : dev_i2c(i2c), _expgpio0(pin)
    {
  //      MyDevice.I2cDevAddr=dev_addr;
   //     Device = &MyDevice;
               
        _gpio0 = NULL;
        if (pin_gpio1 != NC) {
            _gpio1Int = new InterruptIn(pin_gpio1);
        } else {
            _gpio1Int = NULL;
        }
    }    
    
   /** Destructor
    */
    virtual ~VL6180()
    {        
        if (_gpio1Int != NULL) {
            delete _gpio1Int;
        }
    }
    
        
    
    MyVL6180Dev_t getDevicePtr() { return Device; }

    
    /* warning: VL53L1 class inherits from GenericSensor, RangeSensor and LightSensor, that haven`t a destructor.
       The warning should request to introduce a virtual destructor to make sure to delete the object */

    /*** Interface Methods ***/
    /*** High level API ***/
    /**
     * @brief       PowerOn the sensor
     * @return      void
     */
    /* turns on the sensor */
    virtual void VL53L1_On(void)
    {
        printf("VL53L1_On\r\n");
        if (_gpio0) {
            *_gpio0 = 1;
        } else {
            if (_expgpio0) {
                *_expgpio0 = 1;
            }
        }
        wait_ms(10);
    }

    /**
     * @brief       PowerOff the sensor
     * @return      void
     */
    /* turns off the sensor */
    virtual void VL53L1_Off(void)
    {
        printf("VL53L1_Off\r\n");
        if (_gpio0) {
            *_gpio0 = 0;
        } else {
            if (_expgpio0) {
                *_expgpio0 = 0;
            }
        }
        wait_ms(10);
    }
    
    int is_present()
    {
        int status;
        uint8_t id = 0;

        status = read_id(&id);
        if (status) {
            printf("Failed to read ID device. Device not present!\n\r");
        }
        return status;
    }

    /**
     * @brief       Initialize the sensor with default values
     * @return      0 on Success
     */
     
     VL6180_ERROR InitSensor(uint8_t address){
        VL6180_ERROR status = 0;
        VL53L1_Off();
        VL53L1_On();
        status = vl6180_SetI2CAddress(address);
        printf("vl6180_SetI2CAddress %d %d \n",address,status);

        wait_ms(20);       // cgm todo fix
        return status;
     }



/**
 *
 * @brief One time device initialization
 * @param void
 * @return     0 on success,  @a #CALIBRATION_WARNING if failed
 */
    virtual int init(void *init)
    {
        printf("init called no function \n");
        return 0;
  //     return vl6180_SensorInit();
    }


    /**
     * @brief       Initialize the sensor with default values
     * @return      "0" on success
     */
    int init_sensor(uint8_t new_addr);

    /* Read function of the ID device */
    virtual int read_id(uint8_t *id){
        int status = 0;
        uint16_t rl_id = 0;
    
        uint8_t ExpanderData[2];
    
        ExpanderData[0] = 0;
        ExpanderData[1] = 0;
        rl_id = 0;
        dev_i2c->vl6180_i2c_read(&ExpanderData[0], Device.i2c_addr, IDENTIFICATION_MODEL_ID, 2);  // cgm is IDENTIFICATION_MODEL_ID correct
    
        rl_id = (ExpanderData[0] << 8) + ExpanderData[1];
        printf("Model ID is: %d (%X)  \r\n",rl_id, rl_id);
    
        uint8_t tmp = 0;
        ExpanderData[0] = VL53L1_FIRMWARE__SYSTEM_STATUS >> 8;
        ExpanderData[1] = VL53L1_FIRMWARE__SYSTEM_STATUS & 0x0FF;
        dev_i2c->vl6180_i2c_read(&tmp,  Device.i2c_addr, VL53L1_FIRMWARE__SYSTEM_STATUS, 1);

        printf("Firmware system is: %d\r\n",tmp);
    
        if (rl_id == 0xEACC) {
            printf("Device is present %d:\r\n", rl_id);
            return status;
        }
        return -1;
    }



/**
 * @brief Get ranging result and only that
 * @param pRange_mm  Pointer to range distance
 * @return           0 on success
 */
    virtual int get_distance(uint32_t *piData)
    {
    int status;
    uint16_t distance;
//    status = vl6180_GetDistance(&distance);  //todo cgm does not exist
    *piData = (uint32_t) distance;
    return status;
    }
    
    
    /**
 * @brief   Run a single ALS measurement in single shot polling mode
 *
 * @par Function Description
 * Kick off a new single shot ALS then wait new measurement ready to retrieve it ( polling system interrupt status register for als) \n
 * ALS must be prepared by a first call to @a VL6180x_Prepare() \n
 * \n Should not be used in continuous or interrupt mode it will break it and create hazard in start/stop \n
 *
 * @param dev          The device
 * @param pAlsData     Als data structure to fill up @a VL6180x_AlsData_t
 * @return             0 on success
 */
 //   VL6180_ERROR VL6180x_AlsPollMeasurement(VL6180xDev_t dev, VL6180x_AlsData_t *pAlsData);


/* VL53L1X_api.h functions */



    /**
     * @brief This function returns the SW driver version
     */
    VL6180_ERROR vl6180_GetSWVersion(VL6180_Version_t *pVersion);

    /**
     * @brief This function sets the sensor I2C address used in case multiple devices application, default address 0x52
     */
    VL6180_ERROR vl6180_SetI2CAddress(uint8_t new_address);

    /**
     * @brief This function loads the 135 bytes default values to initialize the sensor.
     * @param dev Device address
     * @return 0:success, != 0:failed
     */
    VL6180_ERROR vl6180_SensorInit();

    /**
     * @brief This function clears the interrupt, to be called after a ranging data reading
     * to arm the interrupt for the next data ready event.
     */
    VL6180_ERROR vl6180_ClearInterrupt();

    /**
     * @brief This function programs the interrupt polarity\n
     * 1=active high (default), 0=active low
     */
    VL6180_ERROR vl6180_SetInterruptPolarity(uint8_t IntPol);

    /**
     * @brief This function returns the current interrupt polarity\n
     * 1=active high (default), 0=active low
     */
    VL6180_ERROR vl6180_GetInterruptPolarity(uint8_t *pIntPol);

    /**
     * @brief This function starts the ranging distance operation\n
     * 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
     * 1=active high (default), 0=active low, use SetInterruptPolarity() to change the interrupt polarity if required.
     */
    VL6180_ERROR vl6180_StartRanging();

    /**
     * @brief This function stops the ranging.
     */
    VL6180_ERROR vl6180_StopRanging();

    
    /**
     * @brief This function programs the timing budget in ms.
     * Predefined values = 15, 20, 33, 50, 100(default), 200, 500.
     */
    VL6180_ERROR vl6180_SetTimingBudgetInMs(uint16_t TimingBudgetInMs);

    /**
     * @brief This function returns the current timing budget in ms.
     */
    VL6180_ERROR vl6180_GetTimingBudgetInMs(uint16_t *pTimingBudgetInMs);

    /**
     * @brief This function programs the distance mode (1=short, 2=long(default)).
     * Short mode max distance is limited to 1.3 m but better ambient immunity.\n
     * Long mode can range up to 4 m in the dark with 200 ms timing budget.
     */
    VL6180_ERROR vl6180_SetDistanceMode(uint16_t DistanceMode);

    /**
     * @brief This function returns the current distance mode (1=short, 2=long).
     */
    VL6180_ERROR vl6180_GetDistanceMode(uint16_t *pDistanceMode);

    /**
     * @brief This function programs the Intermeasurement period in ms\n
     * Intermeasurement period must be >/= timing budget. This condition is not checked by the API,
     * the customer has the duty to check the condition. Default = 100 ms
     */
    VL6180_ERROR vl6180_SetInterMeasurementInMs(uint16_t InterMeasurementInMs);

    /**
     * @brief This function returns the Intermeasurement period in ms.
     */
    VL6180_ERROR vl6180_GetInterMeasurementInMs(uint16_t * pIM);

    /**
     * @brief This function returns the boot state of the device (1:booted, 0:not booted)
     */
    VL6180_ERROR vl6180_BootState(uint8_t *state);

    /**
     * @brief This function returns the sensor id, sensor Id must be 0xEEAC
     */
    VL6180_ERROR vl6180_GetSensorId(uint16_t *id);

    /**
     * @brief This function returns the distance measured by the sensor in mm
     */
    VL6180_ERROR vl6180_GetDistance(uint16_t *distance);

    /**
     * @brief This function returns the returned signal per SPAD in kcps/SPAD.
     * With kcps stands for Kilo Count Per Second
     */
    VL6180_ERROR VL53L1X_GetSignalPerSpad(uint16_t *signalPerSp);

    /**
     * @brief This function returns the ambient per SPAD in kcps/SPAD
     */
    VL6180_ERROR VL53L1X_GetAmbientPerSpad(uint16_t *amb);

    /**
     * @brief This function returns the returned signal in kcps.
     */
    VL6180_ERROR VL53L1X_GetSignalRate(uint16_t *signalRate);

    /**
     * @brief This function returns the current number of enabled SPADs
     */
    VL6180_ERROR VL53L1X_GetSpadNb(uint16_t *spNb);

    /**
     * @brief This function returns the ambient rate in kcps
     */
    VL6180_ERROR VL53L1X_GetAmbientRate(uint16_t *ambRate);

    /**
     * @brief This function returns the ranging status error \n
     * (0:no error, 1:sigma failed, 2:signal failed, ..., 7:wrap-around)
     */
    VL6180_ERROR VL53L1X_GetRangeStatus(uint8_t *rangeStatus);

    /**
     * @brief This function programs the offset correction in mm
     * @param OffsetValue:the offset correction value to program in mm
     */
    VL6180_ERROR VL53L1X_SetOffset(int16_t OffsetValue);

    /**
     * @brief This function returns the programmed offset correction value in mm
     */
    VL6180_ERROR VL53L1X_GetOffset(int16_t *Offset);

    /**
     * @brief This function programs the xtalk correction value in cps (Count Per Second).\n
     * This is the number of photons reflected back from the cover glass in cps.
     */
    VL6180_ERROR VL53L1X_SetXtalk(uint16_t XtalkValue);

    /**
     * @brief This function returns the current programmed xtalk correction value in cps
     */
    VL6180_ERROR VL53L1X_GetXtalk(uint16_t *Xtalk);

    /**
     * @brief This function programs the threshold detection mode\n
     * Example:\n
     * VL53L1X_SetDistanceThreshold(dev,100,300,0,1): Below 100 \n
     * VL53L1X_SetDistanceThreshold(dev,100,300,1,1): Above 300 \n
     * VL53L1X_SetDistanceThreshold(dev,100,300,2,1): Out of window \n
     * VL53L1X_SetDistanceThreshold(dev,100,300,3,1): In window \n
     * @param   dev : device address
     * @param   ThreshLow(in mm) : the threshold under which one the device raises an interrupt if Window = 0
     * @param   ThreshHigh(in mm) :  the threshold above which one the device raises an interrupt if Window = 1
     * @param   Window detection mode : 0=below, 1=above, 2=out, 3=in
     * @param   IntOnNoTarget = 1 (No longer used - just use 1)
     */
    VL6180_ERROR vl6180_SetDistanceThreshold(uint16_t ThreshLow,
                      uint16_t ThreshHigh, uint8_t Window,
                      uint8_t IntOnNoTarget);

    /**
     * @brief This function returns the window detection mode (0=below; 1=above; 2=out; 3=in)
     */
    VL6180_ERROR vl6180_GetDistanceThresholdWindow(uint16_t *window);

    /**
     * @brief This function returns the low threshold in mm
     */
    VL6180_ERROR vl6180_GetDistanceThresholdLow(uint16_t *low);

    /**
     * @brief This function returns the high threshold in mm
     */
    VL6180_ERROR vl6180_GetDistanceThresholdHigh(uint16_t *high);

    /**
     * @brief This function programs the ROI (Region of Interest)\n
     * The ROI position is centered, only the ROI size can be reprogrammed.\n
     * The smallest acceptable ROI size = 4\n
     * @param X:ROI Width; Y=ROI Height
     */
    VL6180_ERROR VL53L1X_SetROI(uint16_t X, uint16_t Y);

    /**
     *@brief This function returns width X and height Y
     */
    VL6180_ERROR VL53L1X_GetROI_XY(uint16_t *ROI_X, uint16_t *ROI_Y);

    /**
     * @brief This function programs a new signal threshold in kcps (default=1024 kcps\n
     */
    VL6180_ERROR VL53L1X_SetSignalThreshold(uint16_t signal);

    /**
     * @brief This function returns the current signal threshold in kcps
     */
    VL6180_ERROR VL53L1X_GetSignalThreshold(uint16_t *signal);

    /**
     * @brief This function programs a new sigma threshold in mm (default=15 mm)
     */
    VL6180_ERROR VL53L1X_SetSigmaThreshold(uint16_t sigma);

    /**
     * @brief This function returns the current sigma threshold in mm
     */
    VL6180_ERROR VL53L1X_GetSigmaThreshold(uint16_t *signal);

    /**
     * @brief This function performs the temperature calibration.
     * It is recommended to call this function any time the temperature might have changed by more than 8 deg C
     * without sensor ranging activity for an extended period.
     */
    VL6180_ERROR VL53L1X_StartTemperatureUpdate();
    
    /**
 * @brief Wait for device booted after chip enable (hardware standby)
 * @par Function Description
 * After Chip enable Application you can also simply wait at least 1ms to ensure device is ready
 * @warning After device chip enable (gpio0) de-asserted  user must wait gpio1 to get asserted (hardware standby).
 * or wait at least 400usec prior to do any low level access or api call .
 *
 * This function implements polling for standby but you must ensure 400usec from chip enable passed\n
 * @warning Calling this function if device is not fresh out of reset will  result in an indefinite loop\n
 *
 * @param dev  The device
 * @return     0 on success
 */
    VL6180_ERROR vl6180_WaitDeviceBooted(VL6180Dev_t dev);
    
    VL6180_ERROR vl6180_InitData(VL6180Dev_t dev);

    VL6180_ERROR vl6180_DMaxSetState(VL6180Dev_t dev, int state);

    VL6180_ERROR vl6180_UpscaleGetScaling(VL6180Dev_t dev);
    
    VL6180_ERROR vl6180_FilterGetState(VL6180Dev_t dev);
    
     /**
  * @brief  Prepare device for operation
  * @par Function Description
  * Does static initialization and reprogram common default settings \n
  * Device is prepared for new measure, ready single shot ranging typical polling operation\n
  * After prepare user can : \n
  * @li Call other API function to set other settings\n
  * @li Configure the interrupt pins, etc... \n
  * @li Then start ranging operations in single shot or continuous mode
  *
  * @param dev   The device
  * @return      0 on success
  */
    VL6180_ERROR vl6180_Prepare(VL6180Dev_t dev);
    
    /**
  * @brief Single shot Range measurement in polling mode.
  *
  * @par Function Description
  * Kick off a new single shot range  then wait for ready to retrieve it by polling interrupt status \n
  * Ranging must be prepared by a first call to  @a VL6180_Prepare() and it is safer to clear  very first poll call \n
  * This function reference VL6180_PollDelay(dev) porting macro/call on each polling loop,
  * but PollDelay(dev) may never be called if measure in ready on first poll loop \n
  * Should not be use in continuous mode operation as it will stop it and cause stop/start misbehaviour \n
  * \n This function clears Range Interrupt status , but not error one. For that uses  @a VL6180_ClearErrorInterrupt() \n
  * This range error is not related VL6180_RangeData_t::errorStatus that refer measure status \n
  *
  * @param dev          The device
  * @param pRangeData   Will be populated with the result ranging data @a  VL6180_RangeData_t
  * @return 0 on success , @a #RANGE_ERROR if device reports an error case in it status (not cleared) use
  *
  * \sa ::VL6180_RangeData_t
  */
    VL6180_ERROR vl6180_RangePollMeasurement(VL6180Dev_t dev, VL6180_RangeData_t *pRangeData);
    
    /**************************************************************************/
    
    VL6180_ERROR VL6180_I2CWrite(uint8_t dev, uint16_t index, uint8_t *data, uint16_t number_of_bytes);
    VL6180_ERROR VL6180_I2CRead(uint8_t dev, uint16_t index, uint8_t *data, uint16_t number_of_bytes);



    VL6180_ERROR vl6180_RangeStartContinuousMode(VL6180Dev_t dev);
    
    VL6180_ERROR vl6180_RangeStartSingleShot(VL6180Dev_t dev);
    
    VL6180_ERROR vl6180_RangeSetInterMeasPeriod(VL6180Dev_t dev, uint32_t  InterMeasTime_msec);
    
    VL6180_ERROR vl6180_RangeGetMeasurement(VL6180Dev_t dev, VL6180_RangeData_t *pRangeData);
    
    VL6180_ERROR vl6180_RangeGetMeasurementIfReady(VL6180Dev_t dev, VL6180_RangeData_t *pRangeData);
    
    VL6180_ERROR vl6180_SetupGPIO1(VL6180Dev_t dev, uint8_t IntFunction, int ActiveHigh);
    
    VL6180_ERROR vl6180_RangeConfigInterrupt(VL6180Dev_t dev, uint8_t ConfigGpioInt);
 
    VL6180_ERROR vl6180_ClearInterrupt(VL6180Dev_t dev, uint8_t IntClear);
   
    VL6180_ERROR vl6180_RangeSetThresholds(VL6180Dev_t dev, uint16_t low, uint16_t high, int UseSafeParamHold); 
    
    VL6180_ERROR vl6180_FilterSetState(VL6180Dev_t dev, int state);
    
    VL6180_ERROR vl6180_UpscaleSetScaling(VL6180Dev_t dev, uint8_t scaling);
    
 protected:

    /* IO Device */
    vl6180_DevI2C *dev_i2c;
    
    /* Digital out pin */
    DigitalOut *_gpio0;
    /* GPIO expander */
    Stmpe1600DigiOut *_expgpio0;
    /* Measure detection IRQ */
    InterruptIn *_gpio1Int;
 
    ///* Digital out pin */
    //int gpio0;
    //int gpio1Int;
    /* Device data */
//    VL53L1_DEV_t MyDevice;
//    VL53L1_DEV Device;
    VL6180Dev_t MyDevice;
    MyVL6180Dev_t Device;
};


#endif /* _VL6180_CLASS_H_ */