use VL6180XA1 chip wothout X-NUCLEO-6180XA1 Board. Simple way to use the chip.

Dependents:   Check_VL6180XA1_ToF

Fork of X_NUCLEO_6180XA1 by ST

VL6180X.h

Committer:
kenjiArai
Date:
2018-02-01
Revision:
60:972b4898a007
Parent:
59:81afbb75311d

File content as of revision 60:972b4898a007:

/**
 ******************************************************************************
 * @file    VL6180X.h
 * @author  AST / EST
 * @version V0.0.1
 * @date    9-November-2015
 * @brief   Header file for component VL6180X
 ******************************************************************************
 * @attention
 *
 * <h2><center>&copy; COPYRIGHT(c) 2015 STMicroelectronics</center></h2>
 *
 * Redistribution and use in source and binary forms, with or without modification,
 * are permitted provided that the following conditions are met:
 *   1. Redistributions of source code must retain the above copyright notice,
 *      this list of conditions and the following disclaimer.
 *   2. 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.
 *   3. 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 AND FITNESS FOR A PARTICULAR PURPOSE ARE
 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS 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.
 *
 ******************************************************************************
*/

//------- Feburary 1st, 2018 by JH1PJL / K.Arai --------------------------------
// Change X_NUCLEO_6180XA1 library to 6180XA1_simplest library
//    modified -> all related files
//------------------------------------------------------------------------------

#ifndef __VL6180X_CLASS_H
#define __VL6180X_CLASS_H

/* Includes ------------------------------------------------------------------*/
#include "mbed.h"
#include "vl6180x_cfg.h"
#include "vl6180x_def.h"

/* Definitions ---------------------------------------------------------------*/
#define DEFAULT_DEVICE_ADDRESS		0x29

/* Types ---------------------------------------------------------------------*/

/* data struct containing range measure, light measure and type of error provided to the user
   in case of invalid data range_mm=0xFFFFFFFF and lux=0xFFFFFFFF */
typedef struct MeasureData {
    uint32_t range_mm;
    uint32_t lux;
    uint32_t range_error;
    uint32_t als_error;
    uint32_t int_error;
} measure_data_t;

/* sensor operating modes */
typedef enum {
    range_single_shot_polling=1,
    als_single_shot_polling,
    range_continuous_polling,
    als_continuous_polling,
} operating_mode_t;

struct MyVL6180Dev_t {
    struct VL6180XDevData_t Data;
    uint8_t I2cAddr;
    unsigned Present:1;
    unsigned Ready:1;
};
typedef struct MyVL6180Dev_t *VL6180XDev_t;

/** Interface for STMicronics VL6180X
 *  Proximity sensor, gesture and ambient light sensing (ALS) module
 *
 * @code
 * #include "mbed.h"
 *
 * // I2C Communication
 * VL6180X		sensor(I2C_SDA, I2C_SCL, D8);	// SDA, SCL & Chip Enable
 * // If you connected I2C line not only this device but also other devices,
 * //     you need to declare following method.
 * I2C			i2c(I2C_SDA, I2C_SCL);
 * VL6180X		sensor(i2c, D8);				// I2C, Chip Enable
 *
 * int main()
 * { 
 * 	 uint32_t lux;
 * 	 uint32_t dist;
 * 
 * 	 while (true) {
 * 		sensor.get_distance(&dist);
 * 		sensor.get_lux(&lux);
 * 		wait_ms(500);
 *   }
 * }
 * @endcode
 */

/* Classes -------------------------------------------------------------------*/
/**
 * Class representing a VL6180X sensor component
 */
class VL6180X
{
public:
    /** Constructor 1
     * @param[in] Pin for I2C SDA & SDL
     * @param[in] pin Mbed DigitalOut PinName to be used as component GPIO_0 CE
     * @param[in] DevAddr device address, 0x29 by default
     */
    VL6180X(PinName p_sda, PinName p_scl,PinName ce_pin, uint8_t DevAddr=DEFAULT_DEVICE_ADDRESS)
		: _i2c_p(new I2C(p_sda, p_scl)), _i2c(*_i2c_p), _gpio0(ce_pin)
	{
        _my_device.I2cAddr=DevAddr;
        _my_device.Present=0;
        _my_device.Ready=0;
        _device=&_my_device;;
        init();
    }

    /** Constructor 2
     * @param[in] &i2c device I2C to be used for communication
     * @param[in] pin Mbed DigitalOut PinName to be used as component GPIO_0 CE
     * @param[in] DevAddr device address, 0x29 by default
     */
    VL6180X(I2C& p_i2c, PinName ce_pin, uint8_t DevAddr=DEFAULT_DEVICE_ADDRESS)
		: _i2c(p_i2c), _gpio0(ce_pin)
	{
        _my_device.I2cAddr=DevAddr;
        _my_device.Present=0;
        _my_device.Ready=0;
        _device=&_my_device;;
        init();
    }

    /**
     * @brief Get a single distance measure result
     *
     * @par Function Description
     * It can be called after having initialized a component. It start a single
     * distance measure in polling mode and wait until the measure is finisched.
     * The function block until the measure is finished, it can blocks indefinitely
     * in case the measure never ends for any reason \n
     *
     * @param pi_data  Pointer to distance
     * @return 0 on success
     */
    virtual int get_distance(uint32_t *pi_data) {
        int status=0;
        status=start_measurement(range_single_shot_polling);
        if (!status) {
            VL6180X_RangeWaitDeviceReady(_device, 2000);
            for (status=1; status!=0; status=VL6180X_RangeGetResult(_device, pi_data));
        }
        stop_measurement(range_single_shot_polling);
        VL6180X_RangeWaitDeviceReady(_device, 2000);
        return status;
    }

    /**
     * @brief Get a single light (in Lux) measure result
     *
     * @par Function Description
     * It can be called after having initialized a component. It start a single
     * light measure in polling mode and wait until the measure is finisched.
     * The function block until the measure is finished, it can blocks indefinitely
     * in case the measure never ends for any reason \n
     */
    virtual int get_lux(uint32_t *pi_data) {
        int status=0;

        status = start_measurement(als_single_shot_polling);
        if (!status) {
            VL6180X_AlsWaitDeviceReady(_device, 2000);
            for (status=1; status!=0; status=VL6180X_AlsGetLux(_device, pi_data));
        }
        stop_measurement(als_single_shot_polling);
        VL6180X_AlsWaitDeviceReady(_device, 2000);
        return status;
    }

    /**
     *
     * @brief One time device initialization
     *
     * To be called once and only once after device is brought out of reset (Chip enable) and booted see @a VL6180X_WaitDeviceBooted()
     *
     * @par Function Description
     * When not used after a fresh device "power up" or reset, it may return @a #CALIBRATION_WARNING
     * meaning wrong calibration data may have been fetched from device that can result in ranging offset error\n
     * If application cannot execute device reset or need to run VL6180X_InitData  multiple time
     * then it  must ensure proper offset calibration saving and restore on its own
     * by using @a VL6180X_GetOffsetCalibrationData() on first power up and then @a VL6180X_SetOffsetCalibrationData() all all subsequent init
     *
     * @param void
     * @return     0 on success,  @a #CALIBRATION_WARNING if failed
    */
    int init(void) {
        int status;

        _gpio0 = 0;
        for(volatile uint32_t i = 0; i < 100000; i++) {
            ;
        }
        _gpio0 = 1;
        for(volatile uint32_t i = 0; i < 100000; i++) {
            ;
        }
        status = VL6180X_WaitDeviceBooted(_device);
        status = IsPresent();
        if(!status) {
            _device->Present=1;
            VL6180X_InitData(_device);
            if(status) {
                printf("Failed to init VL6180X sensor!\n\r");
                return status;
            }
            //status=prepare();
            status = VL6180X_Prepare(_device);
            if(status) {
                printf("Failed to prepare VL6180X!\n\r");
                return status;
            }
            _device->Ready = 1;
        }
        return status;
    }

private:
    static const unsigned int TEMP_BUF_SIZE = 32;

    /**
     * @brief  Writes a buffer towards the I2C peripheral device.
     * @param  pBuffer pointer to the byte-array data to send
     * @param  DeviceAddr specifies the peripheral device slave address.
     * @param  RegisterAddr specifies the internal address register
     *         where to start writing to (must be correctly masked).
     * @param  NumByteToWrite number of bytes to be written.
     * @retval 0 if ok,
     * @retval -1 if an I2C error has occured, or
     * @retval -2 on temporary buffer overflow (i.e. NumByteToWrite was too high)
     * @note   On some devices if NumByteToWrite is greater
     *         than one, the RegisterAddr must be masked correctly!
     */
    int i2c_write(uint8_t* pBuffer, uint8_t DeviceAddr, uint8_t RegisterAddr,
                  uint16_t NumByteToWrite) {
        int ret;
        uint8_t tmp[TEMP_BUF_SIZE];

        if(NumByteToWrite >= TEMP_BUF_SIZE) return -2;

        /* First, send device address. Then, send data and STOP condition */
        tmp[0] = RegisterAddr;
        memcpy(tmp+1, pBuffer, NumByteToWrite);

        ret = _i2c.write(DeviceAddr, (const char*)tmp, NumByteToWrite+1, false);

        if(ret) return -1;
        return 0;
    }

    /**
     * @brief  Reads a buffer from the I2C peripheral device.
     * @param  pBuffer pointer to the byte-array to read data in to
     * @param  DeviceAddr specifies the peripheral device slave address.
     * @param  RegisterAddr specifies the internal address register
     *         where to start reading from (must be correctly masked).
     * @param  NumByteToRead number of bytes to be read.
     * @retval 0 if ok,
     * @retval -1 if an I2C error has occured
     * @note   On some devices if NumByteToWrite is greater
     *         than one, the RegisterAddr must be masked correctly!
     */
    int i2c_read(uint8_t* pBuffer, uint8_t DeviceAddr, uint8_t RegisterAddr,
                 uint16_t NumByteToRead) {
        int ret;

        /* Send device address, with no STOP condition */
        ret = _i2c.write(DeviceAddr, (const char*)&RegisterAddr, 1, true);
        if(!ret) {
            /* Read data, with STOP condition  */
            ret = _i2c.read(DeviceAddr, (char*)pBuffer, NumByteToRead, false);
        }

        if(ret) return -1;
        return 0;
    }

    int start_measurement(operating_mode_t operating_mode);
    int stop_measurement(operating_mode_t operating_mode);
    int VL6180X_WaitDeviceBooted(VL6180XDev_t dev);
    int VL6180X_InitData(VL6180XDev_t dev );
    int VL6180X_Prepare(VL6180XDev_t dev);
    int VL6180X_RangeSetMaxConvergenceTime(VL6180XDev_t dev, uint8_t  MaxConTime_msec);
    int VL6180X_RangeGetResult(VL6180XDev_t dev, uint32_t *pRange_mm);
    int VL6180X_AlsSetIntegrationPeriod(VL6180XDev_t dev, uint16_t period_ms);
    int VL6180X_AlsSetInterMeasurementPeriod(VL6180XDev_t dev,  uint16_t intermeasurement_period_ms);
    int VL6180X_AlsSetAnalogueGain(VL6180XDev_t dev, uint8_t gain);
    int VL6180X_AlsSetThresholds(VL6180XDev_t dev, uint16_t low, uint16_t high);
    int VL6180X_StaticInit(VL6180XDev_t dev);
    int VL6180X_RangeWaitDeviceReady(VL6180XDev_t dev, int MaxLoop );
    int VL6180X_RangeSetRawThresholds(VL6180XDev_t dev, uint8_t low, uint8_t high);
    int VL6180X_RangeSetSystemMode(VL6180XDev_t dev, uint8_t mode);

    int VL6180X_AlsWaitDeviceReady(VL6180XDev_t dev, int MaxLoop );
    int VL6180X_AlsSetSystemMode(VL6180XDev_t dev, uint8_t mode);
    int VL6180X_SetGroupParamHold(VL6180XDev_t dev, int Hold);

    /*  Other functions defined in api.c */
    int VL6180X_RangeStaticInit(VL6180XDev_t dev);
    int VL6180X_AlsGetLux(VL6180XDev_t dev, lux_t *pLux);
    int VL6180X_RangeSetEarlyConvergenceEestimateThreshold(VL6180XDev_t dev);
    int32_t _GetAveTotalTime(VL6180XDev_t dev);

    /* Read function of the ID device */
    virtual int read_id(uint8_t *id);

    /* Write and read functions from I2C */
    int VL6180X_WrByte(VL6180XDev_t dev, uint16_t index, uint8_t data);
    int VL6180X_WrWord(VL6180XDev_t dev, uint16_t index, uint16_t data);
    int VL6180X_WrDWord(VL6180XDev_t dev, uint16_t index, uint32_t data);
    int VL6180X_RdByte(VL6180XDev_t dev, uint16_t index, uint8_t *data);
    int VL6180X_RdWord(VL6180XDev_t dev, uint16_t index, uint16_t *data);
    int VL6180X_RdDWord(VL6180XDev_t dev, uint16_t index, uint32_t *data);
    int VL6180X_UpdateByte(VL6180XDev_t dev, uint16_t index, uint8_t AndData, uint8_t OrData);
    int VL6180X_I2CWrite(uint8_t DeviceAddr, uint16_t RegisterAddr, uint8_t *pBuffer, uint16_t NumByteToWrite);
    int VL6180X_I2CRead(uint8_t DeviceAddr, uint16_t RegisterAddr, uint8_t *pBuffer, uint16_t NumByteToRead);

    int IsPresent();

    /* IO _device */
    I2C		*_i2c_p;
    I2C 	&_i2c;
    /* Digital out pin */
    DigitalOut _gpio0;
    /* _device data */
    MyVL6180Dev_t _my_device;
    VL6180XDev_t _device;
};

#endif // __VL6180X_CLASS_H