stm: laser: STM laser sensor driver.
Add STM laser sensor driver to configure and access laser data using i2c and cci configuration. This is a squash of the following commits from https://github.com/STFlightSenseLinuxDrivers/vl53l0-driver: commit ee84aaad0cc1b7b195dcade15b201829dd87d537 Author: Kalyan Vadlamudi <kalyan-kumar.vadlamudireddy@st.com> Date: Wed Jan 11 09:27:48 2017 -0800 STM Laser: Remove Proprietary License header in vl53l0_i2c_platform.c. Description: vl53l0_i2c_platform.c mentions Proprietary/Confidential information. Remove this and commit 3355587f03c25fbdd7febd68172d3d4339762665 Author: Kalyan Vadlamudi <kalyan-kumar.vadlamudireddy@st.com> Date: Thu Dec 8 15:11:32 2016 -0800 STM Laser: Fix compliation issue in stmvl53l0_module-cci.c. Description: Missing ending brace in stmvl53l0_cci_init() for the cci_client->cci_subdev check commit f85423250c4df248c15ffeddf35ec43d01751793 Author: Kalyan Vadlamudi <kalyan-kumar.vadlamudireddy@st.com> Date: Thu Nov 3 16:55:33 2016 -0700 STM Laser: Fix checkpatch warnings and errors. Description: Use checkpatch script from 4.4 kernel and fix the errors and errors. There are still few typedef related warning in the header files commit 6b3796838d66acb6dbcbdf004b554468f3dc1218 Author: Kalyan Vadlamudi <kalyan-kumar.vadlamudireddy@st.com> Date: Tue Aug 16 17:50:44 2016 -0700 STM Laser : Fix Laser initialization failure Description : Revert the code which powers up Laser device during module init time. CCI probe can happen after STM laser driver probe, which is causing issues during device initialization. Code has been modified to not power up the device during STM laser driver probe. commit 93b6897a2a8c6828169c2501690df7cccf8221c6 Author: Kalyan Vadlamudi <kalyan-kumar.vadlamudireddy@st.com> Date: Tue Aug 2 10:38:23 2016 -0700 Set Default build to USE_CCI commit 357b47b5d809334e8e7bdcad73950ac2bf817043 Author: Kalyan Vadlamudi <kalyan-kumar.vadlamudireddy@st.com> Date: Mon Aug 1 14:27:24 2016 -0700 Update stmvl53l0-cci.h with new fields in cci_data commit 95d072e03e5724445aba17c3a055c1518be9fc7e Author: Kalyan Vadlamudi <kalyan-kumar.vadlamudireddy@st.com> Date: Mon Aug 1 13:55:29 2016 -0700 Add support in CCI driver to read device tree files for gpios information and configure them if present. Power up the device before calling stmvl53l0_setupAPIFunctions commit 1a86a1fcfbbd55059a243588fde8691e1f9ae106 Author: Kalyan Vadlamudi <kalyan-kumar.vadlamudireddy@st.com> Date: Thu Jul 21 14:05:09 2016 -0700 first commit CRs-fixed: 1051771 Change-Id: I47d33f99e264d17549b0d0de174462796cf61978 Git-repo: https://github.com/STFlightSenseLinuxDrivers/vl53l0-driver Git-commit: 1a86a1fcfbbd55059a243588fde8691e1f9ae106 Git-commit: 95d072e03e5724445aba17c3a055c1518be9fc7e Git-commit: 357b47b5d809334e8e7bdcad73950ac2bf817043 Git-commit: 93b6897a2a8c6828169c2501690df7cccf8221c6 Git-commit: 6b3796838d66acb6dbcbdf004b554468f3dc1218 Git-commit: f85423250c4df248c15ffeddf35ec43d01751793 Git-commit: 3355587f03c25fbdd7febd68172d3d4339762665 Git-commit: ee84aaad0cc1b7b195dcade15b201829dd87d537 [bgurung@codeaurora.org: removed license and readme text files. Also removed executable permissions from files.] Signed-off-by: Bikas Gurung <bgurung@codeaurora.org>
This commit is contained in:
parent
37c5f804a2
commit
0a17df37be
36 changed files with 23533 additions and 0 deletions
20
drivers/input/misc/vl53L0/Makefile
Normal file
20
drivers/input/misc/vl53L0/Makefile
Normal file
|
@ -0,0 +1,20 @@
|
||||||
|
#
|
||||||
|
# Makefile for the vl53L0 drivers.
|
||||||
|
#
|
||||||
|
|
||||||
|
# Each configuration option enables a list of files.
|
||||||
|
#FEATURE_USE_CCI := false
|
||||||
|
FEATURE_USE_CCI := true
|
||||||
|
|
||||||
|
ifeq ($(FEATURE_USE_CCI), true)
|
||||||
|
ccflags-y += -Idrivers/input/misc/vl53L0/inc -DCAMERA_CCI
|
||||||
|
else
|
||||||
|
ccflags-y += -Idrivers/input/misc/vl53L0/inc
|
||||||
|
endif
|
||||||
|
|
||||||
|
ccflags-y += -Idrivers/media/platform/msm/camera_v2/sensor/io
|
||||||
|
ccflags-y += -Idrivers/media/platform/msm/camera_v2
|
||||||
|
ccflags-y += -Idrivers/media/platform/msm/camera_v2/common
|
||||||
|
ccflags-y += -Idrivers/media/platform/msm/camera_v2/sensor/cci
|
||||||
|
obj-$(CONFIG_STMVL53L0) += stmvl53l0.o
|
||||||
|
stmvl53l0-objs := stmvl53l0_module.o stmvl53l0_module-i2c.o stmvl53l0_module-cci.o src/vl53l0_api_calibration.o src/vl53l0_api_core.o src/vl53l0_api_histogram.o src/vl53l0_api_ranging.o src/vl53l0_api_strings.o src/vl53l0_api.o src/vl53l0_platform.o src/vl53l0_i2c_platform.o src/vl53l0_port_i2c.o src/vl53l010_api.o src/vl53l010_tuning.o
|
1476
drivers/input/misc/vl53L0/inc/vl53l010_api.h
Normal file
1476
drivers/input/misc/vl53L0/inc/vl53l010_api.h
Normal file
File diff suppressed because it is too large
Load diff
237
drivers/input/misc/vl53L0/inc/vl53l010_device.h
Normal file
237
drivers/input/misc/vl53L0/inc/vl53l010_device.h
Normal file
|
@ -0,0 +1,237 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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.
|
||||||
|
*******************************************************************************/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Device specific defines. To be adapted by implementer for the targeted
|
||||||
|
* device.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef _VL53L010_DEVICE_H_
|
||||||
|
#define _VL53L010_DEVICE_H_
|
||||||
|
|
||||||
|
#include "vl53l0_types.h"
|
||||||
|
|
||||||
|
/** @defgroup VL53L010_SpecDefines_group VL53L010 cut1.0 Device Specific Defines
|
||||||
|
* @brief VL53L010 cut1.0 Device Specific Defines
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/** @defgroup VL53L010_DeviceError_group Device Error
|
||||||
|
* @brief Device Error code
|
||||||
|
*
|
||||||
|
* This enum is Device specific it should be updated in the implementation
|
||||||
|
* Use @a VL53L010_GetStatusErrorString() to get the string.
|
||||||
|
* It is related to Status Register of the Device.
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
typedef uint8_t VL53L010_DeviceError;
|
||||||
|
|
||||||
|
#define VL53L010_DEVICEERROR_NONE ((VL53L010_DeviceError) 0)
|
||||||
|
#define VL53L010_DEVICEERROR_VCSELCONTINUITYTESTFAILURE \
|
||||||
|
((VL53L010_DeviceError) 1)
|
||||||
|
#define VL53L010_DEVICEERROR_VCSELWATCHDOGTESTFAILURE \
|
||||||
|
((VL53L010_DeviceError) 2)
|
||||||
|
#define VL53L010_DEVICEERROR_NOVHVVALUEFOUND \
|
||||||
|
((VL53L010_DeviceError) 3)
|
||||||
|
#define VL53L010_DEVICEERROR_MSRCNOTARGET \
|
||||||
|
((VL53L010_DeviceError) 4)
|
||||||
|
#define VL53L010_DEVICEERROR_MSRCMINIMUMSNR \
|
||||||
|
((VL53L010_DeviceError) 5)
|
||||||
|
#define VL53L010_DEVICEERROR_MSRCWRAPAROUND \
|
||||||
|
((VL53L010_DeviceError) 6)
|
||||||
|
#define VL53L010_DEVICEERROR_TCC \
|
||||||
|
((VL53L010_DeviceError) 7)
|
||||||
|
#define VL53L010_DEVICEERROR_RANGEAWRAPAROUND ((VL53L010_DeviceError)8)
|
||||||
|
#define VL53L010_DEVICEERROR_RANGEBWRAPAROUND ((VL53L010_DeviceError)9)
|
||||||
|
#define VL53L010_DEVICEERROR_MINCLIP ((VL53L010_DeviceError) 10)
|
||||||
|
#define VL53L010_DEVICEERROR_RANGECOMPLETE ((VL53L010_DeviceError) 11)
|
||||||
|
#define VL53L010_DEVICEERROR_ALGOUNDERFLOW ((VL53L010_DeviceError) 12)
|
||||||
|
#define VL53L010_DEVICEERROR_ALGOOVERFLOW ((VL53L010_DeviceError) 13)
|
||||||
|
#define VL53L010_DEVICEERROR_FINALSNRLIMIT ((VL53L010_DeviceError) 14)
|
||||||
|
#define VL53L010_DEVICEERROR_NOTARGETIGNORE ((VL53L010_DeviceError) 15)
|
||||||
|
|
||||||
|
/** @} VL53L010_DeviceError_group */
|
||||||
|
|
||||||
|
/** @defgroup VL53L010_CheckEnable_group Check Enable list
|
||||||
|
* @brief Check Enable code
|
||||||
|
*
|
||||||
|
* Define used to specify the LimitCheckId.
|
||||||
|
* Use @a VL53L010_GetLimitCheckInfo() to get the string.
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define VL53L010_CHECKENABLE_SIGMA_FINAL_RANGE 0
|
||||||
|
#define VL53L010_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE 1
|
||||||
|
#define VL53L010_CHECKENABLE_NUMBER_OF_CHECKS 2
|
||||||
|
|
||||||
|
/** @} VL53L010_CheckEnable_group */
|
||||||
|
|
||||||
|
/** @defgroup VL53L010_GpioFunctionality_group Gpio Functionality
|
||||||
|
* @brief Defines the different functionalities for the device GPIO(s)
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
typedef uint8_t VL53L010_GpioFunctionality;
|
||||||
|
|
||||||
|
#define VL53L010_GPIOFUNCTIONALITY_OFF \
|
||||||
|
((VL53L010_GpioFunctionality) 0)/*!< NO Interrupt */
|
||||||
|
#define VL53L010_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_LOW \
|
||||||
|
((VL53L010_GpioFunctionality) 1)/*!< Level Low (value < thresh_low) */
|
||||||
|
#define VL53L010_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_HIGH \
|
||||||
|
((VL53L010_GpioFunctionality) 2)/*!< Level High (value>thresh_high) */
|
||||||
|
/*!< Out Of Window (value < thresh_low OR value > thresh_high) */
|
||||||
|
#define VL53L010_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_OUT \
|
||||||
|
((VL53L010_GpioFunctionality) 3)
|
||||||
|
#define VL53L010_GPIOFUNCTIONALITY_NEW_MEASURE_READY \
|
||||||
|
((VL53L010_GpioFunctionality) 4) /*!< New Sample Ready */
|
||||||
|
|
||||||
|
/** @} VL53L010_GpioFunctionality_group */
|
||||||
|
|
||||||
|
/* Device register map */
|
||||||
|
|
||||||
|
/** @defgroup VL53L010_DefineRegisters_group Define Registers
|
||||||
|
* @brief List of all the defined registers
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
#define VL53L010_REG_SYSRANGE_START 0x000
|
||||||
|
/** mask existing bit in #VL53L010_REG_SYSRANGE_START*/
|
||||||
|
#define VL53L010_REG_SYSRANGE_MODE_MASK 0x0F
|
||||||
|
/** bit 0 in #VL53L010_REG_SYSRANGE_START write 1 toggle state in
|
||||||
|
* continuous mode and arm next shot in single shot mode
|
||||||
|
*/
|
||||||
|
#define VL53L010_REG_SYSRANGE_MODE_START_STOP 0x01
|
||||||
|
/** bit 1 write 0 in #VL53L010_REG_SYSRANGE_START set single shot mode */
|
||||||
|
#define VL53L010_REG_SYSRANGE_MODE_SINGLESHOT 0x00
|
||||||
|
/** bit 1 write 1 in #VL53L010_REG_SYSRANGE_START set back-to-back
|
||||||
|
* operation mode
|
||||||
|
*/
|
||||||
|
#define VL53L010_REG_SYSRANGE_MODE_BACKTOBACK 0x02
|
||||||
|
/** bit 2 write 1 in #VL53L010_REG_SYSRANGE_START set timed operation
|
||||||
|
* mode
|
||||||
|
*/
|
||||||
|
#define VL53L010_REG_SYSRANGE_MODE_TIMED 0x04
|
||||||
|
/** bit 3 write 1 in #VL53L010_REG_SYSRANGE_START set histogram
|
||||||
|
* operation mode
|
||||||
|
*/
|
||||||
|
#define VL53L010_REG_SYSRANGE_MODE_HISTOGRAM 0x08
|
||||||
|
|
||||||
|
#define VL53L010_REG_SYSTEM_THRESH_HIGH 0x000C /* NOSLC 2 bytes */
|
||||||
|
#define VL53L010_REG_SYSTEM_THRESH_LOW 0x000E /* NOSLC 2 bytes */
|
||||||
|
|
||||||
|
/* FPGA bitstream */
|
||||||
|
#define VL53L010_REG_SYSTEM_SEQUENCE_CONFIG 0x0001
|
||||||
|
#define VL53L010_REG_SYSTEM_INTERMEASUREMENT_PERIOD 0x0004
|
||||||
|
|
||||||
|
#define VL53L010_REG_SYSTEM_REPORT_REQUEST 0x0009
|
||||||
|
#define VL53L010_REG_SYSTEM_RANGEA_DATA 0x04
|
||||||
|
#define VL53L010_REG_SYSTEM_RANGEB_DATA 0x05
|
||||||
|
|
||||||
|
#define VL53L010_REG_SYSTEM_INTERRUPT_CONFIG_GPIO 0x000A
|
||||||
|
#define VL53L010_REG_SYSTEM_INTERRUPT_GPIO_DISABLED 0x00
|
||||||
|
#define VL53L010_REG_SYSTEM_INTERRUPT_GPIO_LEVEL_LOW 0x01
|
||||||
|
#define VL53L010_REG_SYSTEM_INTERRUPT_GPIO_LEVEL_HIGH 0x02
|
||||||
|
#define VL53L010_REG_SYSTEM_INTERRUPT_GPIO_OUT_OF_WINDOW 0x03
|
||||||
|
#define VL53L010_REG_SYSTEM_INTERRUPT_GPIO_NEW_SAMPLE_READY 0x04
|
||||||
|
|
||||||
|
#define VL53L010_REG_GPIO_HV_MUX_ACTIVE_HIGH 0x0084
|
||||||
|
|
||||||
|
#define VL53L010_REG_SYSTEM_INTERRUPT_CLEAR 0x000B
|
||||||
|
|
||||||
|
/* Result registers */
|
||||||
|
#define VL53L010_REG_RESULT_INTERRUPT_STATUS 0x0013
|
||||||
|
#define VL53L010_REG_RESULT_RANGE_STATUS 0x0014
|
||||||
|
|
||||||
|
#define VL53L010_REG_RESULT_SIGNAL_COUNT_RATE_RET 0x001A
|
||||||
|
#define VL53L010_REG_RESULT_AMBIENT_COUNT_RATE_RET 0x001C
|
||||||
|
#define VL53L010_REG_RESULT_FINAL_RANGE 0x001E
|
||||||
|
|
||||||
|
/* Algo register */
|
||||||
|
#define VL53L010_REG_ALGO_CROSSTALK_COMPENSATION_RATE 0x0020
|
||||||
|
#define VL53L010_REG_ALGO_RANGE_IGNORE_VALID_HEIGHT 0x0025
|
||||||
|
#define VL53L010_REG_ALGO_RANGE_IGNORE_THRESHOLD 0x0026
|
||||||
|
#define VL53L010_REG_ALGO_SNR_RATIO 0x0027
|
||||||
|
#define VL53L010_REG_ALGO_RANGE_CHECK_ENABLES 0x0028
|
||||||
|
|
||||||
|
#define VL53L010_REG_ALGO_PART_TO_PART_RANGE_OFFSET 0x0029
|
||||||
|
|
||||||
|
#define VL53L010_REG_I2C_SLAVE_DEVICE_ADDRESS 0x008a
|
||||||
|
|
||||||
|
/* MSRC registers */
|
||||||
|
#define VL53L010_REG_MSRC_CONFIG_COUNT 0x0044
|
||||||
|
#define VL53L010_REG_MSRC_CONFIG_TIMEOUT 0x0046
|
||||||
|
#define VL53L010_REG_MSRC_CONFIG_MIN_SNR 0x0055
|
||||||
|
#define VL53L010_REG_MSRC_CONFIG_VALID_PHASE_LOW 0x0047
|
||||||
|
#define VL53L010_REG_MSRC_CONFIG_VALID_PHASE_HIGH 0x0048
|
||||||
|
|
||||||
|
/* RANGE A registers */
|
||||||
|
#define VL53L010_REG_RNGA_CONFIG_VCSEL_PERIOD 0x0050
|
||||||
|
#define VL53L010_REG_RNGA_TIMEOUT_MSB 0x0051
|
||||||
|
#define VL53L010_REG_RNGA_TIMEOUT_LSB 0x0052
|
||||||
|
#define VL53L010_REG_RNGA_CONFIG_VALID_PHASE_LOW 0x0056
|
||||||
|
#define VL53L010_REG_RNGA_CONFIG_VALID_PHASE_HIGH 0x0057
|
||||||
|
|
||||||
|
/* RANGE B1 registers */
|
||||||
|
#define VL53L010_REG_RNGB1_CONFIG_VCSEL_PERIOD 0x0060
|
||||||
|
#define VL53L010_REG_RNGB1_TIMEOUT_MSB 0x0061
|
||||||
|
#define VL53L010_REG_RNGB1_TIMEOUT_LSB 0x0062
|
||||||
|
#define VL53L010_REG_RNGB1_CONFIG_VALID_PHASE_LOW 0x0066
|
||||||
|
#define VL53L010_REG_RNGB1_CONFIG_VALID_PHASE_HIGH 0x0067
|
||||||
|
|
||||||
|
/* RANGE B2 registers */
|
||||||
|
#define VL53L010_REG_RNGB2_CONFIG_VCSEL_PERIOD 0x0070
|
||||||
|
#define VL53L010_REG_RNGB2_TIMEOUT_MSB 0x0071
|
||||||
|
#define VL53L010_REG_RNGB2_TIMEOUT_LSB 0x0072
|
||||||
|
#define VL53L010_REG_RNGB2_CONFIG_VALID_PHASE_LOW 0x0076
|
||||||
|
#define VL53L010_REG_RNGB2_CONFIG_VALID_PHASE_HIGH 0x0077
|
||||||
|
|
||||||
|
#define VL53L010_REG_SOFT_RESET_GO2_SOFT_RESET_N 0x00bf
|
||||||
|
#define VL53L010_REG_IDENTIFICATION_MODEL_ID 0x00c0
|
||||||
|
#define VL53L010_REG_IDENTIFICATION_REVISION_ID 0x00c2
|
||||||
|
#define VL53L010_REG_IDENTIFICATION_MODULE_ID 0x00c3
|
||||||
|
|
||||||
|
#define VL53L010_REG_OSC_CALIBRATE_VAL 0x00f8
|
||||||
|
|
||||||
|
#define VL53L010_REG_FIRMWARE_MODE_STATUS 0x00C5
|
||||||
|
|
||||||
|
#define VL53L010_REG_DYNAMIC_SPAD_ACTUAL_RTN_SPADS_INT 0x0016
|
||||||
|
|
||||||
|
#define VL53L010_SIGMA_ESTIMATE_MAX_VALUE 65535
|
||||||
|
/*equivalent to a range sigma of 655.35mm */
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Speed of light in um per 1E-10 Seconds
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define VL53L010_SPEED_OF_LIGHT_IN_AIR 2997
|
||||||
|
|
||||||
|
/** @} VL53L010_DefineRegisters_group */
|
||||||
|
|
||||||
|
/** @} VL53L010_SpecDefines_group */
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* _VL53L010_DEVICE_H_ */
|
134
drivers/input/misc/vl53L0/inc/vl53l010_strings.h
Normal file
134
drivers/input/misc/vl53L0/inc/vl53l010_strings.h
Normal file
|
@ -0,0 +1,134 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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 VL53L010_STRINGS_H_
|
||||||
|
#define VL53L010_STRINGS_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define VL53L010_STRING_DEVICE_INFO_NAME \
|
||||||
|
"VL53L0 cut1.0"
|
||||||
|
#define VL53L010_STRING_DEVICE_INFO_NAME_TS0 \
|
||||||
|
"VL53L0 TS0"
|
||||||
|
#define VL53L010_STRING_DEVICE_INFO_NAME_TS1 \
|
||||||
|
"VL53L0 TS1"
|
||||||
|
#define VL53L010_STRING_DEVICE_INFO_NAME_TS2 \
|
||||||
|
"VL53L0 TS2"
|
||||||
|
#define VL53L010_STRING_DEVICE_INFO_NAME_ES1 \
|
||||||
|
"VL53L0 ES1 or later"
|
||||||
|
#define VL53L010_STRING_DEVICE_INFO_TYPE \
|
||||||
|
"VL53L0"
|
||||||
|
|
||||||
|
/* PAL ERROR strings */
|
||||||
|
#define VL53L010_STRING_ERROR_NONE \
|
||||||
|
"No Error"
|
||||||
|
#define VL53L010_STRING_ERROR_CALIBRATION_WARNING \
|
||||||
|
"Calibration Warning Error"
|
||||||
|
#define VL53L010_STRING_ERROR_MIN_CLIPPED \
|
||||||
|
"Min clipped error"
|
||||||
|
#define VL53L010_STRING_ERROR_UNDEFINED \
|
||||||
|
"Undefined error"
|
||||||
|
#define VL53L010_STRING_ERROR_INVALID_PARAMS \
|
||||||
|
"Invalid parameters error"
|
||||||
|
#define VL53L010_STRING_ERROR_NOT_SUPPORTED \
|
||||||
|
"Not supported error"
|
||||||
|
#define VL53L010_STRING_ERROR_RANGE_ERROR \
|
||||||
|
"Range error"
|
||||||
|
#define VL53L010_STRING_ERROR_TIME_OUT \
|
||||||
|
"Time out error"
|
||||||
|
#define VL53L010_STRING_ERROR_MODE_NOT_SUPPORTED \
|
||||||
|
"Mode not supported error"
|
||||||
|
#define VL53L010_STRING_ERROR_NOT_IMPLEMENTED \
|
||||||
|
"Not implemented error"
|
||||||
|
|
||||||
|
#define VL53L010_STRING_UNKNOW_ERROR_CODE \
|
||||||
|
"Unknow Error Code"
|
||||||
|
#define VL53L010_STRING_ERROR_BUFFER_TOO_SMALL \
|
||||||
|
"Buffer too small"
|
||||||
|
|
||||||
|
#define VL53L010_STRING_ERROR_GPIO_NOT_EXISTING \
|
||||||
|
"GPIO not existing"
|
||||||
|
#define VL53L010_STRING_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED \
|
||||||
|
"GPIO functionality not supported"
|
||||||
|
#define VL53L010_STRING_ERROR_CONTROL_INTERFACE \
|
||||||
|
"Control Interface Error"
|
||||||
|
|
||||||
|
|
||||||
|
/* Device Specific */
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_NONE \
|
||||||
|
"No Update"
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_VCSELCONTINUITYTESTFAILURE \
|
||||||
|
"VCSEL Continuity Test Failure"
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_VCSELWATCHDOGTESTFAILURE \
|
||||||
|
"VCSEL Watchdog Test Failure"
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_NOVHVVALUEFOUND \
|
||||||
|
"No VHV Value found"
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_MSRCNOTARGET \
|
||||||
|
"MSRC No Target Error"
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_MSRCMINIMUMSNR \
|
||||||
|
"MSRC Minimum SNR Error"
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_MSRCWRAPAROUND \
|
||||||
|
"MSRC Wraparound Error"
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_TCC \
|
||||||
|
"TCC Error"
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_RANGEAWRAPAROUND \
|
||||||
|
"Range A Wraparound Error"
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_RANGEBWRAPAROUND \
|
||||||
|
"Range B Wraparound Error"
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_MINCLIP \
|
||||||
|
"Min Clip Error"
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_RANGECOMPLETE \
|
||||||
|
"Range Complete"
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_ALGOUNDERFLOW \
|
||||||
|
"Range Algo Underflow Error"
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_ALGOOVERFLOW \
|
||||||
|
"Range Algo Overlow Error"
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_FINALSNRLIMIT \
|
||||||
|
"Final Minimum SNR Error"
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_NOTARGETIGNORE \
|
||||||
|
"No Target Ignore Error"
|
||||||
|
#define VL53L010_STRING_DEVICEERROR_UNKNOWN \
|
||||||
|
"Unknown error code"
|
||||||
|
|
||||||
|
|
||||||
|
/* Check Enable */
|
||||||
|
#define VL53L010_STRING_CHECKENABLE_SIGMA \
|
||||||
|
"SIGMA"
|
||||||
|
#define VL53L010_STRING_CHECKENABLE_SIGNAL_RATE \
|
||||||
|
"SIGNAL RATE"
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
58
drivers/input/misc/vl53L0/inc/vl53l010_tuning.h
Normal file
58
drivers/input/misc/vl53L0/inc/vl53l010_tuning.h
Normal file
|
@ -0,0 +1,58 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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 _VL53L010_TUNING_H_
|
||||||
|
#define _VL53L010_TUNING_H_
|
||||||
|
|
||||||
|
#include "vl53l0_def.h"
|
||||||
|
#include "vl53l0_platform.h"
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Internal function used to Program the default tuning settings
|
||||||
|
*
|
||||||
|
* @ingroup VL53L0_general_group
|
||||||
|
* @note This function access to the device
|
||||||
|
*
|
||||||
|
* @param Dev Device Handle
|
||||||
|
* @return VL53L0_ERROR_NONE Success
|
||||||
|
* @return "Other error code" See ::VL53L0_Error
|
||||||
|
*/
|
||||||
|
VL53L0_Error VL53L010_load_tuning_settings(VL53L0_DEV Dev);
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* _VL53L010_TUNING_H_ */
|
1950
drivers/input/misc/vl53L0/inc/vl53l0_api.h
Normal file
1950
drivers/input/misc/vl53L0/inc/vl53l0_api.h
Normal file
File diff suppressed because it is too large
Load diff
85
drivers/input/misc/vl53L0/inc/vl53l0_api_calibration.h
Normal file
85
drivers/input/misc/vl53L0/inc/vl53l0_api_calibration.h
Normal file
|
@ -0,0 +1,85 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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 _VL53L0_API_CALIBRATION_H_
|
||||||
|
#define _VL53L0_API_CALIBRATION_H_
|
||||||
|
|
||||||
|
#include "vl53l0_def.h"
|
||||||
|
#include "vl53l0_platform.h"
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_perform_xtalk_calibration(VL53L0_DEV Dev,
|
||||||
|
FixPoint1616_t XTalkCalDistance,
|
||||||
|
FixPoint1616_t *pXTalkCompensationRateMegaCps);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_perform_offset_calibration(VL53L0_DEV Dev,
|
||||||
|
FixPoint1616_t CalDistanceMilliMeter,
|
||||||
|
int32_t *pOffsetMicroMeter);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_set_offset_calibration_data_micro_meter(VL53L0_DEV Dev,
|
||||||
|
int32_t OffsetCalibrationDataMicroMeter);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_offset_calibration_data_micro_meter(VL53L0_DEV Dev,
|
||||||
|
int32_t *pOffsetCalibrationDataMicroMeter);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_apply_offset_adjustment(VL53L0_DEV Dev);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_perform_ref_spad_management(VL53L0_DEV Dev,
|
||||||
|
uint32_t *refSpadCount, uint8_t *isApertureSpads);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_set_reference_spads(VL53L0_DEV Dev,
|
||||||
|
uint32_t count, uint8_t isApertureSpads);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_reference_spads(VL53L0_DEV Dev,
|
||||||
|
uint32_t *pSpadCount, uint8_t *pIsApertureSpads);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_perform_phase_calibration(VL53L0_DEV Dev,
|
||||||
|
uint8_t *pPhaseCal, const uint8_t get_data_enable,
|
||||||
|
const uint8_t restore_config);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_perform_ref_calibration(VL53L0_DEV Dev,
|
||||||
|
uint8_t *pVhvSettings, uint8_t *pPhaseCal, uint8_t get_data_enable);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_set_ref_calibration(VL53L0_DEV Dev,
|
||||||
|
uint8_t VhvSettings, uint8_t PhaseCal);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_ref_calibration(VL53L0_DEV Dev,
|
||||||
|
uint8_t *pVhvSettings, uint8_t *pPhaseCal);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* _VL53L0_API_CALIBRATION_H_ */
|
108
drivers/input/misc/vl53L0/inc/vl53l0_api_core.h
Normal file
108
drivers/input/misc/vl53L0/inc/vl53l0_api_core.h
Normal file
|
@ -0,0 +1,108 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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 _VL53L0_API_CORE_H_
|
||||||
|
#define _VL53L0_API_CORE_H_
|
||||||
|
|
||||||
|
#include "vl53l0_def.h"
|
||||||
|
#include "vl53l0_platform.h"
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_reverse_bytes(uint8_t *data, uint32_t size);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_measurement_poll_for_completion(VL53L0_DEV Dev);
|
||||||
|
|
||||||
|
uint8_t VL53L0_encode_vcsel_period(uint8_t vcsel_period_pclks);
|
||||||
|
|
||||||
|
uint8_t VL53L0_decode_vcsel_period(uint8_t vcsel_period_reg);
|
||||||
|
|
||||||
|
uint32_t VL53L0_isqrt(uint32_t num);
|
||||||
|
|
||||||
|
uint32_t VL53L0_quadrature_sum(uint32_t a, uint32_t b);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_info_from_device(VL53L0_DEV Dev, uint8_t option);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_set_vcsel_pulse_period(VL53L0_DEV Dev,
|
||||||
|
VL53L0_VcselPeriod VcselPeriodType, uint8_t VCSELPulsePeriodPCLK);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_vcsel_pulse_period(VL53L0_DEV Dev,
|
||||||
|
VL53L0_VcselPeriod VcselPeriodType, uint8_t *pVCSELPulsePeriodPCLK);
|
||||||
|
|
||||||
|
uint32_t VL53L0_decode_timeout(uint16_t encoded_timeout);
|
||||||
|
|
||||||
|
VL53L0_Error get_sequence_step_timeout(VL53L0_DEV Dev,
|
||||||
|
VL53L0_SequenceStepId SequenceStepId,
|
||||||
|
uint32_t *pTimeOutMicroSecs);
|
||||||
|
|
||||||
|
VL53L0_Error set_sequence_step_timeout(VL53L0_DEV Dev,
|
||||||
|
VL53L0_SequenceStepId SequenceStepId,
|
||||||
|
uint32_t TimeOutMicroSecs);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_set_measurement_timing_budget_micro_seconds(VL53L0_DEV Dev,
|
||||||
|
uint32_t MeasurementTimingBudgetMicroSeconds);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_measurement_timing_budget_micro_seconds(VL53L0_DEV Dev,
|
||||||
|
uint32_t *pMeasurementTimingBudgetMicroSeconds);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_load_tuning_settings(VL53L0_DEV Dev,
|
||||||
|
uint8_t *pTuningSettingBuffer);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_calc_sigma_estimate(VL53L0_DEV Dev,
|
||||||
|
VL53L0_RangingMeasurementData_t *pRangingMeasurementData,
|
||||||
|
FixPoint1616_t *pSigmaEstimate, uint32_t *pDmax_mm);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_total_xtalk_rate(VL53L0_DEV Dev,
|
||||||
|
VL53L0_RangingMeasurementData_t *pRangingMeasurementData,
|
||||||
|
FixPoint1616_t *ptotal_xtalk_rate_mcps);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_total_signal_rate(VL53L0_DEV Dev,
|
||||||
|
VL53L0_RangingMeasurementData_t *pRangingMeasurementData,
|
||||||
|
FixPoint1616_t *ptotal_signal_rate_mcps);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_pal_range_status(VL53L0_DEV Dev,
|
||||||
|
uint8_t DeviceRangeStatus,
|
||||||
|
FixPoint1616_t SignalRate,
|
||||||
|
uint16_t EffectiveSpadRtnCount,
|
||||||
|
VL53L0_RangingMeasurementData_t *pRangingMeasurementData,
|
||||||
|
uint8_t *pPalRangeStatus);
|
||||||
|
|
||||||
|
uint32_t VL53L0_calc_timeout_mclks(VL53L0_DEV Dev,
|
||||||
|
uint32_t timeout_period_us, uint8_t vcsel_period_pclks);
|
||||||
|
|
||||||
|
uint16_t VL53L0_encode_timeout(uint32_t timeout_macro_clks);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* _VL53L0_API_CORE_H_ */
|
70
drivers/input/misc/vl53L0/inc/vl53l0_api_histogram.h
Normal file
70
drivers/input/misc/vl53L0/inc/vl53l0_api_histogram.h
Normal file
|
@ -0,0 +1,70 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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 _VL53L0_API_HISTOGRAM_H_
|
||||||
|
#define _VL53L0_API_HISTOGRAM_H_
|
||||||
|
|
||||||
|
#include "vl53l0_def.h"
|
||||||
|
#include "vl53l0_platform.h"
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_confirm_measurement_start(VL53L0_DEV Dev);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_set_histogram_mode(VL53L0_DEV Dev,
|
||||||
|
VL53L0_HistogramModes HistogramMode);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_histogram_mode(VL53L0_DEV Dev,
|
||||||
|
VL53L0_HistogramModes *pHistogramMode);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_start_histogram_measurement(VL53L0_DEV Dev,
|
||||||
|
VL53L0_HistogramModes histoMode,
|
||||||
|
uint32_t count);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_perform_single_histogram_measurement(VL53L0_DEV Dev,
|
||||||
|
VL53L0_HistogramMeasurementData_t *pHistogramMeasurementData);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_histogram_measurement_data(VL53L0_DEV Dev,
|
||||||
|
VL53L0_HistogramMeasurementData_t *pHistogramMeasurementData);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_read_histo_measurement(VL53L0_DEV Dev,
|
||||||
|
uint32_t *histoData, uint32_t offset, VL53L0_HistogramModes histoMode);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_perform_xtalk_measurement(VL53L0_DEV dev,
|
||||||
|
uint32_t timeout_ms, FixPoint1616_t *pxtalk_per_spad,
|
||||||
|
uint8_t *pambient_too_high);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* _VL53L0_API_HISTOGRAM_H_ */
|
47
drivers/input/misc/vl53L0/inc/vl53l0_api_ranging.h
Normal file
47
drivers/input/misc/vl53L0/inc/vl53l0_api_ranging.h
Normal file
|
@ -0,0 +1,47 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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 _VL53L0_API_RANGING_H_
|
||||||
|
#define _VL53L0_API_RANGING_H_
|
||||||
|
|
||||||
|
#include "vl53l0_def.h"
|
||||||
|
#include "vl53l0_platform.h"
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* _VL53L0_API_RANGING_H_ */
|
277
drivers/input/misc/vl53L0/inc/vl53l0_api_strings.h
Normal file
277
drivers/input/misc/vl53L0/inc/vl53l0_api_strings.h
Normal file
|
@ -0,0 +1,277 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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 VL53L0_API_STRINGS_H_
|
||||||
|
#define VL53L0_API_STRINGS_H_
|
||||||
|
|
||||||
|
#include "vl53l0_def.h"
|
||||||
|
#include "vl53l0_platform.h"
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_device_info(VL53L0_DEV Dev,
|
||||||
|
VL53L0_DeviceInfo_t *pVL53L0_DeviceInfo);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_device_error_string(VL53L0_DeviceError ErrorCode,
|
||||||
|
char *pDeviceErrorString);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_range_status_string(uint8_t RangeStatus,
|
||||||
|
char *pRangeStatusString);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_pal_error_string(VL53L0_Error PalErrorCode,
|
||||||
|
char *pPalErrorString);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_pal_state_string(VL53L0_State PalStateCode,
|
||||||
|
char *pPalStateString);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_sequence_steps_info(
|
||||||
|
VL53L0_SequenceStepId SequenceStepId,
|
||||||
|
char *pSequenceStepsString);
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_limit_check_info(VL53L0_DEV Dev, uint16_t LimitCheckId,
|
||||||
|
char *pLimitCheckString);
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef USE_EMPTY_STRING
|
||||||
|
#define VL53L0_STRING_DEVICE_INFO_NAME ""
|
||||||
|
#define VL53L0_STRING_DEVICE_INFO_NAME_TS0 ""
|
||||||
|
#define VL53L0_STRING_DEVICE_INFO_NAME_TS1 ""
|
||||||
|
#define VL53L0_STRING_DEVICE_INFO_NAME_TS2 ""
|
||||||
|
#define VL53L0_STRING_DEVICE_INFO_NAME_ES1 ""
|
||||||
|
#define VL53L0_STRING_DEVICE_INFO_TYPE ""
|
||||||
|
|
||||||
|
/* PAL ERROR strings */
|
||||||
|
#define VL53L0_STRING_ERROR_NONE ""
|
||||||
|
#define VL53L0_STRING_ERROR_CALIBRATION_WARNING ""
|
||||||
|
#define VL53L0_STRING_ERROR_MIN_CLIPPED ""
|
||||||
|
#define VL53L0_STRING_ERROR_UNDEFINED ""
|
||||||
|
#define VL53L0_STRING_ERROR_INVALID_PARAMS ""
|
||||||
|
#define VL53L0_STRING_ERROR_NOT_SUPPORTED ""
|
||||||
|
#define VL53L0_STRING_ERROR_RANGE_ERROR ""
|
||||||
|
#define VL53L0_STRING_ERROR_TIME_OUT ""
|
||||||
|
#define VL53L0_STRING_ERROR_MODE_NOT_SUPPORTED ""
|
||||||
|
#define VL53L0_STRING_ERROR_BUFFER_TOO_SMALL ""
|
||||||
|
#define VL53L0_STRING_ERROR_GPIO_NOT_EXISTING ""
|
||||||
|
#define VL53L0_STRING_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED ""
|
||||||
|
#define VL53L0_STRING_ERROR_CONTROL_INTERFACE ""
|
||||||
|
#define VL53L0_STRING_ERROR_INVALID_COMMAND ""
|
||||||
|
#define VL53L0_STRING_ERROR_DIVISION_BY_ZERO ""
|
||||||
|
#define VL53L0_STRING_ERROR_REF_SPAD_INIT ""
|
||||||
|
#define VL53L0_STRING_ERROR_NOT_IMPLEMENTED ""
|
||||||
|
|
||||||
|
#define VL53L0_STRING_UNKNOW_ERROR_CODE ""
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/* Range Status */
|
||||||
|
#define VL53L0_STRING_RANGESTATUS_NONE ""
|
||||||
|
#define VL53L0_STRING_RANGESTATUS_RANGEVALID ""
|
||||||
|
#define VL53L0_STRING_RANGESTATUS_SIGMA ""
|
||||||
|
#define VL53L0_STRING_RANGESTATUS_SIGNAL ""
|
||||||
|
#define VL53L0_STRING_RANGESTATUS_MINRANGE ""
|
||||||
|
#define VL53L0_STRING_RANGESTATUS_PHASE ""
|
||||||
|
#define VL53L0_STRING_RANGESTATUS_HW ""
|
||||||
|
|
||||||
|
|
||||||
|
/* Range Status */
|
||||||
|
#define VL53L0_STRING_STATE_POWERDOWN ""
|
||||||
|
#define VL53L0_STRING_STATE_WAIT_STATICINIT ""
|
||||||
|
#define VL53L0_STRING_STATE_STANDBY ""
|
||||||
|
#define VL53L0_STRING_STATE_IDLE ""
|
||||||
|
#define VL53L0_STRING_STATE_RUNNING ""
|
||||||
|
#define VL53L0_STRING_STATE_UNKNOWN ""
|
||||||
|
#define VL53L0_STRING_STATE_ERROR ""
|
||||||
|
|
||||||
|
|
||||||
|
/* Device Specific */
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_NONE ""
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_VCSELCONTINUITYTESTFAILURE ""
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_VCSELWATCHDOGTESTFAILURE ""
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_NOVHVVALUEFOUND ""
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_MSRCNOTARGET ""
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_SNRCHECK ""
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_RANGEPHASECHECK ""
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_SIGMATHRESHOLDCHECK ""
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_TCC ""
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_PHASECONSISTENCY ""
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_MINCLIP ""
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_RANGECOMPLETE ""
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_ALGOUNDERFLOW ""
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_ALGOOVERFLOW ""
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_RANGEIGNORETHRESHOLD ""
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_UNKNOWN ""
|
||||||
|
|
||||||
|
/* Check Enable */
|
||||||
|
#define VL53L0_STRING_CHECKENABLE_SIGMA_FINAL_RANGE ""
|
||||||
|
#define VL53L0_STRING_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE ""
|
||||||
|
#define VL53L0_STRING_CHECKENABLE_SIGNAL_REF_CLIP ""
|
||||||
|
#define VL53L0_STRING_CHECKENABLE_RANGE_IGNORE_THRESHOLD ""
|
||||||
|
|
||||||
|
/* Sequence Step */
|
||||||
|
#define VL53L0_STRING_SEQUENCESTEP_TCC ""
|
||||||
|
#define VL53L0_STRING_SEQUENCESTEP_DSS ""
|
||||||
|
#define VL53L0_STRING_SEQUENCESTEP_MSRC ""
|
||||||
|
#define VL53L0_STRING_SEQUENCESTEP_PRE_RANGE ""
|
||||||
|
#define VL53L0_STRING_SEQUENCESTEP_FINAL_RANGE ""
|
||||||
|
#else
|
||||||
|
#define VL53L0_STRING_DEVICE_INFO_NAME "VL53L0 cut1.0"
|
||||||
|
#define VL53L0_STRING_DEVICE_INFO_NAME_TS0 "VL53L0 TS0"
|
||||||
|
#define VL53L0_STRING_DEVICE_INFO_NAME_TS1 "VL53L0 TS1"
|
||||||
|
#define VL53L0_STRING_DEVICE_INFO_NAME_TS2 "VL53L0 TS2"
|
||||||
|
#define VL53L0_STRING_DEVICE_INFO_NAME_ES1 "VL53L0 ES1 or later"
|
||||||
|
#define VL53L0_STRING_DEVICE_INFO_TYPE "VL53L0"
|
||||||
|
|
||||||
|
/* PAL ERROR strings */
|
||||||
|
#define VL53L0_STRING_ERROR_NONE \
|
||||||
|
"No Error"
|
||||||
|
#define VL53L0_STRING_ERROR_CALIBRATION_WARNING \
|
||||||
|
"Calibration Warning Error"
|
||||||
|
#define VL53L0_STRING_ERROR_MIN_CLIPPED \
|
||||||
|
"Min clipped error"
|
||||||
|
#define VL53L0_STRING_ERROR_UNDEFINED \
|
||||||
|
"Undefined error"
|
||||||
|
#define VL53L0_STRING_ERROR_INVALID_PARAMS \
|
||||||
|
"Invalid parameters error"
|
||||||
|
#define VL53L0_STRING_ERROR_NOT_SUPPORTED \
|
||||||
|
"Not supported error"
|
||||||
|
#define VL53L0_STRING_ERROR_RANGE_ERROR \
|
||||||
|
"Range error"
|
||||||
|
#define VL53L0_STRING_ERROR_TIME_OUT \
|
||||||
|
"Time out error"
|
||||||
|
#define VL53L0_STRING_ERROR_MODE_NOT_SUPPORTED \
|
||||||
|
"Mode not supported error"
|
||||||
|
#define VL53L0_STRING_ERROR_BUFFER_TOO_SMALL \
|
||||||
|
"Buffer too small"
|
||||||
|
#define VL53L0_STRING_ERROR_GPIO_NOT_EXISTING \
|
||||||
|
"GPIO not existing"
|
||||||
|
#define VL53L0_STRING_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED \
|
||||||
|
"GPIO funct not supported"
|
||||||
|
#define VL53L0_STRING_ERROR_INTERRUPT_NOT_CLEARED \
|
||||||
|
"Interrupt not Cleared"
|
||||||
|
#define VL53L0_STRING_ERROR_CONTROL_INTERFACE \
|
||||||
|
"Control Interface Error"
|
||||||
|
#define VL53L0_STRING_ERROR_INVALID_COMMAND \
|
||||||
|
"Invalid Command Error"
|
||||||
|
#define VL53L0_STRING_ERROR_DIVISION_BY_ZERO \
|
||||||
|
"Division by zero Error"
|
||||||
|
#define VL53L0_STRING_ERROR_REF_SPAD_INIT \
|
||||||
|
"Reference Spad Init Error"
|
||||||
|
#define VL53L0_STRING_ERROR_NOT_IMPLEMENTED \
|
||||||
|
"Not implemented error"
|
||||||
|
|
||||||
|
#define VL53L0_STRING_UNKNOW_ERROR_CODE \
|
||||||
|
"Unknown Error Code"
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/* Range Status */
|
||||||
|
#define VL53L0_STRING_RANGESTATUS_NONE "No Update"
|
||||||
|
#define VL53L0_STRING_RANGESTATUS_RANGEVALID "Range Valid"
|
||||||
|
#define VL53L0_STRING_RANGESTATUS_SIGMA "Sigma Fail"
|
||||||
|
#define VL53L0_STRING_RANGESTATUS_SIGNAL "Signal Fail"
|
||||||
|
#define VL53L0_STRING_RANGESTATUS_MINRANGE "Min Range Fail"
|
||||||
|
#define VL53L0_STRING_RANGESTATUS_PHASE "Phase Fail"
|
||||||
|
#define VL53L0_STRING_RANGESTATUS_HW "Hardware Fail"
|
||||||
|
|
||||||
|
|
||||||
|
/* Range Status */
|
||||||
|
#define VL53L0_STRING_STATE_POWERDOWN "POWERDOWN State"
|
||||||
|
#define VL53L0_STRING_STATE_WAIT_STATICINIT \
|
||||||
|
"Wait for staticinit State"
|
||||||
|
#define VL53L0_STRING_STATE_STANDBY "STANDBY State"
|
||||||
|
#define VL53L0_STRING_STATE_IDLE "IDLE State"
|
||||||
|
#define VL53L0_STRING_STATE_RUNNING "RUNNING State"
|
||||||
|
#define VL53L0_STRING_STATE_UNKNOWN "UNKNOWN State"
|
||||||
|
#define VL53L0_STRING_STATE_ERROR "ERROR State"
|
||||||
|
|
||||||
|
|
||||||
|
/* Device Specific */
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_NONE "No Update"
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_VCSELCONTINUITYTESTFAILURE \
|
||||||
|
"VCSEL Continuity Test Failure"
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_VCSELWATCHDOGTESTFAILURE \
|
||||||
|
"VCSEL Watchdog Test Failure"
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_NOVHVVALUEFOUND \
|
||||||
|
"No VHV Value found"
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_MSRCNOTARGET \
|
||||||
|
"MSRC No Target Error"
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_SNRCHECK \
|
||||||
|
"SNR Check Exit"
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_RANGEPHASECHECK \
|
||||||
|
"Range Phase Check Error"
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_SIGMATHRESHOLDCHECK \
|
||||||
|
"Sigma Threshold Check Error"
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_TCC \
|
||||||
|
"TCC Error"
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_PHASECONSISTENCY \
|
||||||
|
"Phase Consistency Error"
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_MINCLIP \
|
||||||
|
"Min Clip Error"
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_RANGECOMPLETE \
|
||||||
|
"Range Complete"
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_ALGOUNDERFLOW \
|
||||||
|
"Range Algo Underflow Error"
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_ALGOOVERFLOW \
|
||||||
|
"Range Algo Overlow Error"
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_RANGEIGNORETHRESHOLD \
|
||||||
|
"Range Ignore Threshold Error"
|
||||||
|
#define VL53L0_STRING_DEVICEERROR_UNKNOWN \
|
||||||
|
"Unknown error code"
|
||||||
|
|
||||||
|
/* Check Enable */
|
||||||
|
#define VL53L0_STRING_CHECKENABLE_SIGMA_FINAL_RANGE \
|
||||||
|
"SIGMA FINAL RANGE"
|
||||||
|
#define VL53L0_STRING_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE \
|
||||||
|
"SIGNAL RATE FINAL RANGE"
|
||||||
|
#define VL53L0_STRING_CHECKENABLE_SIGNAL_REF_CLIP \
|
||||||
|
"SIGNAL REF CLIP"
|
||||||
|
#define VL53L0_STRING_CHECKENABLE_RANGE_IGNORE_THRESHOLD \
|
||||||
|
"RANGE IGNORE THRESHOLD"
|
||||||
|
#define VL53L0_STRING_CHECKENABLE_SIGNAL_RATE_MSRC \
|
||||||
|
"SIGNAL RATE MSRC"
|
||||||
|
#define VL53L0_STRING_CHECKENABLE_SIGNAL_RATE_PRE_RANGE \
|
||||||
|
"SIGNAL RATE PRE RANGE"
|
||||||
|
|
||||||
|
/* Sequence Step */
|
||||||
|
#define VL53L0_STRING_SEQUENCESTEP_TCC "TCC"
|
||||||
|
#define VL53L0_STRING_SEQUENCESTEP_DSS "DSS"
|
||||||
|
#define VL53L0_STRING_SEQUENCESTEP_MSRC "MSRC"
|
||||||
|
#define VL53L0_STRING_SEQUENCESTEP_PRE_RANGE "PRE RANGE"
|
||||||
|
#define VL53L0_STRING_SEQUENCESTEP_FINAL_RANGE "FINAL RANGE"
|
||||||
|
#endif /* USE_EMPTY_STRING */
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
663
drivers/input/misc/vl53L0/inc/vl53l0_def.h
Normal file
663
drivers/input/misc/vl53L0/inc/vl53l0_def.h
Normal file
|
@ -0,0 +1,663 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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.
|
||||||
|
*******************************************************************************/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file VL53L0_def.h
|
||||||
|
*
|
||||||
|
* @brief Type definitions for VL53L0 API.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef _VL53L0_DEF_H_
|
||||||
|
#define _VL53L0_DEF_H_
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/** @defgroup VL53L0_globaldefine_group VL53L0 Defines
|
||||||
|
* @brief VL53L0 Defines
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
/** PAL SPECIFICATION major version */
|
||||||
|
#define VL53L010_SPECIFICATION_VER_MAJOR 1
|
||||||
|
/** PAL SPECIFICATION minor version */
|
||||||
|
#define VL53L010_SPECIFICATION_VER_MINOR 2
|
||||||
|
/** PAL SPECIFICATION sub version */
|
||||||
|
#define VL53L010_SPECIFICATION_VER_SUB 7
|
||||||
|
/** PAL SPECIFICATION sub version */
|
||||||
|
#define VL53L010_SPECIFICATION_VER_REVISION 1440
|
||||||
|
|
||||||
|
/** VL53L0 PAL IMPLEMENTATION major version */
|
||||||
|
#define VL53L010_IMPLEMENTATION_VER_MAJOR 1
|
||||||
|
/** VL53L0 PAL IMPLEMENTATION minor version */
|
||||||
|
#define VL53L010_IMPLEMENTATION_VER_MINOR 0
|
||||||
|
/** VL53L0 PAL IMPLEMENTATION sub version */
|
||||||
|
#define VL53L010_IMPLEMENTATION_VER_SUB 9
|
||||||
|
/** VL53L0 PAL IMPLEMENTATION sub version */
|
||||||
|
#define VL53L010_IMPLEMENTATION_VER_REVISION 3673
|
||||||
|
|
||||||
|
/** PAL SPECIFICATION major version */
|
||||||
|
#define VL53L0_SPECIFICATION_VER_MAJOR 1
|
||||||
|
/** PAL SPECIFICATION minor version */
|
||||||
|
#define VL53L0_SPECIFICATION_VER_MINOR 2
|
||||||
|
/** PAL SPECIFICATION sub version */
|
||||||
|
#define VL53L0_SPECIFICATION_VER_SUB 7
|
||||||
|
/** PAL SPECIFICATION sub version */
|
||||||
|
#define VL53L0_SPECIFICATION_VER_REVISION 1440
|
||||||
|
|
||||||
|
/** VL53L0 PAL IMPLEMENTATION major version */
|
||||||
|
#define VL53L0_IMPLEMENTATION_VER_MAJOR 1
|
||||||
|
/** VL53L0 PAL IMPLEMENTATION minor version */
|
||||||
|
#define VL53L0_IMPLEMENTATION_VER_MINOR 1
|
||||||
|
/** VL53L0 PAL IMPLEMENTATION sub version */
|
||||||
|
#define VL53L0_IMPLEMENTATION_VER_SUB 20
|
||||||
|
/** VL53L0 PAL IMPLEMENTATION sub version */
|
||||||
|
#define VL53L0_IMPLEMENTATION_VER_REVISION 4606
|
||||||
|
#define VL53L0_DEFAULT_MAX_LOOP 200
|
||||||
|
#define VL53L0_MAX_STRING_LENGTH 32
|
||||||
|
|
||||||
|
|
||||||
|
#include "vl53l0_device.h"
|
||||||
|
#include "vl53l0_types.h"
|
||||||
|
|
||||||
|
|
||||||
|
/****************************************
|
||||||
|
* PRIVATE define do not edit
|
||||||
|
****************************************/
|
||||||
|
|
||||||
|
/** @brief Defines the parameters of the Get Version Functions
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint32_t revision; /*!< revision number */
|
||||||
|
uint8_t major; /*!< major number */
|
||||||
|
uint8_t minor; /*!< minor number */
|
||||||
|
uint8_t build; /*!< build number */
|
||||||
|
} VL53L0_Version_t;
|
||||||
|
|
||||||
|
|
||||||
|
/** @brief Defines the parameters of the Get Device Info Functions
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
char Name[VL53L0_MAX_STRING_LENGTH];
|
||||||
|
/*!< Name of the Device e.g. Left_Distance */
|
||||||
|
char Type[VL53L0_MAX_STRING_LENGTH];
|
||||||
|
/*!< Type of the Device e.g VL53L0 */
|
||||||
|
char ProductId[VL53L0_MAX_STRING_LENGTH];
|
||||||
|
/*!< Product Identifier String */
|
||||||
|
uint8_t ProductType;
|
||||||
|
/*!< Product Type, VL53L0 = 1, VL53L1 = 2 */
|
||||||
|
uint8_t ProductRevisionMajor;
|
||||||
|
/*!< Product revision major */
|
||||||
|
uint8_t ProductRevisionMinor;
|
||||||
|
/*!< Product revision minor */
|
||||||
|
} VL53L0_DeviceInfo_t;
|
||||||
|
|
||||||
|
|
||||||
|
/** @defgroup VL53L0_define_Error_group Error and Warning code returned by API
|
||||||
|
* The following DEFINE are used to identify the PAL ERROR
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
typedef int8_t VL53L0_Error;
|
||||||
|
|
||||||
|
#define VL53L0_ERROR_NONE ((VL53L0_Error) 0)
|
||||||
|
#define VL53L0_ERROR_CALIBRATION_WARNING ((VL53L0_Error) - 1)
|
||||||
|
/*!< Warning invalid calibration data may be in used
|
||||||
|
* \a VL53L0_InitData()
|
||||||
|
* \a VL53L0_GetOffsetCalibrationData
|
||||||
|
* \a VL53L0_SetOffsetCalibrationData
|
||||||
|
*/
|
||||||
|
#define VL53L0_ERROR_MIN_CLIPPED ((VL53L0_Error) - 2)
|
||||||
|
/*!< Warning parameter passed was clipped to min before to be applied */
|
||||||
|
|
||||||
|
#define VL53L0_ERROR_UNDEFINED ((VL53L0_Error) - 3)
|
||||||
|
/*!< Unqualified error */
|
||||||
|
#define VL53L0_ERROR_INVALID_PARAMS ((VL53L0_Error) - 4)
|
||||||
|
/*!< Parameter passed is invalid or out of range */
|
||||||
|
#define VL53L0_ERROR_NOT_SUPPORTED ((VL53L0_Error) - 5)
|
||||||
|
/*!< Function is not supported in current mode or configuration */
|
||||||
|
#define VL53L0_ERROR_RANGE_ERROR ((VL53L0_Error) - 6)
|
||||||
|
/*!< Device report a ranging error interrupt status */
|
||||||
|
#define VL53L0_ERROR_TIME_OUT ((VL53L0_Error) - 7)
|
||||||
|
/*!< Aborted due to time out */
|
||||||
|
#define VL53L0_ERROR_MODE_NOT_SUPPORTED ((VL53L0_Error) - 8)
|
||||||
|
/*!< Asked mode is not supported by the device */
|
||||||
|
#define VL53L0_ERROR_BUFFER_TOO_SMALL ((VL53L0_Error) - 9)
|
||||||
|
/*!< ... */
|
||||||
|
#define VL53L0_ERROR_GPIO_NOT_EXISTING ((VL53L0_Error) - 10)
|
||||||
|
/*!< User tried to setup a non-existing GPIO pin */
|
||||||
|
#define VL53L0_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED ((VL53L0_Error) - 11)
|
||||||
|
/*!< unsupported GPIO functionality */
|
||||||
|
#define VL53L0_ERROR_INTERRUPT_NOT_CLEARED ((VL53L0_Error) - 12)
|
||||||
|
/*!< Error during interrupt clear */
|
||||||
|
#define VL53L0_ERROR_CONTROL_INTERFACE ((VL53L0_Error) - 20)
|
||||||
|
/*!< error reported from IO functions */
|
||||||
|
#define VL53L0_ERROR_INVALID_COMMAND ((VL53L0_Error) - 30)
|
||||||
|
/*!< The command is not allowed in the current device state
|
||||||
|
* (power down)
|
||||||
|
*/
|
||||||
|
#define VL53L0_ERROR_DIVISION_BY_ZERO ((VL53L0_Error) - 40)
|
||||||
|
/*!< In the function a division by zero occurs */
|
||||||
|
#define VL53L0_ERROR_REF_SPAD_INIT ((VL53L0_Error) - 50)
|
||||||
|
/*!< Error during reference SPAD initialization */
|
||||||
|
#define VL53L0_ERROR_NOT_IMPLEMENTED ((VL53L0_Error) - 99)
|
||||||
|
/*!< Tells requested functionality has not been implemented yet or
|
||||||
|
* not compatible with the device
|
||||||
|
*/
|
||||||
|
/** @} VL53L0_define_Error_group */
|
||||||
|
|
||||||
|
|
||||||
|
/** @defgroup VL53L0_define_DeviceModes_group Defines Device modes
|
||||||
|
* Defines all possible modes for the device
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
typedef uint8_t VL53L0_DeviceModes;
|
||||||
|
|
||||||
|
#define VL53L0_DEVICEMODE_SINGLE_RANGING ((VL53L0_DeviceModes) 0)
|
||||||
|
#define VL53L0_DEVICEMODE_CONTINUOUS_RANGING ((VL53L0_DeviceModes) 1)
|
||||||
|
#define VL53L0_DEVICEMODE_SINGLE_HISTOGRAM ((VL53L0_DeviceModes) 2)
|
||||||
|
#define VL53L0_DEVICEMODE_CONTINUOUS_TIMED_RANGING ((VL53L0_DeviceModes) 3)
|
||||||
|
#define VL53L0_DEVICEMODE_SINGLE_ALS ((VL53L0_DeviceModes) 10)
|
||||||
|
#define VL53L0_DEVICEMODE_GPIO_DRIVE ((VL53L0_DeviceModes) 20)
|
||||||
|
#define VL53L0_DEVICEMODE_GPIO_OSC ((VL53L0_DeviceModes) 21)
|
||||||
|
/* ... Modes to be added depending on device */
|
||||||
|
/** @} VL53L0_define_DeviceModes_group */
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/** @defgroup VL53L0_define_HistogramModes_group Defines Histogram modes
|
||||||
|
* Defines all possible Histogram modes for the device
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
typedef uint8_t VL53L0_HistogramModes;
|
||||||
|
|
||||||
|
#define VL53L0_HISTOGRAMMODE_DISABLED ((VL53L0_HistogramModes) 0)
|
||||||
|
/*!< Histogram Disabled */
|
||||||
|
#define VL53L0_HISTOGRAMMODE_REFERENCE_ONLY ((VL53L0_HistogramModes) 1)
|
||||||
|
/*!< Histogram Reference array only */
|
||||||
|
#define VL53L0_HISTOGRAMMODE_RETURN_ONLY ((VL53L0_HistogramModes) 2)
|
||||||
|
/*!< Histogram Return array only */
|
||||||
|
#define VL53L0_HISTOGRAMMODE_BOTH ((VL53L0_HistogramModes) 3)
|
||||||
|
/*!< Histogram both Reference and Return Arrays */
|
||||||
|
/* ... Modes to be added depending on device */
|
||||||
|
/** @} VL53L0_define_HistogramModes_group */
|
||||||
|
|
||||||
|
|
||||||
|
/** @defgroup VL53L0_define_PowerModes_group List of available Power Modes
|
||||||
|
* List of available Power Modes
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
typedef uint8_t VL53L0_PowerModes;
|
||||||
|
|
||||||
|
#define VL53L0_POWERMODE_STANDBY_LEVEL1 ((VL53L0_PowerModes) 0)
|
||||||
|
/*!< Standby level 1 */
|
||||||
|
#define VL53L0_POWERMODE_STANDBY_LEVEL2 ((VL53L0_PowerModes) 1)
|
||||||
|
/*!< Standby level 2 */
|
||||||
|
#define VL53L0_POWERMODE_IDLE_LEVEL1 ((VL53L0_PowerModes) 2)
|
||||||
|
/*!< Idle level 1 */
|
||||||
|
#define VL53L0_POWERMODE_IDLE_LEVEL2 ((VL53L0_PowerModes) 3)
|
||||||
|
/*!< Idle level 2 */
|
||||||
|
|
||||||
|
/** @} VL53L0_define_PowerModes_group */
|
||||||
|
|
||||||
|
|
||||||
|
/** @brief Defines all parameters for the device
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
VL53L0_DeviceModes DeviceMode;
|
||||||
|
/*!< Defines type of measurement to be done for the next measure */
|
||||||
|
VL53L0_HistogramModes HistogramMode;
|
||||||
|
/*!< Defines type of histogram measurement to be done for the next
|
||||||
|
* measure
|
||||||
|
*/
|
||||||
|
uint32_t MeasurementTimingBudgetMicroSeconds;
|
||||||
|
/*!< Defines the allowed total time for a single measurement */
|
||||||
|
uint32_t InterMeasurementPeriodMilliSeconds;
|
||||||
|
/*!< Defines time between two consecutive measurements (between two
|
||||||
|
* measurement starts). If set to 0 means back-to-back mode
|
||||||
|
*/
|
||||||
|
uint8_t XTalkCompensationEnable;
|
||||||
|
/*!< Tells if Crosstalk compensation shall be enable or not */
|
||||||
|
uint16_t XTalkCompensationRangeMilliMeter;
|
||||||
|
/*!< CrossTalk compensation range in millimeter */
|
||||||
|
FixPoint1616_t XTalkCompensationRateMegaCps;
|
||||||
|
/*!< CrossTalk compensation rate in Mega counts per seconds.
|
||||||
|
* Expressed in 16.16 fixed point format.
|
||||||
|
*/
|
||||||
|
int32_t RangeOffsetMicroMeters;
|
||||||
|
/*!< Range offset adjustment (mm). */
|
||||||
|
|
||||||
|
uint8_t LimitChecksEnable[VL53L0_CHECKENABLE_NUMBER_OF_CHECKS];
|
||||||
|
/*!< This Array store all the Limit Check enable for this device. */
|
||||||
|
uint8_t LimitChecksStatus[VL53L0_CHECKENABLE_NUMBER_OF_CHECKS];
|
||||||
|
/*!< This Array store all the Status of the check linked to last
|
||||||
|
* measurement.
|
||||||
|
*/
|
||||||
|
FixPoint1616_t LimitChecksValue[VL53L0_CHECKENABLE_NUMBER_OF_CHECKS];
|
||||||
|
/*!< This Array store all the Limit Check value for this device */
|
||||||
|
|
||||||
|
uint8_t WrapAroundCheckEnable;
|
||||||
|
/*!< Tells if Wrap Around Check shall be enable or not */
|
||||||
|
} VL53L0_DeviceParameters_t;
|
||||||
|
|
||||||
|
|
||||||
|
/** @defgroup VL53L0_define_State_group Defines the current status of the device
|
||||||
|
* Defines the current status of the device
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
typedef uint8_t VL53L0_State;
|
||||||
|
|
||||||
|
#define VL53L0_STATE_POWERDOWN ((VL53L0_State) 0)
|
||||||
|
/*!< Device is in HW reset */
|
||||||
|
#define VL53L0_STATE_WAIT_STATICINIT ((VL53L0_State) 1)
|
||||||
|
/*!< Device is initialized and wait for static initialization */
|
||||||
|
#define VL53L0_STATE_STANDBY ((VL53L0_State) 2)
|
||||||
|
/*!< Device is in Low power Standby mode */
|
||||||
|
#define VL53L0_STATE_IDLE ((VL53L0_State) 3)
|
||||||
|
/*!< Device has been initialized and ready to do measurements */
|
||||||
|
#define VL53L0_STATE_RUNNING ((VL53L0_State) 4)
|
||||||
|
/*!< Device is performing measurement */
|
||||||
|
#define VL53L0_STATE_UNKNOWN ((VL53L0_State) 98)
|
||||||
|
/*!< Device is in unknown state and need to be rebooted */
|
||||||
|
#define VL53L0_STATE_ERROR ((VL53L0_State) 99)
|
||||||
|
/*!< Device is in error state and need to be rebooted */
|
||||||
|
|
||||||
|
/** @} VL53L0_define_State_group */
|
||||||
|
|
||||||
|
|
||||||
|
/** @brief Structure containing the Dmax computation parameters and data
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
int32_t AmbTuningWindowFactor_K;
|
||||||
|
/*!< internal algo tuning (*1000) */
|
||||||
|
int32_t RetSignalAt0mm;
|
||||||
|
/*!< intermediate dmax computation value caching */
|
||||||
|
} VL53L0_DMaxData_t;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @struct VL53L0_RangeData_t
|
||||||
|
* @brief Range measurement data.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint32_t TimeStamp; /*!< 32-bit time stamp. */
|
||||||
|
uint32_t MeasurementTimeUsec;
|
||||||
|
/*!< Give the Measurement time needed by the device to do the
|
||||||
|
* measurement.
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
uint16_t RangeMilliMeter; /*!< range distance in millimeter. */
|
||||||
|
|
||||||
|
uint16_t RangeDMaxMilliMeter;
|
||||||
|
/*!< Tells what is the maximum detection distance of the device
|
||||||
|
* in current setup and environment conditions (Filled when
|
||||||
|
* applicable)
|
||||||
|
*/
|
||||||
|
|
||||||
|
FixPoint1616_t SignalRateRtnMegaCps;
|
||||||
|
/*!< Return signal rate (MCPS)\n these is a 16.16 fix point
|
||||||
|
* value, which is effectively a measure of target
|
||||||
|
* reflectance.
|
||||||
|
*/
|
||||||
|
FixPoint1616_t AmbientRateRtnMegaCps;
|
||||||
|
/*!< Return ambient rate (MCPS)\n these is a 16.16 fix point
|
||||||
|
* value, which is effectively a measure of the ambien
|
||||||
|
* t light.
|
||||||
|
*/
|
||||||
|
|
||||||
|
uint16_t EffectiveSpadRtnCount;
|
||||||
|
/*!< Return the effective SPAD count for the return signal.
|
||||||
|
* To obtain Real value it should be divided by 256
|
||||||
|
*/
|
||||||
|
|
||||||
|
uint8_t ZoneId;
|
||||||
|
/*!< Denotes which zone and range scheduler stage the range
|
||||||
|
* data relates to.
|
||||||
|
*/
|
||||||
|
uint8_t RangeFractionalPart;
|
||||||
|
/*!< Fractional part of range distance. Final value is a
|
||||||
|
* FixPoint168 value.
|
||||||
|
*/
|
||||||
|
uint8_t RangeStatus;
|
||||||
|
/*!< Range Status for the current measurement. This is device
|
||||||
|
* dependent. Value = 0 means value is valid.
|
||||||
|
* See \ref RangeStatusPage
|
||||||
|
*/
|
||||||
|
} VL53L0_RangingMeasurementData_t;
|
||||||
|
|
||||||
|
|
||||||
|
#define VL53L0_HISTOGRAM_BUFFER_SIZE 24
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @struct VL53L0_HistogramData_t
|
||||||
|
* @brief Histogram measurement data.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
/* Histogram Measurement data */
|
||||||
|
uint32_t HistogramData[VL53L0_HISTOGRAM_BUFFER_SIZE];
|
||||||
|
/*!< Histogram data */
|
||||||
|
/*!< Indicate the types of histogram data :
|
||||||
|
*Return only, Reference only, both Return and Reference
|
||||||
|
*/
|
||||||
|
uint8_t HistogramType;
|
||||||
|
uint8_t FirstBin; /*!< First Bin value */
|
||||||
|
uint8_t BufferSize; /*!< Buffer Size - Set by the user.*/
|
||||||
|
uint8_t NumberOfBins;
|
||||||
|
/*!< Number of bins filled by the histogram measurement */
|
||||||
|
|
||||||
|
VL53L0_DeviceError ErrorStatus;
|
||||||
|
/*!< Error status of the current measurement. \n
|
||||||
|
* see @a ::VL53L0_DeviceError @a VL53L0_GetStatusErrorString()
|
||||||
|
*/
|
||||||
|
} VL53L0_HistogramMeasurementData_t;
|
||||||
|
|
||||||
|
#define VL53L0_REF_SPAD_BUFFER_SIZE 6
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @struct VL53L0_SpadData_t
|
||||||
|
* @brief Spad Configuration Data.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t RefSpadEnables[VL53L0_REF_SPAD_BUFFER_SIZE];
|
||||||
|
/*!< Reference Spad Enables */
|
||||||
|
uint8_t RefGoodSpadMap[VL53L0_REF_SPAD_BUFFER_SIZE];
|
||||||
|
/*!< Reference Spad Good Spad Map */
|
||||||
|
} VL53L0_SpadData_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
FixPoint1616_t OscFrequencyMHz; /* Frequency used */
|
||||||
|
|
||||||
|
uint16_t LastEncodedTimeout;
|
||||||
|
/* last encoded Time out used for timing budget*/
|
||||||
|
|
||||||
|
VL53L0_GpioFunctionality Pin0GpioFunctionality;
|
||||||
|
/* store the functionality of the GPIO: pin0 */
|
||||||
|
|
||||||
|
uint32_t FinalRangeTimeoutMicroSecs;
|
||||||
|
/*!< Execution time of the final range*/
|
||||||
|
uint8_t FinalRangeVcselPulsePeriod;
|
||||||
|
/*!< Vcsel pulse period (pll clocks) for the final range measurement*/
|
||||||
|
uint32_t PreRangeTimeoutMicroSecs;
|
||||||
|
/*!< Execution time of the final range*/
|
||||||
|
uint8_t PreRangeVcselPulsePeriod;
|
||||||
|
/*!< Vcsel pulse period (pll clocks) for the pre-range measurement*/
|
||||||
|
|
||||||
|
uint16_t SigmaEstRefArray;
|
||||||
|
/*!< Reference array sigma value in 1/100th of [mm] e.g. 100 = 1mm */
|
||||||
|
uint16_t SigmaEstEffPulseWidth;
|
||||||
|
/*!< Effective Pulse width for sigma estimate in 1/100th
|
||||||
|
* of ns e.g. 900 = 9.0ns
|
||||||
|
*/
|
||||||
|
uint16_t SigmaEstEffAmbWidth;
|
||||||
|
/*!< Effective Ambient width for sigma estimate in 1/100th of ns
|
||||||
|
* e.g. 500 = 5.0ns
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
/* Indicate if read from device has been done (==1) or not (==0) */
|
||||||
|
uint8_t ReadDataFromDeviceDone;
|
||||||
|
uint8_t ModuleId; /* Module ID */
|
||||||
|
uint8_t Revision; /* test Revision */
|
||||||
|
char ProductId[VL53L0_MAX_STRING_LENGTH];
|
||||||
|
/* Product Identifier String */
|
||||||
|
uint8_t ReferenceSpadCount; /* used for ref spad management */
|
||||||
|
uint8_t ReferenceSpadType; /* used for ref spad management */
|
||||||
|
uint8_t RefSpadsInitialised; /* reports if ref spads are initialised. */
|
||||||
|
uint32_t PartUIDUpper; /*!< Unique Part ID Upper */
|
||||||
|
uint32_t PartUIDLower; /*!< Unique Part ID Lower */
|
||||||
|
/*!< Peek Signal rate at 400 mm*/
|
||||||
|
FixPoint1616_t SignalRateMeasFixed400mm;
|
||||||
|
|
||||||
|
} VL53L0_DeviceSpecificParameters_t;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @struct VL53L0_DevData_t
|
||||||
|
*
|
||||||
|
* @brief VL53L0 PAL device ST private data structure \n
|
||||||
|
* End user should never access any of these field directly
|
||||||
|
*
|
||||||
|
* These must never access directly but only via macro
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
VL53L0_DMaxData_t DMaxData;
|
||||||
|
/*!< Dmax Data */
|
||||||
|
int32_t Part2PartOffsetNVMMicroMeter;
|
||||||
|
/*!< backed up NVM value */
|
||||||
|
int32_t Part2PartOffsetAdjustmentNVMMicroMeter;
|
||||||
|
/*!< backed up NVM value representing additional offset adjustment */
|
||||||
|
VL53L0_DeviceParameters_t CurrentParameters;
|
||||||
|
/*!< Current Device Parameter */
|
||||||
|
VL53L0_RangingMeasurementData_t LastRangeMeasure;
|
||||||
|
/*!< Ranging Data */
|
||||||
|
VL53L0_HistogramMeasurementData_t LastHistogramMeasure;
|
||||||
|
/*!< Histogram Data */
|
||||||
|
VL53L0_DeviceSpecificParameters_t DeviceSpecificParameters;
|
||||||
|
/*!< Parameters specific to the device */
|
||||||
|
VL53L0_SpadData_t SpadData;
|
||||||
|
/*!< Spad Data */
|
||||||
|
uint8_t SequenceConfig;
|
||||||
|
/*!< Internal value for the sequence config */
|
||||||
|
uint8_t RangeFractionalEnable;
|
||||||
|
/*!< Enable/Disable fractional part of ranging data */
|
||||||
|
VL53L0_State PalState;
|
||||||
|
/*!< Current state of the PAL for this device */
|
||||||
|
VL53L0_PowerModes PowerMode;
|
||||||
|
/*!< Current Power Mode */
|
||||||
|
uint16_t SigmaEstRefArray;
|
||||||
|
/*!< Reference array sigma value in 1/100th of [mm] e.g. 100 = 1mm */
|
||||||
|
uint16_t SigmaEstEffPulseWidth;
|
||||||
|
/*!< Effective Pulse width for sigma estimate in 1/100th
|
||||||
|
* of ns e.g. 900 = 9.0ns
|
||||||
|
*/
|
||||||
|
uint16_t SigmaEstEffAmbWidth;
|
||||||
|
/*!< Effective Ambient width for sigma estimate in 1/100th of ns
|
||||||
|
* e.g. 500 = 5.0ns
|
||||||
|
*/
|
||||||
|
uint8_t StopVariable;
|
||||||
|
/*!< StopVariable used during the stop sequence */
|
||||||
|
uint16_t targetRefRate;
|
||||||
|
/*!< Target Ambient Rate for Ref spad management */
|
||||||
|
FixPoint1616_t SigmaEstimate;
|
||||||
|
/*!< Sigma Estimate - based on ambient & VCSEL rates and
|
||||||
|
* signal_total_events
|
||||||
|
*/
|
||||||
|
FixPoint1616_t SignalEstimate;
|
||||||
|
/*!< Signal Estimate - based on ambient & VCSEL rates and cross talk */
|
||||||
|
FixPoint1616_t LastSignalRefMcps;
|
||||||
|
/*!< Latest Signal ref in Mcps */
|
||||||
|
uint8_t *pTuningSettingsPointer;
|
||||||
|
/*!< Pointer for Tuning Settings table */
|
||||||
|
uint8_t UseInternalTuningSettings;
|
||||||
|
/*!< Indicate if we use Tuning Settings table */
|
||||||
|
uint16_t LinearityCorrectiveGain;
|
||||||
|
/*!< Linearity Corrective Gain value in x1000 */
|
||||||
|
uint16_t DmaxCalRangeMilliMeter;
|
||||||
|
/*!< Dmax Calibration Range millimeter */
|
||||||
|
FixPoint1616_t DmaxCalSignalRateRtnMegaCps;
|
||||||
|
/*!< Dmax Calibration Signal Rate Return MegaCps */
|
||||||
|
|
||||||
|
} VL53L0_DevData_t;
|
||||||
|
|
||||||
|
|
||||||
|
/** @defgroup VL53L0_define_InterruptPolarity_group Defines the Polarity
|
||||||
|
* of the Interrupt
|
||||||
|
* Defines the Polarity of the Interrupt
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
typedef uint8_t VL53L0_InterruptPolarity;
|
||||||
|
|
||||||
|
#define VL53L0_INTERRUPTPOLARITY_LOW ((VL53L0_InterruptPolarity) 0)
|
||||||
|
/*!< Set active low polarity best setup for falling edge. */
|
||||||
|
#define VL53L0_INTERRUPTPOLARITY_HIGH ((VL53L0_InterruptPolarity) 1)
|
||||||
|
/*!< Set active high polarity best setup for rising edge. */
|
||||||
|
|
||||||
|
/** @} VL53L0_define_InterruptPolarity_group */
|
||||||
|
|
||||||
|
|
||||||
|
/** @defgroup VL53L0_define_VcselPeriod_group Vcsel Period Defines
|
||||||
|
* Defines the range measurement for which to access the vcsel period.
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
typedef uint8_t VL53L0_VcselPeriod;
|
||||||
|
|
||||||
|
#define VL53L0_VCSEL_PERIOD_PRE_RANGE ((VL53L0_VcselPeriod) 0)
|
||||||
|
/*!<Identifies the pre-range vcsel period. */
|
||||||
|
#define VL53L0_VCSEL_PERIOD_FINAL_RANGE ((VL53L0_VcselPeriod) 1)
|
||||||
|
/*!<Identifies the final range vcsel period. */
|
||||||
|
|
||||||
|
/** @} VL53L0_define_VcselPeriod_group */
|
||||||
|
|
||||||
|
/** @defgroup VL53L0_define_SchedulerSequence_group Defines the steps
|
||||||
|
* carried out by the scheduler during a range measurement.
|
||||||
|
* @{
|
||||||
|
* Defines the states of all the steps in the scheduler
|
||||||
|
* i.e. enabled/disabled.
|
||||||
|
*/
|
||||||
|
typedef struct {
|
||||||
|
uint8_t TccOn; /*!<Reports if Target Centre Check On */
|
||||||
|
uint8_t MsrcOn; /*!<Reports if MSRC On */
|
||||||
|
uint8_t DssOn; /*!<Reports if DSS On */
|
||||||
|
uint8_t PreRangeOn; /*!<Reports if Pre-Range On */
|
||||||
|
uint8_t FinalRangeOn; /*!<Reports if Final-Range On */
|
||||||
|
} VL53L0_SchedulerSequenceSteps_t;
|
||||||
|
|
||||||
|
/** @} VL53L0_define_SchedulerSequence_group */
|
||||||
|
|
||||||
|
/** @defgroup VL53L0_define_SequenceStepId_group Defines the Polarity
|
||||||
|
* of the Interrupt
|
||||||
|
* Defines the the sequence steps performed during ranging..
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
typedef uint8_t VL53L0_SequenceStepId;
|
||||||
|
|
||||||
|
#define VL53L0_SEQUENCESTEP_TCC ((VL53L0_VcselPeriod) 0)
|
||||||
|
/*!<Target CentreCheck identifier. */
|
||||||
|
#define VL53L0_SEQUENCESTEP_DSS ((VL53L0_VcselPeriod) 1)
|
||||||
|
/*!<Dynamic Spad Selection function Identifier. */
|
||||||
|
#define VL53L0_SEQUENCESTEP_MSRC ((VL53L0_VcselPeriod) 2)
|
||||||
|
/*!<Minimum Signal Rate Check function Identifier. */
|
||||||
|
#define VL53L0_SEQUENCESTEP_PRE_RANGE ((VL53L0_VcselPeriod) 3)
|
||||||
|
/*!<Pre-Range check Identifier. */
|
||||||
|
#define VL53L0_SEQUENCESTEP_FINAL_RANGE ((VL53L0_VcselPeriod) 4)
|
||||||
|
/*!<Final Range Check Identifier. */
|
||||||
|
|
||||||
|
#define VL53L0_SEQUENCESTEP_NUMBER_OF_CHECKS 5
|
||||||
|
/*!<Number of Sequence Step Managed by the API. */
|
||||||
|
|
||||||
|
/** @} VL53L0_define_SequenceStepId_group */
|
||||||
|
|
||||||
|
|
||||||
|
/* MACRO Definitions */
|
||||||
|
/** @defgroup VL53L0_define_GeneralMacro_group General Macro Defines
|
||||||
|
* General Macro Defines
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Defines */
|
||||||
|
#define VL53L0_SETPARAMETERFIELD(Dev, field, value) \
|
||||||
|
PALDevDataSet(Dev, CurrentParameters.field, value)
|
||||||
|
|
||||||
|
#define VL53L0_GETPARAMETERFIELD(Dev, field, variable) \
|
||||||
|
(variable = ((PALDevDataGet(Dev, CurrentParameters)).field))
|
||||||
|
|
||||||
|
|
||||||
|
#define VL53L0_SETARRAYPARAMETERFIELD(Dev, field, index, value) \
|
||||||
|
PALDevDataSet(Dev, CurrentParameters.field[index], value)
|
||||||
|
|
||||||
|
#define VL53L0_GETARRAYPARAMETERFIELD(Dev, field, index, variable) \
|
||||||
|
(variable = (PALDevDataGet(Dev, CurrentParameters)).field[index])
|
||||||
|
|
||||||
|
|
||||||
|
#define VL53L0_SETDEVICESPECIFICPARAMETER(Dev, field, value) \
|
||||||
|
PALDevDataSet(Dev, DeviceSpecificParameters.field, value)
|
||||||
|
|
||||||
|
#define VL53L0_GETDEVICESPECIFICPARAMETER(Dev, field) \
|
||||||
|
PALDevDataGet(Dev, DeviceSpecificParameters).field
|
||||||
|
|
||||||
|
|
||||||
|
#define VL53L0_FIXPOINT1616TOFIXPOINT97(Value) \
|
||||||
|
(uint16_t)((Value>>9)&0xFFFF)
|
||||||
|
#define VL53L0_FIXPOINT97TOFIXPOINT1616(Value) \
|
||||||
|
(FixPoint1616_t)(Value<<9)
|
||||||
|
|
||||||
|
#define VL53L0_FIXPOINT1616TOFIXPOINT88(Value) \
|
||||||
|
(uint16_t)((Value>>8)&0xFFFF)
|
||||||
|
#define VL53L0_FIXPOINT88TOFIXPOINT1616(Value) \
|
||||||
|
(FixPoint1616_t)(Value<<8)
|
||||||
|
|
||||||
|
#define VL53L0_FIXPOINT1616TOFIXPOINT412(Value) \
|
||||||
|
(uint16_t)((Value>>4)&0xFFFF)
|
||||||
|
#define VL53L0_FIXPOINT412TOFIXPOINT1616(Value) \
|
||||||
|
(FixPoint1616_t)(Value<<4)
|
||||||
|
|
||||||
|
#define VL53L0_FIXPOINT1616TOFIXPOINT313(Value) \
|
||||||
|
(uint16_t)((Value>>3)&0xFFFF)
|
||||||
|
#define VL53L0_FIXPOINT313TOFIXPOINT1616(Value) \
|
||||||
|
(FixPoint1616_t)(Value<<3)
|
||||||
|
|
||||||
|
#define VL53L0_FIXPOINT1616TOFIXPOINT08(Value) \
|
||||||
|
(uint8_t)((Value>>8)&0x00FF)
|
||||||
|
#define VL53L0_FIXPOINT08TOFIXPOINT1616(Value) \
|
||||||
|
(FixPoint1616_t)(Value<<8)
|
||||||
|
|
||||||
|
#define VL53L0_FIXPOINT1616TOFIXPOINT53(Value) \
|
||||||
|
(uint8_t)((Value>>13)&0x00FF)
|
||||||
|
#define VL53L0_FIXPOINT53TOFIXPOINT1616(Value) \
|
||||||
|
(FixPoint1616_t)(Value<<13)
|
||||||
|
|
||||||
|
#define VL53L0_FIXPOINT1616TOFIXPOINT102(Value) \
|
||||||
|
(uint16_t)((Value>>14)&0x0FFF)
|
||||||
|
#define VL53L0_FIXPOINT102TOFIXPOINT1616(Value) \
|
||||||
|
(FixPoint1616_t)(Value<<12)
|
||||||
|
|
||||||
|
#define VL53L0_MAKEUINT16(lsb, msb) (uint16_t)((((uint16_t)msb)<<8) + \
|
||||||
|
(uint16_t)lsb)
|
||||||
|
|
||||||
|
/** @} VL53L0_define_GeneralMacro_group */
|
||||||
|
|
||||||
|
/** @} VL53L0_globaldefine_group */
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* _VL53L0_DEF_H_ */
|
261
drivers/input/misc/vl53L0/inc/vl53l0_device.h
Normal file
261
drivers/input/misc/vl53L0/inc/vl53l0_device.h
Normal file
|
@ -0,0 +1,261 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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.
|
||||||
|
*******************************************************************************/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Device specific defines. To be adapted by implementer for the targeted
|
||||||
|
* device.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef _VL53L0_DEVICE_H_
|
||||||
|
#define _VL53L0_DEVICE_H_
|
||||||
|
|
||||||
|
#include "vl53l0_types.h"
|
||||||
|
|
||||||
|
|
||||||
|
/** @defgroup VL53L0_DevSpecDefines_group VL53L0 cut1.1 Device Specific Defines
|
||||||
|
* @brief VL53L0 cut1.1 Device Specific Defines
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
/** @defgroup VL53L0_DeviceError_group Device Error
|
||||||
|
* @brief Device Error code
|
||||||
|
*
|
||||||
|
* This enum is Device specific it should be updated in the implementation
|
||||||
|
* Use @a VL53L0_GetStatusErrorString() to get the string.
|
||||||
|
* It is related to Status Register of the Device.
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
typedef uint8_t VL53L0_DeviceError;
|
||||||
|
|
||||||
|
#define VL53L0_DEVICEERROR_NONE ((VL53L0_DeviceError) 0)
|
||||||
|
/*!< 0 NoError */
|
||||||
|
#define VL53L0_DEVICEERROR_VCSELCONTINUITYTESTFAILURE ((VL53L0_DeviceError) 1)
|
||||||
|
#define VL53L0_DEVICEERROR_VCSELWATCHDOGTESTFAILURE ((VL53L0_DeviceError) 2)
|
||||||
|
#define VL53L0_DEVICEERROR_NOVHVVALUEFOUND ((VL53L0_DeviceError) 3)
|
||||||
|
#define VL53L0_DEVICEERROR_MSRCNOTARGET ((VL53L0_DeviceError) 4)
|
||||||
|
#define VL53L0_DEVICEERROR_SNRCHECK ((VL53L0_DeviceError) 5)
|
||||||
|
#define VL53L0_DEVICEERROR_RANGEPHASECHECK ((VL53L0_DeviceError) 6)
|
||||||
|
#define VL53L0_DEVICEERROR_SIGMATHRESHOLDCHECK ((VL53L0_DeviceError) 7)
|
||||||
|
#define VL53L0_DEVICEERROR_TCC ((VL53L0_DeviceError) 8)
|
||||||
|
#define VL53L0_DEVICEERROR_PHASECONSISTENCY ((VL53L0_DeviceError) 9)
|
||||||
|
#define VL53L0_DEVICEERROR_MINCLIP ((VL53L0_DeviceError) 10)
|
||||||
|
#define VL53L0_DEVICEERROR_RANGECOMPLETE ((VL53L0_DeviceError) 11)
|
||||||
|
#define VL53L0_DEVICEERROR_ALGOUNDERFLOW ((VL53L0_DeviceError) 12)
|
||||||
|
#define VL53L0_DEVICEERROR_ALGOOVERFLOW ((VL53L0_DeviceError) 13)
|
||||||
|
#define VL53L0_DEVICEERROR_RANGEIGNORETHRESHOLD ((VL53L0_DeviceError) 14)
|
||||||
|
|
||||||
|
/** @} end of VL53L0_DeviceError_group */
|
||||||
|
|
||||||
|
|
||||||
|
/** @defgroup VL53L0_CheckEnable_group Check Enable list
|
||||||
|
* @brief Check Enable code
|
||||||
|
*
|
||||||
|
* Define used to specify the LimitCheckId.
|
||||||
|
* Use @a VL53L0_GetLimitCheckInfo() to get the string.
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define VL53L0_CHECKENABLE_SIGMA_FINAL_RANGE 0
|
||||||
|
#define VL53L0_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE 1
|
||||||
|
#define VL53L0_CHECKENABLE_SIGNAL_REF_CLIP 2
|
||||||
|
#define VL53L0_CHECKENABLE_RANGE_IGNORE_THRESHOLD 3
|
||||||
|
#define VL53L0_CHECKENABLE_SIGNAL_RATE_MSRC 4
|
||||||
|
#define VL53L0_CHECKENABLE_SIGNAL_RATE_PRE_RANGE 5
|
||||||
|
|
||||||
|
#define VL53L0_CHECKENABLE_NUMBER_OF_CHECKS 6
|
||||||
|
|
||||||
|
/** @} end of VL53L0_CheckEnable_group */
|
||||||
|
|
||||||
|
|
||||||
|
/** @defgroup VL53L0_GpioFunctionality_group Gpio Functionality
|
||||||
|
* @brief Defines the different functionalities for the device GPIO(s)
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
typedef uint8_t VL53L0_GpioFunctionality;
|
||||||
|
|
||||||
|
#define VL53L0_GPIOFUNCTIONALITY_OFF \
|
||||||
|
((VL53L0_GpioFunctionality) 0) /*!< NO Interrupt */
|
||||||
|
#define VL53L0_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_LOW \
|
||||||
|
((VL53L0_GpioFunctionality) 1) /*!< Level Low (value < thresh_low) */
|
||||||
|
#define VL53L0_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_HIGH \
|
||||||
|
((VL53L0_GpioFunctionality) 2) /*!< Level High (value > thresh_high) */
|
||||||
|
#define VL53L0_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_OUT \
|
||||||
|
((VL53L0_GpioFunctionality) 3)
|
||||||
|
/*!< Out Of Window (value < thresh_low OR value > thresh_high) */
|
||||||
|
#define VL53L0_GPIOFUNCTIONALITY_NEW_MEASURE_READY \
|
||||||
|
((VL53L0_GpioFunctionality) 4) /*!< New Sample Ready */
|
||||||
|
|
||||||
|
/** @} end of VL53L0_GpioFunctionality_group */
|
||||||
|
|
||||||
|
|
||||||
|
/* Device register map */
|
||||||
|
|
||||||
|
/** @defgroup VL53L0_DefineRegisters_group Define Registers
|
||||||
|
* @brief List of all the defined registers
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
#define VL53L0_REG_SYSRANGE_START 0x000
|
||||||
|
/** mask existing bit in #VL53L0_REG_SYSRANGE_START*/
|
||||||
|
#define VL53L0_REG_SYSRANGE_MODE_MASK 0x0F
|
||||||
|
/** bit 0 in #VL53L0_REG_SYSRANGE_START write 1 toggle state in
|
||||||
|
* continuous mode and arm next shot in single shot mode
|
||||||
|
*/
|
||||||
|
#define VL53L0_REG_SYSRANGE_MODE_START_STOP 0x01
|
||||||
|
/** bit 1 write 0 in #VL53L0_REG_SYSRANGE_START set single shot mode */
|
||||||
|
#define VL53L0_REG_SYSRANGE_MODE_SINGLESHOT 0x00
|
||||||
|
/** bit 1 write 1 in #VL53L0_REG_SYSRANGE_START set back-to-back
|
||||||
|
* operation mode
|
||||||
|
*/
|
||||||
|
#define VL53L0_REG_SYSRANGE_MODE_BACKTOBACK 0x02
|
||||||
|
/** bit 2 write 1 in #VL53L0_REG_SYSRANGE_START set timed operation
|
||||||
|
* mode
|
||||||
|
*/
|
||||||
|
#define VL53L0_REG_SYSRANGE_MODE_TIMED 0x04
|
||||||
|
/** bit 3 write 1 in #VL53L0_REG_SYSRANGE_START set histogram operation
|
||||||
|
* mode
|
||||||
|
*/
|
||||||
|
#define VL53L0_REG_SYSRANGE_MODE_HISTOGRAM 0x08
|
||||||
|
|
||||||
|
|
||||||
|
#define VL53L0_REG_SYSTEM_THRESH_HIGH 0x000C
|
||||||
|
#define VL53L0_REG_SYSTEM_THRESH_LOW 0x000E
|
||||||
|
|
||||||
|
|
||||||
|
#define VL53L0_REG_SYSTEM_SEQUENCE_CONFIG 0x0001
|
||||||
|
#define VL53L0_REG_SYSTEM_RANGE_CONFIG 0x0009
|
||||||
|
#define VL53L0_REG_SYSTEM_INTERMEASUREMENT_PERIOD 0x0004
|
||||||
|
|
||||||
|
|
||||||
|
#define VL53L0_REG_SYSTEM_INTERRUPT_CONFIG_GPIO 0x000A
|
||||||
|
#define VL53L0_REG_SYSTEM_INTERRUPT_GPIO_DISABLED 0x00
|
||||||
|
#define VL53L0_REG_SYSTEM_INTERRUPT_GPIO_LEVEL_LOW 0x01
|
||||||
|
#define VL53L0_REG_SYSTEM_INTERRUPT_GPIO_LEVEL_HIGH 0x02
|
||||||
|
#define VL53L0_REG_SYSTEM_INTERRUPT_GPIO_OUT_OF_WINDOW 0x03
|
||||||
|
#define VL53L0_REG_SYSTEM_INTERRUPT_GPIO_NEW_SAMPLE_READY 0x04
|
||||||
|
|
||||||
|
#define VL53L0_REG_GPIO_HV_MUX_ACTIVE_HIGH 0x0084
|
||||||
|
|
||||||
|
|
||||||
|
#define VL53L0_REG_SYSTEM_INTERRUPT_CLEAR 0x000B
|
||||||
|
|
||||||
|
/* Result registers */
|
||||||
|
#define VL53L0_REG_RESULT_INTERRUPT_STATUS 0x0013
|
||||||
|
#define VL53L0_REG_RESULT_RANGE_STATUS 0x0014
|
||||||
|
|
||||||
|
#define VL53L0_REG_RESULT_CORE_PAGE 1
|
||||||
|
#define VL53L0_REG_RESULT_CORE_AMBIENT_WINDOW_EVENTS_RTN 0x00BC
|
||||||
|
#define VL53L0_REG_RESULT_CORE_RANGING_TOTAL_EVENTS_RTN 0x00C0
|
||||||
|
#define VL53L0_REG_RESULT_CORE_AMBIENT_WINDOW_EVENTS_REF 0x00D0
|
||||||
|
#define VL53L0_REG_RESULT_CORE_RANGING_TOTAL_EVENTS_REF 0x00D4
|
||||||
|
#define VL53L0_REG_RESULT_PEAK_SIGNAL_RATE_REF 0x00B6
|
||||||
|
|
||||||
|
/* Algo register */
|
||||||
|
|
||||||
|
#define VL53L0_REG_ALGO_PART_TO_PART_RANGE_OFFSET_MM 0x0028
|
||||||
|
|
||||||
|
#define VL53L0_REG_I2C_SLAVE_DEVICE_ADDRESS 0x008a
|
||||||
|
|
||||||
|
/* Check Limit registers */
|
||||||
|
#define VL53L0_REG_MSRC_CONFIG_CONTROL 0x0060
|
||||||
|
|
||||||
|
#define VL53L0_REG_PRE_RANGE_CONFIG_MIN_SNR 0X0027
|
||||||
|
#define VL53L0_REG_PRE_RANGE_CONFIG_VALID_PHASE_LOW 0x0056
|
||||||
|
#define VL53L0_REG_PRE_RANGE_CONFIG_VALID_PHASE_HIGH 0x0057
|
||||||
|
#define VL53L0_REG_PRE_RANGE_MIN_COUNT_RATE_RTN_LIMIT 0x0064
|
||||||
|
|
||||||
|
#define VL53L0_REG_FINAL_RANGE_CONFIG_MIN_SNR 0X0067
|
||||||
|
#define VL53L0_REG_FINAL_RANGE_CONFIG_VALID_PHASE_LOW 0x0047
|
||||||
|
#define VL53L0_REG_FINAL_RANGE_CONFIG_VALID_PHASE_HIGH 0x0048
|
||||||
|
#define VL53L0_REG_FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT 0x0044
|
||||||
|
|
||||||
|
|
||||||
|
#define VL53L0_REG_PRE_RANGE_CONFIG_SIGMA_THRESH_HI 0X0061
|
||||||
|
#define VL53L0_REG_PRE_RANGE_CONFIG_SIGMA_THRESH_LO 0X0062
|
||||||
|
|
||||||
|
/* PRE RANGE registers */
|
||||||
|
#define VL53L0_REG_PRE_RANGE_CONFIG_VCSEL_PERIOD 0x0050
|
||||||
|
#define VL53L0_REG_PRE_RANGE_CONFIG_TIMEOUT_MACROP_HI 0x0051
|
||||||
|
#define VL53L0_REG_PRE_RANGE_CONFIG_TIMEOUT_MACROP_LO 0x0052
|
||||||
|
|
||||||
|
#define VL53L0_REG_SYSTEM_HISTOGRAM_BIN 0x0081
|
||||||
|
#define VL53L0_REG_HISTOGRAM_CONFIG_INITIAL_PHASE_SELECT 0x0033
|
||||||
|
#define VL53L0_REG_HISTOGRAM_CONFIG_READOUT_CTRL 0x0055
|
||||||
|
|
||||||
|
#define VL53L0_REG_FINAL_RANGE_CONFIG_VCSEL_PERIOD 0x0070
|
||||||
|
#define VL53L0_REG_FINAL_RANGE_CONFIG_TIMEOUT_MACROP_HI 0x0071
|
||||||
|
#define VL53L0_REG_FINAL_RANGE_CONFIG_TIMEOUT_MACROP_LO 0x0072
|
||||||
|
#define VL53L0_REG_CROSSTALK_COMPENSATION_PEAK_RATE_MCPS 0x0020
|
||||||
|
|
||||||
|
#define VL53L0_REG_MSRC_CONFIG_TIMEOUT_MACROP 0x0046
|
||||||
|
|
||||||
|
|
||||||
|
#define VL53L0_REG_SOFT_RESET_GO2_SOFT_RESET_N 0x00bf
|
||||||
|
#define VL53L0_REG_IDENTIFICATION_MODEL_ID 0x00c0
|
||||||
|
#define VL53L0_REG_IDENTIFICATION_REVISION_ID 0x00c2
|
||||||
|
|
||||||
|
#define VL53L0_REG_OSC_CALIBRATE_VAL 0x00f8
|
||||||
|
|
||||||
|
|
||||||
|
#define VL53L0_SIGMA_ESTIMATE_MAX_VALUE 65535
|
||||||
|
/* equivalent to a range sigma of 655.35mm */
|
||||||
|
|
||||||
|
#define VL53L0_REG_GLOBAL_CONFIG_VCSEL_WIDTH 0x032
|
||||||
|
#define VL53L0_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_0 0x0B0
|
||||||
|
#define VL53L0_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_1 0x0B1
|
||||||
|
#define VL53L0_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_2 0x0B2
|
||||||
|
#define VL53L0_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_3 0x0B3
|
||||||
|
#define VL53L0_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_4 0x0B4
|
||||||
|
#define VL53L0_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_5 0x0B5
|
||||||
|
|
||||||
|
#define VL53L0_REG_GLOBAL_CONFIG_REF_EN_START_SELECT 0xB6
|
||||||
|
#define VL53L0_REG_DYNAMIC_SPAD_NUM_REQUESTED_REF_SPAD 0x4E /* 0x14E */
|
||||||
|
#define VL53L0_REG_DYNAMIC_SPAD_REF_EN_START_OFFSET 0x4F /* 0x14F */
|
||||||
|
#define VL53L0_REG_POWER_MANAGEMENT_GO1_POWER_FORCE 0x80
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Speed of light in um per 1E-10 Seconds
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define VL53L0_SPEED_OF_LIGHT_IN_AIR 2997
|
||||||
|
|
||||||
|
#define VL53L0_REG_VHV_CONFIG_PAD_SCL_SDA__EXTSUP_HV 0x0089
|
||||||
|
|
||||||
|
#define VL53L0_REG_ALGO_PHASECAL_LIM 0x0030 /* 0x130 */
|
||||||
|
#define VL53L0_REG_ALGO_PHASECAL_CONFIG_TIMEOUT 0x0030
|
||||||
|
|
||||||
|
/** @} VL53L0_DefineRegisters_group */
|
||||||
|
|
||||||
|
/** @} VL53L0_DevSpecDefines_group */
|
||||||
|
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* _VL53L0_DEVICE_H_ */
|
||||||
|
|
||||||
|
|
402
drivers/input/misc/vl53L0/inc/vl53l0_i2c_platform.h
Normal file
402
drivers/input/misc/vl53L0/inc/vl53l0_i2c_platform.h
Normal file
|
@ -0,0 +1,402 @@
|
||||||
|
/*
|
||||||
|
* vl53l0_i2c_platform.h - Linux kernel modules for STM VL53L0 FlightSense TOF
|
||||||
|
* sensor
|
||||||
|
*
|
||||||
|
* Copyright (C) 2016 STMicroelectronics Imaging Division.
|
||||||
|
*
|
||||||
|
* This program is free software; you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation; either version 2 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file VL53L0_i2c_platform.h
|
||||||
|
* @brief Function prototype definitions for EWOK Platform layer.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef _VL53L0_I2C_PLATFORM_H_
|
||||||
|
#define _VL53L0_I2C_PLATFORM_H_
|
||||||
|
|
||||||
|
#include "vl53l0_def.h"
|
||||||
|
|
||||||
|
|
||||||
|
/** Maximum buffer size to be used in i2c */
|
||||||
|
#define VL53L0_MAX_I2C_XFER_SIZE 64
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Typedef defining .\n
|
||||||
|
* The developer should modify this to suit the platform being deployed.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Typedef defining 8 bit unsigned char type.\n
|
||||||
|
* The developer should modify this to suit the platform being deployed.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef bool_t
|
||||||
|
typedef unsigned char bool_t;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#define I2C 0x01
|
||||||
|
#define SPI 0x00
|
||||||
|
|
||||||
|
#define COMMS_BUFFER_SIZE 64
|
||||||
|
/*MUST be the same size as the SV task buffer */
|
||||||
|
|
||||||
|
#define BYTES_PER_WORD 2
|
||||||
|
#define BYTES_PER_DWORD 4
|
||||||
|
|
||||||
|
#define VL53L0_MAX_STRING_LENGTH_PLT 256
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Initialise platform comms.
|
||||||
|
*
|
||||||
|
* @param comms_type - selects between I2C and SPI
|
||||||
|
* @param comms_speed_khz - unsigned short containing the I2C speed in kHz
|
||||||
|
*
|
||||||
|
* @return status - status 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_comms_initialise(uint8_t comms_type,
|
||||||
|
uint16_t comms_speed_khz);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Close platform comms.
|
||||||
|
*
|
||||||
|
* @return status - status 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_comms_close(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Cycle Power to Device
|
||||||
|
*
|
||||||
|
* @return status - status 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_cycle_power(void);
|
||||||
|
|
||||||
|
int32_t VL53L0_set_page(VL53L0_DEV dev, uint8_t page_data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Writes the supplied byte buffer to the device
|
||||||
|
*
|
||||||
|
* Wrapper for SystemVerilog Write Multi task
|
||||||
|
*
|
||||||
|
* @code
|
||||||
|
*
|
||||||
|
* Example:
|
||||||
|
*
|
||||||
|
* uint8_t *spad_enables;
|
||||||
|
*
|
||||||
|
* int status = VL53L0_write_multi(RET_SPAD_EN_0, spad_enables, 36);
|
||||||
|
*
|
||||||
|
* @endcode
|
||||||
|
*
|
||||||
|
* @param address - uint8_t device address value
|
||||||
|
* @param index - uint8_t register index value
|
||||||
|
* @param pdata - pointer to uint8_t buffer containing the data to be written
|
||||||
|
* @param count - number of bytes in the supplied byte buffer
|
||||||
|
*
|
||||||
|
* @return status - SystemVerilog status 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_write_multi(VL53L0_DEV dev, uint8_t index, uint8_t *pdata,
|
||||||
|
int32_t count);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Reads the requested number of bytes from the device
|
||||||
|
*
|
||||||
|
* Wrapper for SystemVerilog Read Multi task
|
||||||
|
*
|
||||||
|
* @code
|
||||||
|
*
|
||||||
|
* Example:
|
||||||
|
*
|
||||||
|
* uint8_t buffer[COMMS_BUFFER_SIZE];
|
||||||
|
*
|
||||||
|
* int status = status = VL53L0_read_multi(DEVICE_ID, buffer, 2)
|
||||||
|
*
|
||||||
|
* @endcode
|
||||||
|
*
|
||||||
|
* @param address - uint8_t device address value
|
||||||
|
* @param index - uint8_t register index value
|
||||||
|
* @param pdata - pointer to the uint8_t buffer to store read data
|
||||||
|
* @param count - number of uint8_t's to read
|
||||||
|
*
|
||||||
|
* @return status - SystemVerilog status 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_read_multi(VL53L0_DEV dev, uint8_t index, uint8_t *pdata,
|
||||||
|
int32_t count);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Writes a single byte to the device
|
||||||
|
*
|
||||||
|
* Wrapper for SystemVerilog Write Byte task
|
||||||
|
*
|
||||||
|
* @code
|
||||||
|
*
|
||||||
|
* Example:
|
||||||
|
*
|
||||||
|
* uint8_t page_number = MAIN_SELECT_PAGE;
|
||||||
|
*
|
||||||
|
* int status = VL53L0_write_byte(PAGE_SELECT, page_number);
|
||||||
|
*
|
||||||
|
* @endcode
|
||||||
|
*
|
||||||
|
* @param address - uint8_t device address value
|
||||||
|
* @param index - uint8_t register index value
|
||||||
|
* @param data - uint8_t data value to write
|
||||||
|
*
|
||||||
|
* @return status - SystemVerilog status 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_write_byte(VL53L0_DEV dev, uint8_t index, uint8_t data);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Writes a single word (16-bit unsigned) to the device
|
||||||
|
*
|
||||||
|
* Manages the big-endian nature of the device (first byte written is the
|
||||||
|
* MS byte).
|
||||||
|
* Uses SystemVerilog Write Multi task.
|
||||||
|
*
|
||||||
|
* @code
|
||||||
|
*
|
||||||
|
* Example:
|
||||||
|
*
|
||||||
|
* uint16_t nvm_ctrl_pulse_width = 0x0004;
|
||||||
|
*
|
||||||
|
* int status = VL53L0_write_word(NVM_CTRL__PULSE_WIDTH_MSB,
|
||||||
|
* nvm_ctrl_pulse_width);
|
||||||
|
*
|
||||||
|
* @endcode
|
||||||
|
*
|
||||||
|
* @param address - uint8_t device address value
|
||||||
|
* @param index - uint8_t register index value
|
||||||
|
* @param data - uin16_t data value write
|
||||||
|
*
|
||||||
|
* @return status - SystemVerilog status 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_write_word(VL53L0_DEV dev, uint8_t index, uint16_t data);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Writes a single dword (32-bit unsigned) to the device
|
||||||
|
*
|
||||||
|
* Manages the big-endian nature of the device (first byte written is the
|
||||||
|
* MS byte).
|
||||||
|
* Uses SystemVerilog Write Multi task.
|
||||||
|
*
|
||||||
|
* @code
|
||||||
|
*
|
||||||
|
* Example:
|
||||||
|
*
|
||||||
|
* uint32_t nvm_data = 0x0004;
|
||||||
|
*
|
||||||
|
* int status = VL53L0_write_dword(NVM_CTRL__DATAIN_MMM, nvm_data);
|
||||||
|
*
|
||||||
|
* @endcode
|
||||||
|
*
|
||||||
|
* @param address - uint8_t device address value
|
||||||
|
* @param index - uint8_t register index value
|
||||||
|
* @param data - uint32_t data value to write
|
||||||
|
*
|
||||||
|
* @return status - SystemVerilog status 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_write_dword(VL53L0_DEV dev, uint8_t index, uint32_t data);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Reads a single byte from the device
|
||||||
|
*
|
||||||
|
* Uses SystemVerilog Read Byte task.
|
||||||
|
*
|
||||||
|
* @code
|
||||||
|
*
|
||||||
|
* Example:
|
||||||
|
*
|
||||||
|
* uint8_t device_status = 0;
|
||||||
|
*
|
||||||
|
* int status = VL53L0_read_byte(STATUS, &device_status);
|
||||||
|
*
|
||||||
|
* @endcode
|
||||||
|
*
|
||||||
|
* @param address - uint8_t device address value
|
||||||
|
* @param index - uint8_t register index value
|
||||||
|
* @param pdata - pointer to uint8_t data value
|
||||||
|
*
|
||||||
|
* @return status - SystemVerilog status 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_read_byte(VL53L0_DEV dev, uint8_t index, uint8_t *pdata);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Reads a single word (16-bit unsigned) from the device
|
||||||
|
*
|
||||||
|
* Manages the big-endian nature of the device (first byte read is the MS byte).
|
||||||
|
* Uses SystemVerilog Read Multi task.
|
||||||
|
*
|
||||||
|
* @code
|
||||||
|
*
|
||||||
|
* Example:
|
||||||
|
*
|
||||||
|
* uint16_t timeout = 0;
|
||||||
|
*
|
||||||
|
* int status = VL53L0_read_word(TIMEOUT_OVERALL_PERIODS_MSB, &timeout);
|
||||||
|
*
|
||||||
|
* @endcode
|
||||||
|
*
|
||||||
|
* @param address - uint8_t device address value
|
||||||
|
* @param index - uint8_t register index value
|
||||||
|
* @param pdata - pointer to uint16_t data value
|
||||||
|
*
|
||||||
|
* @return status - SystemVerilog status 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_read_word(VL53L0_DEV dev, uint8_t index, uint16_t *pdata);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Reads a single dword (32-bit unsigned) from the device
|
||||||
|
*
|
||||||
|
* Manages the big-endian nature of the device (first byte read is the MS byte).
|
||||||
|
* Uses SystemVerilog Read Multi task.
|
||||||
|
*
|
||||||
|
* @code
|
||||||
|
*
|
||||||
|
* Example:
|
||||||
|
*
|
||||||
|
* uint32_t range_1 = 0;
|
||||||
|
*
|
||||||
|
* int status = VL53L0_read_dword(RANGE_1_MMM, &range_1);
|
||||||
|
*
|
||||||
|
* @endcode
|
||||||
|
*
|
||||||
|
* @param address - uint8_t device address value
|
||||||
|
* @param index - uint8_t register index value
|
||||||
|
* @param pdata - pointer to uint32_t data value
|
||||||
|
*
|
||||||
|
* @return status - SystemVerilog status 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_read_dword(VL53L0_DEV dev, uint8_t index, uint32_t *pdata);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Implements a programmable wait in us
|
||||||
|
*
|
||||||
|
* Wrapper for SystemVerilog Wait in micro seconds task
|
||||||
|
*
|
||||||
|
* @param wait_us - integer wait in micro seconds
|
||||||
|
*
|
||||||
|
* @return status - SystemVerilog status 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_platform_wait_us(int32_t wait_us);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Implements a programmable wait in ms
|
||||||
|
*
|
||||||
|
* Wrapper for SystemVerilog Wait in milli seconds task
|
||||||
|
*
|
||||||
|
* @param wait_ms - integer wait in milli seconds
|
||||||
|
*
|
||||||
|
* @return status - SystemVerilog status 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_wait_ms(int32_t wait_ms);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Set GPIO value
|
||||||
|
*
|
||||||
|
* @param level - input level - either 0 or 1
|
||||||
|
*
|
||||||
|
* @return status - SystemVerilog status 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_set_gpio(uint8_t level);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get GPIO value
|
||||||
|
*
|
||||||
|
* @param plevel - uint8_t pointer to store GPIO level (0 or 1)
|
||||||
|
*
|
||||||
|
* @return status - SystemVerilog status 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_get_gpio(uint8_t *plevel);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Release force on GPIO
|
||||||
|
*
|
||||||
|
* @return status - SystemVerilog status 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_release_gpio(void);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get the frequency of the timer used for ranging results time stamps
|
||||||
|
*
|
||||||
|
* @param[out] ptimer_freq_hz : pointer for timer frequency
|
||||||
|
*
|
||||||
|
* @return status : 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_get_timer_frequency(int32_t *ptimer_freq_hz);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Get the timer value in units of timer_freq_hz
|
||||||
|
* (see VL53L0_get_timestamp_frequency())
|
||||||
|
*
|
||||||
|
* @param[out] ptimer_count : pointer for timer count value
|
||||||
|
*
|
||||||
|
* @return status : 0 = ok, 1 = error
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
int32_t VL53L0_get_timer_value(int32_t *ptimer_count);
|
||||||
|
int VL53L0_I2CWrite(VL53L0_DEV dev, uint8_t *buff, uint8_t len);
|
||||||
|
int VL53L0_I2CRead(VL53L0_DEV dev, uint8_t *buff, uint8_t len);
|
||||||
|
|
||||||
|
#endif /* _VL53L0_I2C_PLATFORM_H_ */
|
||||||
|
|
|
@ -0,0 +1,194 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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 _VL53L0_INTERRUPT_THRESHOLD_SETTINGS_H_
|
||||||
|
#define _VL53L0_INTERRUPT_THRESHOLD_SETTINGS_H_
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
uint8_t InterruptThresholdSettings[] = {
|
||||||
|
|
||||||
|
/* Start of Interrupt Threshold Settings */
|
||||||
|
0x1, 0xff, 0x00,
|
||||||
|
0x1, 0x80, 0x01,
|
||||||
|
0x1, 0xff, 0x01,
|
||||||
|
0x1, 0x00, 0x00,
|
||||||
|
0x1, 0xff, 0x01,
|
||||||
|
0x1, 0x4f, 0x02,
|
||||||
|
0x1, 0xFF, 0x0E,
|
||||||
|
0x1, 0x00, 0x03,
|
||||||
|
0x1, 0x01, 0x84,
|
||||||
|
0x1, 0x02, 0x0A,
|
||||||
|
0x1, 0x03, 0x03,
|
||||||
|
0x1, 0x04, 0x08,
|
||||||
|
0x1, 0x05, 0xC8,
|
||||||
|
0x1, 0x06, 0x03,
|
||||||
|
0x1, 0x07, 0x8D,
|
||||||
|
0x1, 0x08, 0x08,
|
||||||
|
0x1, 0x09, 0xC6,
|
||||||
|
0x1, 0x0A, 0x01,
|
||||||
|
0x1, 0x0B, 0x02,
|
||||||
|
0x1, 0x0C, 0x00,
|
||||||
|
0x1, 0x0D, 0xD5,
|
||||||
|
0x1, 0x0E, 0x18,
|
||||||
|
0x1, 0x0F, 0x12,
|
||||||
|
0x1, 0x10, 0x01,
|
||||||
|
0x1, 0x11, 0x82,
|
||||||
|
0x1, 0x12, 0x00,
|
||||||
|
0x1, 0x13, 0xD5,
|
||||||
|
0x1, 0x14, 0x18,
|
||||||
|
0x1, 0x15, 0x13,
|
||||||
|
0x1, 0x16, 0x03,
|
||||||
|
0x1, 0x17, 0x86,
|
||||||
|
0x1, 0x18, 0x0A,
|
||||||
|
0x1, 0x19, 0x09,
|
||||||
|
0x1, 0x1A, 0x08,
|
||||||
|
0x1, 0x1B, 0xC2,
|
||||||
|
0x1, 0x1C, 0x03,
|
||||||
|
0x1, 0x1D, 0x8F,
|
||||||
|
0x1, 0x1E, 0x0A,
|
||||||
|
0x1, 0x1F, 0x06,
|
||||||
|
0x1, 0x20, 0x01,
|
||||||
|
0x1, 0x21, 0x02,
|
||||||
|
0x1, 0x22, 0x00,
|
||||||
|
0x1, 0x23, 0xD5,
|
||||||
|
0x1, 0x24, 0x18,
|
||||||
|
0x1, 0x25, 0x22,
|
||||||
|
0x1, 0x26, 0x01,
|
||||||
|
0x1, 0x27, 0x82,
|
||||||
|
0x1, 0x28, 0x00,
|
||||||
|
0x1, 0x29, 0xD5,
|
||||||
|
0x1, 0x2A, 0x18,
|
||||||
|
0x1, 0x2B, 0x0B,
|
||||||
|
0x1, 0x2C, 0x28,
|
||||||
|
0x1, 0x2D, 0x78,
|
||||||
|
0x1, 0x2E, 0x28,
|
||||||
|
0x1, 0x2F, 0x91,
|
||||||
|
0x1, 0x30, 0x00,
|
||||||
|
0x1, 0x31, 0x0B,
|
||||||
|
0x1, 0x32, 0x00,
|
||||||
|
0x1, 0x33, 0x0B,
|
||||||
|
0x1, 0x34, 0x00,
|
||||||
|
0x1, 0x35, 0xA1,
|
||||||
|
0x1, 0x36, 0x00,
|
||||||
|
0x1, 0x37, 0xA0,
|
||||||
|
0x1, 0x38, 0x00,
|
||||||
|
0x1, 0x39, 0x04,
|
||||||
|
0x1, 0x3A, 0x28,
|
||||||
|
0x1, 0x3B, 0x30,
|
||||||
|
0x1, 0x3C, 0x0C,
|
||||||
|
0x1, 0x3D, 0x04,
|
||||||
|
0x1, 0x3E, 0x0F,
|
||||||
|
0x1, 0x3F, 0x79,
|
||||||
|
0x1, 0x40, 0x28,
|
||||||
|
0x1, 0x41, 0x1E,
|
||||||
|
0x1, 0x42, 0x2F,
|
||||||
|
0x1, 0x43, 0x87,
|
||||||
|
0x1, 0x44, 0x00,
|
||||||
|
0x1, 0x45, 0x0B,
|
||||||
|
0x1, 0x46, 0x00,
|
||||||
|
0x1, 0x47, 0x0B,
|
||||||
|
0x1, 0x48, 0x00,
|
||||||
|
0x1, 0x49, 0xA7,
|
||||||
|
0x1, 0x4A, 0x00,
|
||||||
|
0x1, 0x4B, 0xA6,
|
||||||
|
0x1, 0x4C, 0x00,
|
||||||
|
0x1, 0x4D, 0x04,
|
||||||
|
0x1, 0x4E, 0x01,
|
||||||
|
0x1, 0x4F, 0x00,
|
||||||
|
0x1, 0x50, 0x00,
|
||||||
|
0x1, 0x51, 0x80,
|
||||||
|
0x1, 0x52, 0x09,
|
||||||
|
0x1, 0x53, 0x08,
|
||||||
|
0x1, 0x54, 0x01,
|
||||||
|
0x1, 0x55, 0x00,
|
||||||
|
0x1, 0x56, 0x0F,
|
||||||
|
0x1, 0x57, 0x79,
|
||||||
|
0x1, 0x58, 0x09,
|
||||||
|
0x1, 0x59, 0x05,
|
||||||
|
0x1, 0x5A, 0x00,
|
||||||
|
0x1, 0x5B, 0x60,
|
||||||
|
0x1, 0x5C, 0x05,
|
||||||
|
0x1, 0x5D, 0xD1,
|
||||||
|
0x1, 0x5E, 0x0C,
|
||||||
|
0x1, 0x5F, 0x3C,
|
||||||
|
0x1, 0x60, 0x00,
|
||||||
|
0x1, 0x61, 0xD0,
|
||||||
|
0x1, 0x62, 0x0B,
|
||||||
|
0x1, 0x63, 0x03,
|
||||||
|
0x1, 0x64, 0x28,
|
||||||
|
0x1, 0x65, 0x10,
|
||||||
|
0x1, 0x66, 0x2A,
|
||||||
|
0x1, 0x67, 0x39,
|
||||||
|
0x1, 0x68, 0x0B,
|
||||||
|
0x1, 0x69, 0x02,
|
||||||
|
0x1, 0x6A, 0x28,
|
||||||
|
0x1, 0x6B, 0x10,
|
||||||
|
0x1, 0x6C, 0x2A,
|
||||||
|
0x1, 0x6D, 0x61,
|
||||||
|
0x1, 0x6E, 0x0C,
|
||||||
|
0x1, 0x6F, 0x00,
|
||||||
|
0x1, 0x70, 0x0F,
|
||||||
|
0x1, 0x71, 0x79,
|
||||||
|
0x1, 0x72, 0x00,
|
||||||
|
0x1, 0x73, 0x0B,
|
||||||
|
0x1, 0x74, 0x00,
|
||||||
|
0x1, 0x75, 0x0B,
|
||||||
|
0x1, 0x76, 0x00,
|
||||||
|
0x1, 0x77, 0xA1,
|
||||||
|
0x1, 0x78, 0x00,
|
||||||
|
0x1, 0x79, 0xA0,
|
||||||
|
0x1, 0x7A, 0x00,
|
||||||
|
0x1, 0x7B, 0x04,
|
||||||
|
0x1, 0xFF, 0x04,
|
||||||
|
0x1, 0x79, 0x1D,
|
||||||
|
0x1, 0x7B, 0x27,
|
||||||
|
0x1, 0x96, 0x0E,
|
||||||
|
0x1, 0x97, 0xFE,
|
||||||
|
0x1, 0x98, 0x03,
|
||||||
|
0x1, 0x99, 0xEF,
|
||||||
|
0x1, 0x9A, 0x02,
|
||||||
|
0x1, 0x9B, 0x44,
|
||||||
|
0x1, 0x73, 0x07,
|
||||||
|
0x1, 0x70, 0x01,
|
||||||
|
0x1, 0xff, 0x01,
|
||||||
|
0x1, 0x00, 0x01,
|
||||||
|
0x1, 0xff, 0x00,
|
||||||
|
0x00, 0x00, 0x00
|
||||||
|
};
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* _VL53L0_INTERRUPT_THRESHOLD_SETTINGS_H_ */
|
231
drivers/input/misc/vl53L0/inc/vl53l0_platform.h
Normal file
231
drivers/input/misc/vl53L0/inc/vl53l0_platform.h
Normal file
|
@ -0,0 +1,231 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2015, 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 _VL53L0_PLATFORM_H_
|
||||||
|
#define _VL53L0_PLATFORM_H_
|
||||||
|
|
||||||
|
#include <linux/delay.h>
|
||||||
|
#include "vl53l0_def.h"
|
||||||
|
#include "vl53l0_platform_log.h"
|
||||||
|
|
||||||
|
#include "stmvl53l0-i2c.h"
|
||||||
|
#include "stmvl53l0-cci.h"
|
||||||
|
#include "stmvl53l0.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file vl53l0_platform.h
|
||||||
|
*
|
||||||
|
* @brief All end user OS/platform/application porting
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @defgroup VL53L0_platform_group VL53L0 Platform Functions
|
||||||
|
* @brief VL53L0 Platform Functions
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @struct VL53L0_Dev_t
|
||||||
|
* @brief Generic PAL device type that does link between API and platform
|
||||||
|
* abstraction layer
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
typedef struct stmvl53l0_data *VL53L0_DEV;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @def PALDevDataGet
|
||||||
|
* @brief Get ST private structure @a VL53L0_DevData_t data access
|
||||||
|
*
|
||||||
|
* @param Dev Device Handle
|
||||||
|
* @param field ST structure field name
|
||||||
|
* It maybe used and as real data "ref" not just as "get" for sub-structure item
|
||||||
|
* like PALDevDataGet(FilterData.field)[i] or
|
||||||
|
* PALDevDataGet(FilterData.MeasurementIndex)++
|
||||||
|
*/
|
||||||
|
#define PALDevDataGet(Dev, field) (Dev->Data.field)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @def PALDevDataSet(Dev, field, data)
|
||||||
|
* @brief Set ST private structure @a VL53L0_DevData_t data field
|
||||||
|
* @param Dev Device Handle
|
||||||
|
* @param field ST structure field na*me
|
||||||
|
* @param data Data to be set
|
||||||
|
*/
|
||||||
|
#define PALDevDataSet(Dev, field, data) ((Dev->Data.field) = (data))
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @defgroup VL53L0_registerAccess_group PAL Register Access Functions
|
||||||
|
* @brief PAL Register Access Functions
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Lock comms interface to serialize all commands to a shared I2C interface
|
||||||
|
* for a specific device
|
||||||
|
* @param Dev Device Handle
|
||||||
|
* @return VL53L0_ERROR_NONE Success
|
||||||
|
* @return "Other error code" See ::VL53L0_Error
|
||||||
|
*/
|
||||||
|
VL53L0_Error VL53L0_LockSequenceAccess(VL53L0_DEV Dev);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Unlock comms interface to serialize all commands to a shared I2C interface
|
||||||
|
* for a specific device
|
||||||
|
* @param Dev Device Handle
|
||||||
|
* @return VL53L0_ERROR_NONE Success
|
||||||
|
* @return "Other error code" See ::VL53L0_Error
|
||||||
|
*/
|
||||||
|
VL53L0_Error VL53L0_UnlockSequenceAccess(VL53L0_DEV Dev);
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Writes the supplied byte buffer to the device
|
||||||
|
* @param Dev Device Handle
|
||||||
|
* @param index The register index
|
||||||
|
* @param pdata Pointer to uint8_t buffer containing the data to be written
|
||||||
|
* @param count Number of bytes in the supplied byte buffer
|
||||||
|
* @return VL53L0_ERROR_NONE Success
|
||||||
|
* @return "Other error code" See ::VL53L0_Error
|
||||||
|
*/
|
||||||
|
VL53L0_Error VL53L0_WriteMulti(VL53L0_DEV Dev, uint8_t index,
|
||||||
|
uint8_t *pdata, uint32_t count);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Reads the requested number of bytes from the device
|
||||||
|
* @param Dev Device Handle
|
||||||
|
* @param index The register index
|
||||||
|
* @param pdata Pointer to the uint8_t buffer to store read data
|
||||||
|
* @param count Number of uint8_t's to read
|
||||||
|
* @return VL53L0_ERROR_NONE Success
|
||||||
|
* @return "Other error code" See ::VL53L0_Error
|
||||||
|
*/
|
||||||
|
VL53L0_Error VL53L0_ReadMulti(VL53L0_DEV Dev, uint8_t index,
|
||||||
|
uint8_t *pdata, uint32_t count);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Write single byte register
|
||||||
|
* @param Dev Device Handle
|
||||||
|
* @param index The register index
|
||||||
|
* @param data 8 bit register data
|
||||||
|
* @return VL53L0_ERROR_NONE Success
|
||||||
|
* @return "Other error code" See ::VL53L0_Error
|
||||||
|
*/
|
||||||
|
VL53L0_Error VL53L0_WrByte(VL53L0_DEV Dev, uint8_t index, uint8_t data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Write word register
|
||||||
|
* @param Dev Device Handle
|
||||||
|
* @param index The register index
|
||||||
|
* @param data 16 bit register data
|
||||||
|
* @return VL53L0_ERROR_NONE Success
|
||||||
|
* @return "Other error code" See ::VL53L0_Error
|
||||||
|
*/
|
||||||
|
VL53L0_Error VL53L0_WrWord(VL53L0_DEV Dev, uint8_t index, uint16_t data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Write double word (4 byte) register
|
||||||
|
* @param Dev Device Handle
|
||||||
|
* @param index The register index
|
||||||
|
* @param data 32 bit register data
|
||||||
|
* @return VL53L0_ERROR_NONE Success
|
||||||
|
* @return "Other error code" See ::VL53L0_Error
|
||||||
|
*/
|
||||||
|
VL53L0_Error VL53L0_WrDWord(VL53L0_DEV Dev, uint8_t index, uint32_t data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Read single byte register
|
||||||
|
* @param Dev Device Handle
|
||||||
|
* @param index The register index
|
||||||
|
* @param data pointer to 8 bit data
|
||||||
|
* @return VL53L0_ERROR_NONE Success
|
||||||
|
* @return "Other error code" See ::VL53L0_Error
|
||||||
|
*/
|
||||||
|
VL53L0_Error VL53L0_RdByte(VL53L0_DEV Dev, uint8_t index, uint8_t *data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Read word (2byte) register
|
||||||
|
* @param Dev Device Handle
|
||||||
|
* @param index The register index
|
||||||
|
* @param data pointer to 16 bit data
|
||||||
|
* @return VL53L0_ERROR_NONE Success
|
||||||
|
* @return "Other error code" See ::VL53L0_Error
|
||||||
|
*/
|
||||||
|
VL53L0_Error VL53L0_RdWord(VL53L0_DEV Dev, uint8_t index, uint16_t *data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Read dword (4byte) register
|
||||||
|
* @param Dev Device Handle
|
||||||
|
* @param index The register index
|
||||||
|
* @param data pointer to 32 bit data
|
||||||
|
* @return VL53L0_ERROR_NONE Success
|
||||||
|
* @return "Other error code" See ::VL53L0_Error
|
||||||
|
*/
|
||||||
|
VL53L0_Error VL53L0_RdDWord(VL53L0_DEV Dev, uint8_t index, uint32_t *data);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Threat safe Update (read/modify/write) single byte register
|
||||||
|
*
|
||||||
|
* Final_reg = (Initial_reg & and_data) |or_data
|
||||||
|
*
|
||||||
|
* @param Dev Device Handle
|
||||||
|
* @param index The register index
|
||||||
|
* @param AndData 8 bit and data
|
||||||
|
* @param OrData 8 bit or data
|
||||||
|
* @return VL53L0_ERROR_NONE Success
|
||||||
|
* @return "Other error code" See ::VL53L0_Error
|
||||||
|
*/
|
||||||
|
VL53L0_Error VL53L0_UpdateByte(VL53L0_DEV Dev, uint8_t index,
|
||||||
|
uint8_t AndData, uint8_t OrData);
|
||||||
|
|
||||||
|
/** @} end of VL53L0_registerAccess_group */
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief execute delay in all polling API call
|
||||||
|
*
|
||||||
|
* A typical multi-thread or RTOs implementation is to sleep the task for
|
||||||
|
* some 5ms (with 100Hz max rate faster polling is not needed)
|
||||||
|
* if nothing specific is need you can define it as an empty/void macro
|
||||||
|
* @code
|
||||||
|
* #define VL53L0_PollingDelay(...) (void)0
|
||||||
|
* @endcode
|
||||||
|
* @param Dev Device Handle
|
||||||
|
* @return VL53L0_ERROR_NONE Success
|
||||||
|
* @return "Other error code" See ::VL53L0_Error
|
||||||
|
*/
|
||||||
|
VL53L0_Error VL53L0_PollingDelay(VL53L0_DEV Dev);
|
||||||
|
/* usually best implemented as a real function */
|
||||||
|
|
||||||
|
/** @} end of VL53L0_platform_group */
|
||||||
|
|
||||||
|
#endif /* _VL53L0_PLATFORM_H_ */
|
||||||
|
|
||||||
|
|
||||||
|
|
128
drivers/input/misc/vl53L0/inc/vl53l0_platform_log.h
Normal file
128
drivers/input/misc/vl53L0/inc/vl53l0_platform_log.h
Normal file
|
@ -0,0 +1,128 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2015, 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 _VL53L0_PLATFORM_LOG_H_
|
||||||
|
#define _VL53L0_PLATFORM_LOG_H_
|
||||||
|
|
||||||
|
#include <linux/string.h>
|
||||||
|
/* LOG Functions */
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file vl53l0_platform_log.h
|
||||||
|
*
|
||||||
|
* @brief platform log function definition
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* #define VL53L0_LOG_ENABLE */
|
||||||
|
|
||||||
|
enum {
|
||||||
|
TRACE_LEVEL_NONE,
|
||||||
|
TRACE_LEVEL_ERRORS,
|
||||||
|
TRACE_LEVEL_WARNING,
|
||||||
|
TRACE_LEVEL_INFO,
|
||||||
|
TRACE_LEVEL_DEBUG,
|
||||||
|
TRACE_LEVEL_ALL,
|
||||||
|
TRACE_LEVEL_IGNORE
|
||||||
|
};
|
||||||
|
|
||||||
|
enum {
|
||||||
|
TRACE_FUNCTION_NONE = 0,
|
||||||
|
TRACE_FUNCTION_I2C = 1,
|
||||||
|
TRACE_FUNCTION_ALL = 0x7fffffff /* all bits except sign */
|
||||||
|
};
|
||||||
|
|
||||||
|
enum {
|
||||||
|
TRACE_MODULE_NONE = 0x0,
|
||||||
|
TRACE_MODULE_API = 0x1,
|
||||||
|
TRACE_MODULE_PLATFORM = 0x2,
|
||||||
|
TRACE_MODULE_ALL = 0x7fffffff /* all bits except sign */
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef VL53L0_LOG_ENABLE
|
||||||
|
|
||||||
|
#include <linux/module.h>
|
||||||
|
|
||||||
|
|
||||||
|
extern uint32_t _trace_level;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
int32_t VL53L0_trace_config(char *filename, uint32_t modules,
|
||||||
|
uint32_t level, uint32_t functions);
|
||||||
|
|
||||||
|
#if 0
|
||||||
|
void trace_print_module_function(uint32_t module, uint32_t level,
|
||||||
|
uint32_t function, const char *format, ...);
|
||||||
|
#else
|
||||||
|
#define trace_print_module_function(...)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define LOG_GET_TIME() (int)0
|
||||||
|
/*
|
||||||
|
* #define _LOG_FUNCTION_START(module, fmt, ...) \
|
||||||
|
printk(KERN_INFO"beg %s start @%d\t" fmt "\n", \
|
||||||
|
__func__, LOG_GET_TIME(), ##__VA_ARGS__)
|
||||||
|
|
||||||
|
* #define _LOG_FUNCTION_END(module, status, ...)\
|
||||||
|
printk(KERN_INFO"end %s @%d %d\n", \
|
||||||
|
__func__, LOG_GET_TIME(), (int)status)
|
||||||
|
|
||||||
|
* #define _LOG_FUNCTION_END_FMT(module, status, fmt, ...)\
|
||||||
|
printk(KERN_INFO"End %s @%d %d\t"fmt"\n" , \
|
||||||
|
__func__, LOG_GET_TIME(), (int)status, ##__VA_ARGS__)
|
||||||
|
*/
|
||||||
|
#define _LOG_FUNCTION_START(module, fmt, ...) \
|
||||||
|
pr_err("beg %s start @%d\t" fmt "\n", \
|
||||||
|
__func__, LOG_GET_TIME(), ##__VA_ARGS__)
|
||||||
|
|
||||||
|
#define _LOG_FUNCTION_END(module, status, ...)\
|
||||||
|
pr_err("end %s start @%d Status %d\n", \
|
||||||
|
__func__, LOG_GET_TIME(), (int)status)
|
||||||
|
|
||||||
|
#define _LOG_FUNCTION_END_FMT(module, status, fmt, ...)\
|
||||||
|
pr_err("End %s @%d %d\t"fmt"\n", \
|
||||||
|
__func__, LOG_GET_TIME(), (int)status, ##__VA_ARGS__)
|
||||||
|
|
||||||
|
|
||||||
|
#else /* VL53L0_LOG_ENABLE no logging */
|
||||||
|
#define VL53L0_ErrLog(...) (void)0
|
||||||
|
#define _LOG_FUNCTION_START(module, fmt, ...) (void)0
|
||||||
|
#define _LOG_FUNCTION_END(module, status, ...) (void)0
|
||||||
|
#define _LOG_FUNCTION_END_FMT(module, status, fmt, ...) (void)0
|
||||||
|
#endif /* else */
|
||||||
|
|
||||||
|
#define VL53L0_COPYSTRING(str, ...) strlcpy(str, ##__VA_ARGS__, sizeof(str))
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* _VL53L0_PLATFORM_LOG_H_ */
|
||||||
|
|
||||||
|
|
||||||
|
|
146
drivers/input/misc/vl53L0/inc/vl53l0_tuning.h
Normal file
146
drivers/input/misc/vl53L0/inc/vl53l0_tuning.h
Normal file
|
@ -0,0 +1,146 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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 _VL53L0_TUNING_H_
|
||||||
|
#define _VL53L0_TUNING_H_
|
||||||
|
|
||||||
|
#include "vl53l0_def.h"
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
uint8_t DefaultTuningSettings[] = {
|
||||||
|
|
||||||
|
/* update 02/11/2015_v36 */
|
||||||
|
0x01, 0xFF, 0x01,
|
||||||
|
0x01, 0x00, 0x00,
|
||||||
|
|
||||||
|
0x01, 0xFF, 0x00,
|
||||||
|
0x01, 0x09, 0x00,
|
||||||
|
0x01, 0x10, 0x00,
|
||||||
|
0x01, 0x11, 0x00,
|
||||||
|
|
||||||
|
0x01, 0x24, 0x01,
|
||||||
|
0x01, 0x25, 0xff,
|
||||||
|
0x01, 0x75, 0x00,
|
||||||
|
|
||||||
|
0x01, 0xFF, 0x01,
|
||||||
|
0x01, 0x4e, 0x2c,
|
||||||
|
0x01, 0x48, 0x00,
|
||||||
|
0x01, 0x30, 0x20,
|
||||||
|
|
||||||
|
0x01, 0xFF, 0x00,
|
||||||
|
0x01, 0x30, 0x09, /* mja changed from 0x64. */
|
||||||
|
0x01, 0x54, 0x00,
|
||||||
|
0x01, 0x31, 0x04,
|
||||||
|
0x01, 0x32, 0x03,
|
||||||
|
0x01, 0x40, 0x83,
|
||||||
|
0x01, 0x46, 0x25,
|
||||||
|
0x01, 0x60, 0x00,
|
||||||
|
0x01, 0x27, 0x00,
|
||||||
|
0x01, 0x50, 0x06,
|
||||||
|
0x01, 0x51, 0x00,
|
||||||
|
0x01, 0x52, 0x96,
|
||||||
|
0x01, 0x56, 0x08,
|
||||||
|
0x01, 0x57, 0x30,
|
||||||
|
0x01, 0x61, 0x00,
|
||||||
|
0x01, 0x62, 0x00,
|
||||||
|
0x01, 0x64, 0x00,
|
||||||
|
0x01, 0x65, 0x00,
|
||||||
|
0x01, 0x66, 0xa0,
|
||||||
|
|
||||||
|
0x01, 0xFF, 0x01,
|
||||||
|
0x01, 0x22, 0x32,
|
||||||
|
0x01, 0x47, 0x14,
|
||||||
|
0x01, 0x49, 0xff,
|
||||||
|
0x01, 0x4a, 0x00,
|
||||||
|
|
||||||
|
0x01, 0xFF, 0x00,
|
||||||
|
0x01, 0x7a, 0x0a,
|
||||||
|
0x01, 0x7b, 0x00,
|
||||||
|
0x01, 0x78, 0x21,
|
||||||
|
|
||||||
|
0x01, 0xFF, 0x01,
|
||||||
|
0x01, 0x23, 0x34,
|
||||||
|
0x01, 0x42, 0x00,
|
||||||
|
0x01, 0x44, 0xff,
|
||||||
|
0x01, 0x45, 0x26,
|
||||||
|
0x01, 0x46, 0x05,
|
||||||
|
0x01, 0x40, 0x40,
|
||||||
|
0x01, 0x0E, 0x06,
|
||||||
|
0x01, 0x20, 0x1a,
|
||||||
|
0x01, 0x43, 0x40,
|
||||||
|
|
||||||
|
0x01, 0xFF, 0x00,
|
||||||
|
0x01, 0x34, 0x03,
|
||||||
|
0x01, 0x35, 0x44,
|
||||||
|
|
||||||
|
0x01, 0xFF, 0x01,
|
||||||
|
0x01, 0x31, 0x04,
|
||||||
|
0x01, 0x4b, 0x09,
|
||||||
|
0x01, 0x4c, 0x05,
|
||||||
|
0x01, 0x4d, 0x04,
|
||||||
|
|
||||||
|
|
||||||
|
0x01, 0xFF, 0x00,
|
||||||
|
0x01, 0x44, 0x00,
|
||||||
|
0x01, 0x45, 0x20,
|
||||||
|
0x01, 0x47, 0x08,
|
||||||
|
0x01, 0x48, 0x28,
|
||||||
|
0x01, 0x67, 0x00,
|
||||||
|
0x01, 0x70, 0x04,
|
||||||
|
0x01, 0x71, 0x01,
|
||||||
|
0x01, 0x72, 0xfe,
|
||||||
|
0x01, 0x76, 0x00,
|
||||||
|
0x01, 0x77, 0x00,
|
||||||
|
|
||||||
|
0x01, 0xFF, 0x01,
|
||||||
|
0x01, 0x0d, 0x01,
|
||||||
|
|
||||||
|
0x01, 0xFF, 0x00,
|
||||||
|
0x01, 0x80, 0x01,
|
||||||
|
0x01, 0x01, 0xF8,
|
||||||
|
|
||||||
|
0x01, 0xFF, 0x01,
|
||||||
|
0x01, 0x8e, 0x01,
|
||||||
|
0x01, 0x00, 0x01,
|
||||||
|
0x01, 0xFF, 0x00,
|
||||||
|
0x01, 0x80, 0x00,
|
||||||
|
|
||||||
|
0x00, 0x00, 0x00
|
||||||
|
};
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* _VL53L0_TUNING_H_ */
|
69
drivers/input/misc/vl53L0/inc/vl53l0_types.h
Normal file
69
drivers/input/misc/vl53L0/inc/vl53l0_types.h
Normal file
|
@ -0,0 +1,69 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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 VL53L0_TYPES_H_
|
||||||
|
#define VL53L0_TYPES_H_
|
||||||
|
|
||||||
|
#include <linux/types.h>
|
||||||
|
|
||||||
|
#ifndef NULL
|
||||||
|
#error "TODO review NULL definition or add required include "
|
||||||
|
#define NULL 0
|
||||||
|
#endif
|
||||||
|
/** use where fractional values are expected
|
||||||
|
*
|
||||||
|
* Given a floating point value f it's .16 bit point is (int)(f*(1<<16))
|
||||||
|
*/
|
||||||
|
typedef unsigned int FixPoint1616_t;
|
||||||
|
|
||||||
|
#if !defined(STDINT_H) && !defined(_GCC_STDINT_H) \
|
||||||
|
&& !defined(_STDINT_H) && !defined(_LINUX_TYPES_H)
|
||||||
|
|
||||||
|
#pragma message("Please review type definition of STDINT define for your" \
|
||||||
|
"platform and add to list above ")
|
||||||
|
|
||||||
|
/*
|
||||||
|
* target platform do not provide stdint or use a different #define than above
|
||||||
|
* to avoid seeing the message below addapt the #define list above or implement
|
||||||
|
* all type and delete these pragma
|
||||||
|
*/
|
||||||
|
|
||||||
|
typedef unsigned int uint32_t;
|
||||||
|
typedef int int32_t;
|
||||||
|
|
||||||
|
typedef unsigned short uint16_t;
|
||||||
|
typedef short int16_t;
|
||||||
|
|
||||||
|
typedef unsigned char uint8_t;
|
||||||
|
|
||||||
|
typedef signed char int8_t;
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* VL53L0_TYPES_H_ */
|
||||||
|
|
||||||
|
#endif /* VL6180x_TYPES_H_ */
|
4175
drivers/input/misc/vl53L0/src/vl53l010_api.c
Normal file
4175
drivers/input/misc/vl53L0/src/vl53l010_api.c
Normal file
File diff suppressed because it is too large
Load diff
138
drivers/input/misc/vl53L0/src/vl53l010_tuning.c
Normal file
138
drivers/input/misc/vl53L0/src/vl53l010_tuning.c
Normal file
|
@ -0,0 +1,138 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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.
|
||||||
|
******************************************************************************/
|
||||||
|
|
||||||
|
#include "vl53l010_tuning.h"
|
||||||
|
|
||||||
|
#define LOG_FUNCTION_START(fmt, ...) \
|
||||||
|
_LOG_FUNCTION_START(TRACE_MODULE_API, fmt, ##__VA_ARGS__)
|
||||||
|
#define LOG_FUNCTION_END(status, ...) \
|
||||||
|
_LOG_FUNCTION_END(TRACE_MODULE_API, status, ##__VA_ARGS__)
|
||||||
|
#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
|
||||||
|
_LOG_FUNCTION_END_FMT(TRACE_MODULE_API, status, fmt, ##__VA_ARGS__)
|
||||||
|
|
||||||
|
#ifdef VL53L0_LOG_ENABLE
|
||||||
|
#define trace_print(level, ...) \
|
||||||
|
trace_print_module_function(TRACE_MODULE_API,\
|
||||||
|
level, TRACE_FUNCTION_NONE, ##__VA_ARGS__)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*
|
||||||
|
* //////////////////////////////////////////////////////
|
||||||
|
* //// DEFAULT TUNING SETTINGS ////
|
||||||
|
* //////////////////////////////////////////////////////
|
||||||
|
*/
|
||||||
|
VL53L0_Error VL53L010_load_tuning_settings(VL53L0_DEV Dev)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
|
||||||
|
/* update 14_12_15_v11 */
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0xFF, 0x01);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x00, 0x00);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x91, 0x3C);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0xFF, 0x00);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x54, 0x01);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x33, 0x05);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x32, 0x03);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x30, 0x05);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x50, 0x05);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x60, 0x04);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x70, 0x06);
|
||||||
|
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x46, 0x1a);
|
||||||
|
Status |= VL53L0_WrWord(Dev, 0x51, 0x01a3);
|
||||||
|
Status |= VL53L0_WrWord(Dev, 0x61, 0x01c4);
|
||||||
|
Status |= VL53L0_WrWord(Dev, 0x71, 0x018c);
|
||||||
|
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0xFF, 0x01);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x31, 0x0f);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0xFF, 0x00);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x66, 0x38);
|
||||||
|
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x47, 0x00);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x48, 0xff);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x57, 0x4c);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x67, 0x3c);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x77, 0x5c);
|
||||||
|
|
||||||
|
Status |= VL53L0_WrWord(Dev, 0x44, 0x0000);
|
||||||
|
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x27, 0x00);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x55, 0x00);
|
||||||
|
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0xFF, 0x01);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x30, 0x28);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0xFF, 0x00);
|
||||||
|
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x10, 0x0f);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x11, 0xff);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x40, 0x82);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x41, 0xff);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x42, 0x07);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x43, 0x12);
|
||||||
|
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x20, 0x00);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x21, 0x00);
|
||||||
|
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x28, 0x06);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0xFF, 0x01);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x48, 0x28);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0xFF, 0x00);
|
||||||
|
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x7a, 0x0a);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x7b, 0x00);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x78, 0x00);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0xFF, 0x01);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x44, 0xff);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x45, 0x00);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x46, 0x10);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0xFF, 0x00);
|
||||||
|
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x04, 0x00);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x05, 0x04);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x06, 0x00);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x07, 0x00);
|
||||||
|
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0xFF, 0x01);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x0d, 0x01);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0xFF, 0x00);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x80, 0x01);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x01, 0xF8);
|
||||||
|
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0xFF, 0x01);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x8e, 0x01);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0x00, 0x01);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0xFF, 0x00);
|
||||||
|
|
||||||
|
if (Status != 0)
|
||||||
|
Status = VL53L0_ERROR_CONTROL_INTERFACE;
|
||||||
|
|
||||||
|
LOG_FUNCTION_END(Status);
|
||||||
|
return Status;
|
||||||
|
}
|
3109
drivers/input/misc/vl53L0/src/vl53l0_api.c
Normal file
3109
drivers/input/misc/vl53L0/src/vl53l0_api.c
Normal file
File diff suppressed because it is too large
Load diff
1284
drivers/input/misc/vl53L0/src/vl53l0_api_calibration.c
Normal file
1284
drivers/input/misc/vl53L0/src/vl53l0_api_calibration.c
Normal file
File diff suppressed because it is too large
Load diff
2270
drivers/input/misc/vl53L0/src/vl53l0_api_core.c
Normal file
2270
drivers/input/misc/vl53L0/src/vl53l0_api_core.c
Normal file
File diff suppressed because it is too large
Load diff
750
drivers/input/misc/vl53L0/src/vl53l0_api_histogram.c
Normal file
750
drivers/input/misc/vl53L0/src/vl53l0_api_histogram.c
Normal file
|
@ -0,0 +1,750 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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.
|
||||||
|
******************************************************************************/
|
||||||
|
|
||||||
|
#include "vl53l0_api.h"
|
||||||
|
#include "vl53l0_api_core.h"
|
||||||
|
#include "vl53l0_api_histogram.h"
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef __KERNEL__
|
||||||
|
#include <stdlib.h>
|
||||||
|
#endif
|
||||||
|
#define LOG_FUNCTION_START(fmt, ...) \
|
||||||
|
_LOG_FUNCTION_START(TRACE_MODULE_API, fmt, ##__VA_ARGS__)
|
||||||
|
#define LOG_FUNCTION_END(status, ...) \
|
||||||
|
_LOG_FUNCTION_END(TRACE_MODULE_API, status, ##__VA_ARGS__)
|
||||||
|
#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
|
||||||
|
_LOG_FUNCTION_END_FMT(TRACE_MODULE_API, status, fmt, ##__VA_ARGS__)
|
||||||
|
|
||||||
|
|
||||||
|
typedef uint32_t WindowSelection;
|
||||||
|
#define VL53L0_AMBIENT_WINDOW_ONLY ((WindowSelection) 0)
|
||||||
|
/*!< Measure Ambient Signal only */
|
||||||
|
#define VL53L0_AMBIENT_AND_SIGNAL_WINDOW ((WindowSelection) 1)
|
||||||
|
/*!< Measure Combined Ambient and Signal Rate. */
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_start_histogram_measurement(VL53L0_DEV Dev,
|
||||||
|
VL53L0_HistogramModes histoMode,
|
||||||
|
uint32_t count)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
uint8_t dataByte;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
|
||||||
|
|
||||||
|
dataByte = VL53L0_REG_SYSRANGE_MODE_SINGLESHOT |
|
||||||
|
VL53L0_REG_SYSRANGE_MODE_START_STOP;
|
||||||
|
|
||||||
|
/* First histogram measurement must have bit 5 set */
|
||||||
|
if (count == 0)
|
||||||
|
dataByte |= (1 << 5);
|
||||||
|
|
||||||
|
switch (histoMode) {
|
||||||
|
case VL53L0_HISTOGRAMMODE_DISABLED:
|
||||||
|
/* Selected mode not supported */
|
||||||
|
Status = VL53L0_ERROR_INVALID_COMMAND;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case VL53L0_HISTOGRAMMODE_REFERENCE_ONLY:
|
||||||
|
case VL53L0_HISTOGRAMMODE_RETURN_ONLY:
|
||||||
|
case VL53L0_HISTOGRAMMODE_BOTH:
|
||||||
|
dataByte |= (histoMode << 3);
|
||||||
|
Status = VL53L0_WrByte(Dev, VL53L0_REG_SYSRANGE_START,
|
||||||
|
dataByte);
|
||||||
|
if (Status == VL53L0_ERROR_NONE) {
|
||||||
|
/* Set PAL State to Running */
|
||||||
|
PALDevDataSet(Dev, PalState, VL53L0_STATE_RUNNING);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
/* Selected mode not supported */
|
||||||
|
Status = VL53L0_ERROR_MODE_NOT_SUPPORTED;
|
||||||
|
}
|
||||||
|
|
||||||
|
LOG_FUNCTION_END(Status);
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_confirm_measurement_start(VL53L0_DEV Dev)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
uint8_t NewDataReady = 0;
|
||||||
|
uint32_t LoopNb;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
|
||||||
|
LoopNb = 0;
|
||||||
|
do {
|
||||||
|
Status = VL53L0_GetMeasurementDataReady(Dev, &NewDataReady);
|
||||||
|
if ((NewDataReady == 0x01) || Status != VL53L0_ERROR_NONE)
|
||||||
|
break;
|
||||||
|
|
||||||
|
LoopNb = LoopNb + 1;
|
||||||
|
VL53L0_PollingDelay(Dev);
|
||||||
|
} while (LoopNb < VL53L0_DEFAULT_MAX_LOOP);
|
||||||
|
|
||||||
|
if (LoopNb >= VL53L0_DEFAULT_MAX_LOOP)
|
||||||
|
Status = VL53L0_ERROR_TIME_OUT;
|
||||||
|
|
||||||
|
LOG_FUNCTION_END(Status);
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_set_histogram_mode(VL53L0_DEV Dev,
|
||||||
|
VL53L0_HistogramModes HistogramMode)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
|
||||||
|
switch (HistogramMode) {
|
||||||
|
case VL53L0_HISTOGRAMMODE_DISABLED:
|
||||||
|
case VL53L0_HISTOGRAMMODE_REFERENCE_ONLY:
|
||||||
|
case VL53L0_HISTOGRAMMODE_RETURN_ONLY:
|
||||||
|
case VL53L0_HISTOGRAMMODE_BOTH:
|
||||||
|
/* Supported mode */
|
||||||
|
VL53L0_SETPARAMETERFIELD(Dev, HistogramMode, HistogramMode);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
/* Unsupported mode */
|
||||||
|
Status = VL53L0_ERROR_MODE_NOT_SUPPORTED;
|
||||||
|
}
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_histogram_mode(VL53L0_DEV Dev,
|
||||||
|
VL53L0_HistogramModes *pHistogramMode)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
|
||||||
|
VL53L0_GETPARAMETERFIELD(Dev, HistogramMode, *pHistogramMode);
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_perform_single_histogram_measurement(VL53L0_DEV Dev,
|
||||||
|
VL53L0_HistogramMeasurementData_t *pHistogramMeasurementData)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
VL53L0_DeviceModes DeviceMode;
|
||||||
|
VL53L0_HistogramModes HistogramMode = VL53L0_HISTOGRAMMODE_DISABLED;
|
||||||
|
uint32_t MeasCount;
|
||||||
|
uint32_t Measurements;
|
||||||
|
|
||||||
|
/* Get Current DeviceMode */
|
||||||
|
Status = VL53L0_GetHistogramMode(Dev, &HistogramMode);
|
||||||
|
|
||||||
|
|
||||||
|
if (Status != VL53L0_ERROR_NONE)
|
||||||
|
return Status;
|
||||||
|
|
||||||
|
|
||||||
|
if (HistogramMode == VL53L0_HISTOGRAMMODE_BOTH) {
|
||||||
|
if (pHistogramMeasurementData->BufferSize <
|
||||||
|
VL53L0_HISTOGRAM_BUFFER_SIZE) {
|
||||||
|
Status = VL53L0_ERROR_BUFFER_TOO_SMALL;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
if (pHistogramMeasurementData->BufferSize <
|
||||||
|
VL53L0_HISTOGRAM_BUFFER_SIZE/2) {
|
||||||
|
Status = VL53L0_ERROR_BUFFER_TOO_SMALL;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
pHistogramMeasurementData->HistogramType = (uint8_t)HistogramMode;
|
||||||
|
pHistogramMeasurementData->ErrorStatus = VL53L0_DEVICEERROR_NONE;
|
||||||
|
pHistogramMeasurementData->FirstBin = 0;
|
||||||
|
pHistogramMeasurementData->NumberOfBins = 0;
|
||||||
|
|
||||||
|
|
||||||
|
/* Get Current DeviceMode */
|
||||||
|
if (Status == VL53L0_ERROR_NONE)
|
||||||
|
Status = VL53L0_GetDeviceMode(Dev, &DeviceMode);
|
||||||
|
|
||||||
|
if (Status == VL53L0_ERROR_NONE)
|
||||||
|
Status = VL53L0_WrByte(Dev, VL53L0_REG_SYSTEM_HISTOGRAM_BIN,
|
||||||
|
0x00);
|
||||||
|
|
||||||
|
if (Status == VL53L0_ERROR_NONE)
|
||||||
|
Status = VL53L0_WrByte(Dev,
|
||||||
|
VL53L0_REG_HISTOGRAM_CONFIG_INITIAL_PHASE_SELECT, 0x00);
|
||||||
|
|
||||||
|
if (Status == VL53L0_ERROR_NONE)
|
||||||
|
Status = VL53L0_WrByte(Dev,
|
||||||
|
VL53L0_REG_HISTOGRAM_CONFIG_READOUT_CTRL, 0x01);
|
||||||
|
|
||||||
|
if (Status != VL53L0_ERROR_NONE)
|
||||||
|
return Status;
|
||||||
|
|
||||||
|
Measurements = 3;
|
||||||
|
if (HistogramMode == VL53L0_HISTOGRAMMODE_BOTH)
|
||||||
|
Measurements = 6;
|
||||||
|
|
||||||
|
if (DeviceMode != VL53L0_DEVICEMODE_SINGLE_HISTOGRAM) {
|
||||||
|
Status = VL53L0_ERROR_INVALID_COMMAND;
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* DeviceMode == VL53L0_DEVICEMODE_SINGLE_HISTOGRAM */
|
||||||
|
MeasCount = 0;
|
||||||
|
while ((MeasCount < Measurements) && (Status == VL53L0_ERROR_NONE)) {
|
||||||
|
Status = VL53L0_start_histogram_measurement(Dev, HistogramMode,
|
||||||
|
MeasCount);
|
||||||
|
|
||||||
|
if (Status == VL53L0_ERROR_NONE)
|
||||||
|
VL53L0_confirm_measurement_start(Dev);
|
||||||
|
|
||||||
|
if (Status == VL53L0_ERROR_NONE)
|
||||||
|
PALDevDataSet(Dev, PalState, VL53L0_STATE_RUNNING);
|
||||||
|
|
||||||
|
if (Status == VL53L0_ERROR_NONE)
|
||||||
|
Status = VL53L0_measurement_poll_for_completion(Dev);
|
||||||
|
|
||||||
|
if (Status == VL53L0_ERROR_NONE) {
|
||||||
|
Status = VL53L0_read_histo_measurement(Dev,
|
||||||
|
pHistogramMeasurementData->HistogramData,
|
||||||
|
MeasCount,
|
||||||
|
HistogramMode);
|
||||||
|
|
||||||
|
if (Status == VL53L0_ERROR_NONE) {
|
||||||
|
/*
|
||||||
|
* When reading both rtn and ref arrays,
|
||||||
|
* histograms are read two bins at a time.
|
||||||
|
* For rtn or ref only, histograms are read four
|
||||||
|
* bins at a time.
|
||||||
|
*/
|
||||||
|
if (HistogramMode == VL53L0_HISTOGRAMMODE_BOTH)
|
||||||
|
pHistogramMeasurementData->NumberOfBins
|
||||||
|
+= 2;
|
||||||
|
else
|
||||||
|
pHistogramMeasurementData->NumberOfBins
|
||||||
|
+= 4;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (Status == VL53L0_ERROR_NONE)
|
||||||
|
Status = VL53L0_ClearInterruptMask(Dev, 0);
|
||||||
|
|
||||||
|
MeasCount++;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Change PAL State in case of single ranging or single histogram */
|
||||||
|
if (Status == VL53L0_ERROR_NONE) {
|
||||||
|
pHistogramMeasurementData->NumberOfBins = 12;
|
||||||
|
PALDevDataSet(Dev, PalState, VL53L0_STATE_IDLE);
|
||||||
|
}
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_histogram_measurement_data(VL53L0_DEV Dev,
|
||||||
|
VL53L0_HistogramMeasurementData_t *pHistogramMeasurementData)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NOT_IMPLEMENTED;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
|
||||||
|
LOG_FUNCTION_END(Status);
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_read_histo_measurement(VL53L0_DEV Dev,
|
||||||
|
uint32_t *histoData,
|
||||||
|
uint32_t offset,
|
||||||
|
VL53L0_HistogramModes histoMode)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
uint8_t localBuffer[28];
|
||||||
|
uint32_t cDataSize = 4;
|
||||||
|
uint32_t offset1;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
|
||||||
|
Status = VL53L0_WrByte(Dev, 0xFF, VL53L0_REG_RESULT_CORE_PAGE);
|
||||||
|
Status = VL53L0_ReadMulti(Dev,
|
||||||
|
(uint8_t)VL53L0_REG_RESULT_CORE_AMBIENT_WINDOW_EVENTS_RTN,
|
||||||
|
localBuffer,
|
||||||
|
28);
|
||||||
|
Status |= VL53L0_WrByte(Dev, 0xFF, 0x00);
|
||||||
|
|
||||||
|
if (Status == VL53L0_ERROR_NONE) {
|
||||||
|
VL53L0_reverse_bytes(&localBuffer[0], cDataSize);
|
||||||
|
VL53L0_reverse_bytes(&localBuffer[4], cDataSize);
|
||||||
|
VL53L0_reverse_bytes(&localBuffer[20], cDataSize);
|
||||||
|
VL53L0_reverse_bytes(&localBuffer[24], cDataSize);
|
||||||
|
|
||||||
|
offset1 = offset * cDataSize;
|
||||||
|
if (histoMode == VL53L0_HISTOGRAMMODE_BOTH) {
|
||||||
|
/*
|
||||||
|
* When reading both return and ref data, each
|
||||||
|
* measurement reads two ref values and two return
|
||||||
|
* values. Data is stored in an interleaved sequence,
|
||||||
|
* starting with the return histogram.
|
||||||
|
*
|
||||||
|
* Some result Core registers are reused for the
|
||||||
|
* histogram measurements
|
||||||
|
*
|
||||||
|
* The bin values are retrieved in the following order
|
||||||
|
* VL53L0_REG_RESULT_CORE_RANGING_TOTAL_EVENTS_RTN
|
||||||
|
* VL53L0_REG_RESULT_CORE_RANGING_TOTAL_EVENTS_REF
|
||||||
|
* VL53L0_REG_RESULT_CORE_AMBIENT_WINDOW_EVENTS_RTN
|
||||||
|
* VL53L0_REG_RESULT_CORE_AMBIENT_WINDOW_EVENTS_REF
|
||||||
|
*/
|
||||||
|
|
||||||
|
memcpy(&histoData[offset1], &localBuffer[4],
|
||||||
|
cDataSize); /* rtn */
|
||||||
|
memcpy(&histoData[offset1 + 1], &localBuffer[24],
|
||||||
|
cDataSize); /* ref */
|
||||||
|
memcpy(&histoData[offset1 + 2], &localBuffer[0],
|
||||||
|
cDataSize); /* rtn */
|
||||||
|
memcpy(&histoData[offset1 + 3], &localBuffer[20],
|
||||||
|
cDataSize); /* ref */
|
||||||
|
|
||||||
|
} else {
|
||||||
|
/*
|
||||||
|
* When reading either return and ref data, each
|
||||||
|
* measurement reads four bin values.
|
||||||
|
*
|
||||||
|
* The bin values are retrieved in the following order
|
||||||
|
* VL53L0_REG_RESULT_CORE_RANGING_TOTAL_EVENTS_RTN
|
||||||
|
* VL53L0_REG_RESULT_CORE_AMBIENT_WINDOW_EVENTS_RTN
|
||||||
|
* VL53L0_REG_RESULT_CORE_RANGING_TOTAL_EVENTS_REF
|
||||||
|
* VL53L0_REG_RESULT_CORE_AMBIENT_WINDOW_EVENTS_REF
|
||||||
|
*/
|
||||||
|
|
||||||
|
memcpy(&histoData[offset1], &localBuffer[24],
|
||||||
|
cDataSize);
|
||||||
|
memcpy(&histoData[offset1 + 1], &localBuffer[20],
|
||||||
|
cDataSize);
|
||||||
|
memcpy(&histoData[offset1 + 2], &localBuffer[4],
|
||||||
|
cDataSize);
|
||||||
|
memcpy(&histoData[offset1 + 3], &localBuffer[0],
|
||||||
|
cDataSize);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
LOG_FUNCTION_END(Status);
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_max_spads(VL53L0_DEV Dev,
|
||||||
|
uint32_t *pmax_spads, uint8_t *pambient_too_high)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
uint8_t TCC_Enabled;
|
||||||
|
uint8_t MSRC_Enabled;
|
||||||
|
VL53L0_RangingMeasurementData_t RangingMeasurementData;
|
||||||
|
FixPoint1616_t ratio = 0;
|
||||||
|
uint32_t max_spads = 0;
|
||||||
|
|
||||||
|
/* Get the value of the TCC */
|
||||||
|
if (Status == VL53L0_ERROR_NONE)
|
||||||
|
Status = VL53L0_GetSequenceStepEnable(Dev,
|
||||||
|
VL53L0_SEQUENCESTEP_TCC, &TCC_Enabled);
|
||||||
|
|
||||||
|
/* Get the value of the MSRC */
|
||||||
|
if (Status == VL53L0_ERROR_NONE)
|
||||||
|
Status = VL53L0_GetSequenceStepEnable(Dev,
|
||||||
|
VL53L0_SEQUENCESTEP_MSRC, &MSRC_Enabled);
|
||||||
|
|
||||||
|
/* Disable the TCC */
|
||||||
|
if ((Status == VL53L0_ERROR_NONE) && (TCC_Enabled != 0))
|
||||||
|
Status = VL53L0_SetSequenceStepEnable(Dev,
|
||||||
|
VL53L0_SEQUENCESTEP_TCC, 0);
|
||||||
|
|
||||||
|
/* Disable the MSRC */
|
||||||
|
if ((Status == VL53L0_ERROR_NONE) && (MSRC_Enabled != 0))
|
||||||
|
Status = VL53L0_SetSequenceStepEnable(Dev,
|
||||||
|
VL53L0_SEQUENCESTEP_MSRC, 0);
|
||||||
|
|
||||||
|
|
||||||
|
if (Status == VL53L0_ERROR_NONE) {
|
||||||
|
Status = VL53L0_PerformSingleRangingMeasurement(Dev,
|
||||||
|
&RangingMeasurementData);
|
||||||
|
max_spads = (RangingMeasurementData.EffectiveSpadRtnCount +
|
||||||
|
128)/256;
|
||||||
|
*pmax_spads = max_spads;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Check Ambient per spad > 10 Kcps */
|
||||||
|
if (Status == VL53L0_ERROR_NONE) {
|
||||||
|
if (max_spads <= 0) {
|
||||||
|
*pambient_too_high = 1;
|
||||||
|
Status = VL53L0_ERROR_DIVISION_BY_ZERO;
|
||||||
|
} else {
|
||||||
|
ratio = RangingMeasurementData.AmbientRateRtnMegaCps /
|
||||||
|
max_spads;
|
||||||
|
|
||||||
|
/* ratio is given in mega count per second and
|
||||||
|
* FixPoint1616_t
|
||||||
|
*/
|
||||||
|
if (ratio > 65536/100)
|
||||||
|
*pambient_too_high = 1;
|
||||||
|
else
|
||||||
|
*pambient_too_high = 0;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/* Restore the TCC */
|
||||||
|
if (Status == VL53L0_ERROR_NONE) {
|
||||||
|
if (TCC_Enabled != 0)
|
||||||
|
Status = VL53L0_SetSequenceStepEnable(Dev,
|
||||||
|
VL53L0_SEQUENCESTEP_TCC, 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Restore the MSRC */
|
||||||
|
if (Status == VL53L0_ERROR_NONE) {
|
||||||
|
if (MSRC_Enabled != 0)
|
||||||
|
Status = VL53L0_SetSequenceStepEnable(Dev,
|
||||||
|
VL53L0_SEQUENCESTEP_MSRC, 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error calc_xtalk_mcps_per_spad(
|
||||||
|
uint32_t rtn_signal_events,
|
||||||
|
uint32_t timeout_ms,
|
||||||
|
uint32_t max_spads,
|
||||||
|
uint8_t vcsel_pulse_period_pclk,
|
||||||
|
FixPoint1616_t *pxtalk_mcps_per_spad)
|
||||||
|
{
|
||||||
|
/* Calculate the X-Talk per Spad based on given inputs.
|
||||||
|
*
|
||||||
|
* To calculate x-talk, only a portion of the vcsel pulse period is
|
||||||
|
* used, therefore we use the ratio between vcsel_width_pclk and
|
||||||
|
* vcsel_pulse_period_pclks to determine the integration time.
|
||||||
|
*
|
||||||
|
* With the rtn signal events, and the integration time,
|
||||||
|
* the x-talk rate per spad is then determined.
|
||||||
|
*/
|
||||||
|
|
||||||
|
const FixPoint1616_t cmin_xtalk_per_spad = 8; /* 0.000122 */
|
||||||
|
const FixPoint1616_t ccompensation2 = 13;/* 0.0002 */
|
||||||
|
const FixPoint1616_t ccompensation1 = 7; /* 0.0001; */
|
||||||
|
const FixPoint1616_t ctalk_thresh = 66; /* 0.001 */
|
||||||
|
const uint32_t c16BitRoundingParam = 0x00008000;
|
||||||
|
VL53L0_Error status = VL53L0_ERROR_NONE;
|
||||||
|
FixPoint1616_t xtalk_mcps;
|
||||||
|
FixPoint1616_t vcsel_width_to_period_ratio;
|
||||||
|
FixPoint1616_t integration_time_us;
|
||||||
|
uint32_t integration_time_us_int;
|
||||||
|
uint8_t vcsel_width_pclk = 3;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
|
||||||
|
if (vcsel_pulse_period_pclk == 0 || timeout_ms == 0)
|
||||||
|
status = VL53L0_ERROR_DIVISION_BY_ZERO;
|
||||||
|
|
||||||
|
|
||||||
|
if (status == VL53L0_ERROR_NONE) {
|
||||||
|
|
||||||
|
/* (FixPoint1616 + uint32)/uint32 = FixPoint1616 */
|
||||||
|
vcsel_width_to_period_ratio =
|
||||||
|
((vcsel_width_pclk << 16) +
|
||||||
|
(vcsel_pulse_period_pclk/2))/vcsel_pulse_period_pclk;
|
||||||
|
|
||||||
|
/* uint32_t * FixPoint1616 = FixPoint1616 */
|
||||||
|
integration_time_us = timeout_ms * vcsel_width_to_period_ratio
|
||||||
|
* 1000;
|
||||||
|
|
||||||
|
/*FixPoint1616 >>16 = uint32_t */
|
||||||
|
integration_time_us_int = (integration_time_us +
|
||||||
|
c16BitRoundingParam) >> 16;
|
||||||
|
|
||||||
|
/* (uint32_t << 16)/uint32_t = FixPoint1616 */
|
||||||
|
xtalk_mcps = rtn_signal_events << 16;
|
||||||
|
xtalk_mcps = (xtalk_mcps +
|
||||||
|
(integration_time_us_int/2))/integration_time_us_int;
|
||||||
|
|
||||||
|
/* (FixPoint1616 + uint32)/uint32 = FixPoint1616 */
|
||||||
|
*pxtalk_mcps_per_spad = (xtalk_mcps + (max_spads/2))/max_spads;
|
||||||
|
|
||||||
|
/* Apply compensation to prevent overshoot.
|
||||||
|
*/
|
||||||
|
if (*pxtalk_mcps_per_spad < ctalk_thresh)
|
||||||
|
*pxtalk_mcps_per_spad = *pxtalk_mcps_per_spad
|
||||||
|
- ccompensation2;
|
||||||
|
else
|
||||||
|
*pxtalk_mcps_per_spad = *pxtalk_mcps_per_spad
|
||||||
|
- ccompensation1;
|
||||||
|
|
||||||
|
if (*pxtalk_mcps_per_spad < cmin_xtalk_per_spad)
|
||||||
|
*pxtalk_mcps_per_spad = cmin_xtalk_per_spad;
|
||||||
|
|
||||||
|
}
|
||||||
|
LOG_FUNCTION_END("");
|
||||||
|
|
||||||
|
return status;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
uint32_t bytes_to_int(uint8_t *data_bytes)
|
||||||
|
{
|
||||||
|
/* Convert an array of 4 bytes to an integer.
|
||||||
|
*/
|
||||||
|
uint32_t data = (uint32_t)data_bytes[0] << 24;
|
||||||
|
|
||||||
|
data += ((uint32_t)data_bytes[1] << 16);
|
||||||
|
data += ((uint32_t)data_bytes[2] << 8);
|
||||||
|
data += ((uint32_t)data_bytes[3]);
|
||||||
|
return data;
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_Error perform_histo_signal_meas(VL53L0_DEV dev,
|
||||||
|
WindowSelection window_select,
|
||||||
|
uint32_t *psignal_events)
|
||||||
|
{
|
||||||
|
VL53L0_Error status = VL53L0_ERROR_NONE;
|
||||||
|
uint8_t data[8];
|
||||||
|
uint8_t readout_ctrl_val;
|
||||||
|
uint32_t bin_width = 3;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
|
||||||
|
/* Select Ambient or Total Signal Measurement
|
||||||
|
*/
|
||||||
|
if (status == VL53L0_ERROR_NONE) {
|
||||||
|
readout_ctrl_val = bin_width;
|
||||||
|
if (window_select == VL53L0_AMBIENT_WINDOW_ONLY)
|
||||||
|
readout_ctrl_val += 0x80;
|
||||||
|
|
||||||
|
status = VL53L0_WrByte(
|
||||||
|
dev, VL53L0_REG_HISTOGRAM_CONFIG_READOUT_CTRL,
|
||||||
|
readout_ctrl_val);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Perform Measurement.
|
||||||
|
*/
|
||||||
|
if (status == VL53L0_ERROR_NONE)
|
||||||
|
status = VL53L0_start_histogram_measurement(
|
||||||
|
dev, VL53L0_HISTOGRAMMODE_RETURN_ONLY, 0);
|
||||||
|
|
||||||
|
if (status == VL53L0_ERROR_NONE)
|
||||||
|
status = VL53L0_measurement_poll_for_completion(dev);
|
||||||
|
|
||||||
|
if (status == VL53L0_ERROR_NONE)
|
||||||
|
status = VL53L0_ClearInterruptMask(dev, 0);
|
||||||
|
|
||||||
|
/* Read Measurement Data.
|
||||||
|
*/
|
||||||
|
if (status == VL53L0_ERROR_NONE)
|
||||||
|
status = VL53L0_WrByte(dev, 0xFF, VL53L0_REG_RESULT_CORE_PAGE);
|
||||||
|
|
||||||
|
|
||||||
|
if (status == VL53L0_ERROR_NONE) {
|
||||||
|
status = VL53L0_ReadMulti(dev,
|
||||||
|
(uint8_t)VL53L0_REG_RESULT_CORE_AMBIENT_WINDOW_EVENTS_RTN,
|
||||||
|
data,
|
||||||
|
8);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (status == VL53L0_ERROR_NONE)
|
||||||
|
status |= VL53L0_WrByte(dev, 0xFF, 0x00);
|
||||||
|
|
||||||
|
|
||||||
|
/* Take the sum of the Ambient and Signal Window Event readings.
|
||||||
|
*/
|
||||||
|
if (status == VL53L0_ERROR_NONE)
|
||||||
|
*psignal_events = bytes_to_int(data) +
|
||||||
|
bytes_to_int(&(data[4]));
|
||||||
|
|
||||||
|
|
||||||
|
LOG_FUNCTION_END(status);
|
||||||
|
|
||||||
|
return status;
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_Error set_final_range_timeout_us(
|
||||||
|
VL53L0_DEV dev, uint32_t timeout_microSecs,
|
||||||
|
uint16_t final_range_vcsel_period_pclks)
|
||||||
|
{
|
||||||
|
VL53L0_Error status = VL53L0_ERROR_NONE;
|
||||||
|
uint16_t final_range_timeout_mclks;
|
||||||
|
uint16_t final_range_encoded_timeOut;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
|
||||||
|
/* Calculate FINAL RANGE Timeout in Macro Periods (MCLKS)
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* convert timeout to mclks. */
|
||||||
|
final_range_timeout_mclks = VL53L0_calc_timeout_mclks(dev,
|
||||||
|
timeout_microSecs, (uint8_t) final_range_vcsel_period_pclks);
|
||||||
|
|
||||||
|
/* Encode timeout */
|
||||||
|
final_range_encoded_timeOut = VL53L0_encode_timeout(
|
||||||
|
final_range_timeout_mclks);
|
||||||
|
|
||||||
|
/* Write to device */
|
||||||
|
status = VL53L0_WrWord(dev,
|
||||||
|
VL53L0_REG_FINAL_RANGE_CONFIG_TIMEOUT_MACROP_HI,
|
||||||
|
final_range_encoded_timeOut);
|
||||||
|
|
||||||
|
LOG_FUNCTION_END(status);
|
||||||
|
|
||||||
|
return status;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error perform_histogram_config(VL53L0_DEV dev,
|
||||||
|
uint32_t timeout_ms, uint16_t final_range_vcsel_period_pclks)
|
||||||
|
{
|
||||||
|
VL53L0_Error status = VL53L0_ERROR_NONE;
|
||||||
|
uint8_t phaseSelect = 1;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
|
||||||
|
if (status == VL53L0_ERROR_NONE)
|
||||||
|
status = set_final_range_timeout_us(
|
||||||
|
dev, timeout_ms * 1000, final_range_vcsel_period_pclks);
|
||||||
|
|
||||||
|
if (status == VL53L0_ERROR_NONE)
|
||||||
|
status = VL53L0_SetDeviceMode(dev,
|
||||||
|
VL53L0_DEVICEMODE_SINGLE_HISTOGRAM);
|
||||||
|
|
||||||
|
|
||||||
|
if (status == VL53L0_ERROR_NONE)
|
||||||
|
status = VL53L0_SetHistogramMode(dev,
|
||||||
|
VL53L0_HISTOGRAMMODE_BOTH);
|
||||||
|
|
||||||
|
|
||||||
|
if (status == VL53L0_ERROR_NONE)
|
||||||
|
status = VL53L0_WrByte(dev, VL53L0_REG_SYSTEM_HISTOGRAM_BIN,
|
||||||
|
0x00);
|
||||||
|
|
||||||
|
|
||||||
|
/* Apply specific phase select for x-talk measurement */
|
||||||
|
if (status == VL53L0_ERROR_NONE)
|
||||||
|
status = VL53L0_WrByte(dev,
|
||||||
|
VL53L0_REG_HISTOGRAM_CONFIG_INITIAL_PHASE_SELECT,
|
||||||
|
phaseSelect);
|
||||||
|
|
||||||
|
|
||||||
|
LOG_FUNCTION_END(status);
|
||||||
|
|
||||||
|
return status;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_perform_xtalk_measurement(VL53L0_DEV dev,
|
||||||
|
uint32_t timeout_ms, FixPoint1616_t *pxtalk_per_spad,
|
||||||
|
uint8_t *pambient_too_high)
|
||||||
|
{
|
||||||
|
VL53L0_Error status = VL53L0_ERROR_NONE;
|
||||||
|
uint32_t signal_events = 0;
|
||||||
|
uint32_t amb_events = 0;
|
||||||
|
uint32_t meas_timing_budget_us;
|
||||||
|
VL53L0_DeviceModes device_mode;
|
||||||
|
uint8_t final_range_vcsel_period_pclks;
|
||||||
|
uint32_t max_spads;
|
||||||
|
|
||||||
|
/* Get Current DeviceMode */
|
||||||
|
status = VL53L0_GetDeviceMode(dev, &device_mode);
|
||||||
|
|
||||||
|
if (status == VL53L0_ERROR_NONE)
|
||||||
|
status = VL53L0_get_max_spads(dev, &max_spads,
|
||||||
|
pambient_too_high);
|
||||||
|
|
||||||
|
if (status != VL53L0_ERROR_NONE)
|
||||||
|
return status;
|
||||||
|
|
||||||
|
|
||||||
|
if (status == VL53L0_ERROR_NONE) {
|
||||||
|
status = VL53L0_GetVcselPulsePeriod(
|
||||||
|
dev,
|
||||||
|
VL53L0_VCSEL_PERIOD_FINAL_RANGE,
|
||||||
|
&final_range_vcsel_period_pclks);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (status == VL53L0_ERROR_NONE) {
|
||||||
|
if (final_range_vcsel_period_pclks < 10)
|
||||||
|
status = VL53L0_ERROR_INVALID_PARAMS;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (status == VL53L0_ERROR_NONE) {
|
||||||
|
perform_histogram_config(
|
||||||
|
dev, timeout_ms, final_range_vcsel_period_pclks);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (status == VL53L0_ERROR_NONE) {
|
||||||
|
status = perform_histo_signal_meas(
|
||||||
|
dev,
|
||||||
|
VL53L0_AMBIENT_WINDOW_ONLY,
|
||||||
|
&amb_events);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (status == VL53L0_ERROR_NONE) {
|
||||||
|
status = perform_histo_signal_meas(
|
||||||
|
dev,
|
||||||
|
VL53L0_AMBIENT_AND_SIGNAL_WINDOW,
|
||||||
|
&signal_events);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (status == VL53L0_ERROR_NONE) {
|
||||||
|
status = calc_xtalk_mcps_per_spad(
|
||||||
|
(signal_events - amb_events),
|
||||||
|
timeout_ms,
|
||||||
|
max_spads,
|
||||||
|
final_range_vcsel_period_pclks,
|
||||||
|
pxtalk_per_spad);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Revert previous device mode. */
|
||||||
|
if (status == VL53L0_ERROR_NONE)
|
||||||
|
status = VL53L0_SetDeviceMode(dev, device_mode);
|
||||||
|
|
||||||
|
/* Revert previous timing budget, to ensure previous final range vcsel
|
||||||
|
* period is applied.
|
||||||
|
*/
|
||||||
|
if (status == VL53L0_ERROR_NONE) {
|
||||||
|
VL53L0_GETPARAMETERFIELD(
|
||||||
|
dev,
|
||||||
|
MeasurementTimingBudgetMicroSeconds,
|
||||||
|
meas_timing_budget_us);
|
||||||
|
|
||||||
|
status = VL53L0_SetMeasurementTimingBudgetMicroSeconds(
|
||||||
|
dev, meas_timing_budget_us);
|
||||||
|
}
|
||||||
|
|
||||||
|
return status;
|
||||||
|
}
|
||||||
|
|
42
drivers/input/misc/vl53L0/src/vl53l0_api_ranging.c
Normal file
42
drivers/input/misc/vl53L0/src/vl53l0_api_ranging.c
Normal file
|
@ -0,0 +1,42 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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.
|
||||||
|
******************************************************************************/
|
||||||
|
|
||||||
|
#include "vl53l0_api.h"
|
||||||
|
#include "vl53l0_api_core.h"
|
||||||
|
|
||||||
|
|
||||||
|
#ifndef __KERNEL__
|
||||||
|
#include <stdlib.h>
|
||||||
|
#endif
|
||||||
|
#define LOG_FUNCTION_START(fmt, ...) \
|
||||||
|
_LOG_FUNCTION_START(TRACE_MODULE_API, fmt, ##__VA_ARGS__)
|
||||||
|
#define LOG_FUNCTION_END(status, ...) \
|
||||||
|
_LOG_FUNCTION_END(TRACE_MODULE_API, status, ##__VA_ARGS__)
|
||||||
|
#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
|
||||||
|
_LOG_FUNCTION_END_FMT(TRACE_MODULE_API, status, fmt, ##__VA_ARGS__)
|
||||||
|
|
463
drivers/input/misc/vl53L0/src/vl53l0_api_strings.c
Normal file
463
drivers/input/misc/vl53L0/src/vl53l0_api_strings.c
Normal file
|
@ -0,0 +1,463 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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.
|
||||||
|
******************************************************************************/
|
||||||
|
|
||||||
|
#include "vl53l0_api.h"
|
||||||
|
#include "vl53l0_api_core.h"
|
||||||
|
#include "vl53l0_api_strings.h"
|
||||||
|
|
||||||
|
#ifndef __KERNEL__
|
||||||
|
#include <stdlib.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define LOG_FUNCTION_START(fmt, ...) \
|
||||||
|
_LOG_FUNCTION_START(TRACE_MODULE_API, fmt, ##__VA_ARGS__)
|
||||||
|
#define LOG_FUNCTION_END(status, ...) \
|
||||||
|
_LOG_FUNCTION_END(TRACE_MODULE_API, status, ##__VA_ARGS__)
|
||||||
|
#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
|
||||||
|
_LOG_FUNCTION_END_FMT(TRACE_MODULE_API, status, fmt, ##__VA_ARGS__)
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_check_part_used(VL53L0_DEV Dev,
|
||||||
|
uint8_t *Revision,
|
||||||
|
VL53L0_DeviceInfo_t *pVL53L0_DeviceInfo)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
uint8_t ModuleIdInt;
|
||||||
|
char *ProductId_tmp;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
|
||||||
|
Status = VL53L0_get_info_from_device(Dev, 2);
|
||||||
|
|
||||||
|
if (Status == VL53L0_ERROR_NONE) {
|
||||||
|
ModuleIdInt = VL53L0_GETDEVICESPECIFICPARAMETER(Dev, ModuleId);
|
||||||
|
|
||||||
|
if (ModuleIdInt == 0) {
|
||||||
|
*Revision = 0;
|
||||||
|
VL53L0_COPYSTRING(pVL53L0_DeviceInfo->ProductId, "");
|
||||||
|
} else {
|
||||||
|
*Revision = VL53L0_GETDEVICESPECIFICPARAMETER(Dev, Revision);
|
||||||
|
ProductId_tmp = VL53L0_GETDEVICESPECIFICPARAMETER(Dev,
|
||||||
|
ProductId);
|
||||||
|
VL53L0_COPYSTRING(pVL53L0_DeviceInfo->ProductId, ProductId_tmp);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
LOG_FUNCTION_END(Status);
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_device_info(VL53L0_DEV Dev,
|
||||||
|
VL53L0_DeviceInfo_t *pVL53L0_DeviceInfo)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
uint8_t revision_id;
|
||||||
|
uint8_t Revision;
|
||||||
|
|
||||||
|
Status = VL53L0_check_part_used(Dev, &Revision, pVL53L0_DeviceInfo);
|
||||||
|
|
||||||
|
if (Status == VL53L0_ERROR_NONE) {
|
||||||
|
if (Revision == 0) {
|
||||||
|
VL53L0_COPYSTRING(pVL53L0_DeviceInfo->Name,
|
||||||
|
VL53L0_STRING_DEVICE_INFO_NAME_TS0);
|
||||||
|
} else if ((Revision <= 34) && (Revision != 32)) {
|
||||||
|
VL53L0_COPYSTRING(pVL53L0_DeviceInfo->Name,
|
||||||
|
VL53L0_STRING_DEVICE_INFO_NAME_TS1);
|
||||||
|
} else if (Revision < 39) {
|
||||||
|
VL53L0_COPYSTRING(pVL53L0_DeviceInfo->Name,
|
||||||
|
VL53L0_STRING_DEVICE_INFO_NAME_TS2);
|
||||||
|
} else {
|
||||||
|
VL53L0_COPYSTRING(pVL53L0_DeviceInfo->Name,
|
||||||
|
VL53L0_STRING_DEVICE_INFO_NAME_ES1);
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_COPYSTRING(pVL53L0_DeviceInfo->Type,
|
||||||
|
VL53L0_STRING_DEVICE_INFO_TYPE);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (Status == VL53L0_ERROR_NONE) {
|
||||||
|
Status = VL53L0_RdByte(Dev, VL53L0_REG_IDENTIFICATION_MODEL_ID,
|
||||||
|
&pVL53L0_DeviceInfo->ProductType);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (Status == VL53L0_ERROR_NONE) {
|
||||||
|
Status = VL53L0_RdByte(Dev,
|
||||||
|
VL53L0_REG_IDENTIFICATION_REVISION_ID,
|
||||||
|
&revision_id);
|
||||||
|
pVL53L0_DeviceInfo->ProductRevisionMajor = 1;
|
||||||
|
pVL53L0_DeviceInfo->ProductRevisionMinor =
|
||||||
|
(revision_id & 0xF0) >> 4;
|
||||||
|
}
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_device_error_string(VL53L0_DeviceError ErrorCode,
|
||||||
|
char *pDeviceErrorString)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
|
||||||
|
switch (ErrorCode) {
|
||||||
|
case VL53L0_DEVICEERROR_NONE:
|
||||||
|
VL53L0_COPYSTRING(pDeviceErrorString,
|
||||||
|
VL53L0_STRING_DEVICEERROR_NONE);
|
||||||
|
break;
|
||||||
|
case VL53L0_DEVICEERROR_VCSELCONTINUITYTESTFAILURE:
|
||||||
|
VL53L0_COPYSTRING(pDeviceErrorString,
|
||||||
|
VL53L0_STRING_DEVICEERROR_VCSELCONTINUITYTESTFAILURE);
|
||||||
|
break;
|
||||||
|
case VL53L0_DEVICEERROR_VCSELWATCHDOGTESTFAILURE:
|
||||||
|
VL53L0_COPYSTRING(pDeviceErrorString,
|
||||||
|
VL53L0_STRING_DEVICEERROR_VCSELWATCHDOGTESTFAILURE);
|
||||||
|
break;
|
||||||
|
case VL53L0_DEVICEERROR_NOVHVVALUEFOUND:
|
||||||
|
VL53L0_COPYSTRING(pDeviceErrorString,
|
||||||
|
VL53L0_STRING_DEVICEERROR_NOVHVVALUEFOUND);
|
||||||
|
break;
|
||||||
|
case VL53L0_DEVICEERROR_MSRCNOTARGET:
|
||||||
|
VL53L0_COPYSTRING(pDeviceErrorString,
|
||||||
|
VL53L0_STRING_DEVICEERROR_MSRCNOTARGET);
|
||||||
|
break;
|
||||||
|
case VL53L0_DEVICEERROR_SNRCHECK:
|
||||||
|
VL53L0_COPYSTRING(pDeviceErrorString,
|
||||||
|
VL53L0_STRING_DEVICEERROR_SNRCHECK);
|
||||||
|
break;
|
||||||
|
case VL53L0_DEVICEERROR_RANGEPHASECHECK:
|
||||||
|
VL53L0_COPYSTRING(pDeviceErrorString,
|
||||||
|
VL53L0_STRING_DEVICEERROR_RANGEPHASECHECK);
|
||||||
|
break;
|
||||||
|
case VL53L0_DEVICEERROR_SIGMATHRESHOLDCHECK:
|
||||||
|
VL53L0_COPYSTRING(pDeviceErrorString,
|
||||||
|
VL53L0_STRING_DEVICEERROR_SIGMATHRESHOLDCHECK);
|
||||||
|
break;
|
||||||
|
case VL53L0_DEVICEERROR_TCC:
|
||||||
|
VL53L0_COPYSTRING(pDeviceErrorString,
|
||||||
|
VL53L0_STRING_DEVICEERROR_TCC);
|
||||||
|
break;
|
||||||
|
case VL53L0_DEVICEERROR_PHASECONSISTENCY:
|
||||||
|
VL53L0_COPYSTRING(pDeviceErrorString,
|
||||||
|
VL53L0_STRING_DEVICEERROR_PHASECONSISTENCY);
|
||||||
|
break;
|
||||||
|
case VL53L0_DEVICEERROR_MINCLIP:
|
||||||
|
VL53L0_COPYSTRING(pDeviceErrorString,
|
||||||
|
VL53L0_STRING_DEVICEERROR_MINCLIP);
|
||||||
|
break;
|
||||||
|
case VL53L0_DEVICEERROR_RANGECOMPLETE:
|
||||||
|
VL53L0_COPYSTRING(pDeviceErrorString,
|
||||||
|
VL53L0_STRING_DEVICEERROR_RANGECOMPLETE);
|
||||||
|
break;
|
||||||
|
case VL53L0_DEVICEERROR_ALGOUNDERFLOW:
|
||||||
|
VL53L0_COPYSTRING(pDeviceErrorString,
|
||||||
|
VL53L0_STRING_DEVICEERROR_ALGOUNDERFLOW);
|
||||||
|
break;
|
||||||
|
case VL53L0_DEVICEERROR_ALGOOVERFLOW:
|
||||||
|
VL53L0_COPYSTRING(pDeviceErrorString,
|
||||||
|
VL53L0_STRING_DEVICEERROR_ALGOOVERFLOW);
|
||||||
|
break;
|
||||||
|
case VL53L0_DEVICEERROR_RANGEIGNORETHRESHOLD:
|
||||||
|
VL53L0_COPYSTRING(pDeviceErrorString,
|
||||||
|
VL53L0_STRING_DEVICEERROR_RANGEIGNORETHRESHOLD);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
VL53L0_COPYSTRING(pDeviceErrorString,
|
||||||
|
VL53L0_STRING_UNKNOW_ERROR_CODE);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
LOG_FUNCTION_END(Status);
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_range_status_string(uint8_t RangeStatus,
|
||||||
|
char *pRangeStatusString)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
|
||||||
|
switch (RangeStatus) {
|
||||||
|
case 0:
|
||||||
|
VL53L0_COPYSTRING(pRangeStatusString,
|
||||||
|
VL53L0_STRING_RANGESTATUS_RANGEVALID);
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
VL53L0_COPYSTRING(pRangeStatusString,
|
||||||
|
VL53L0_STRING_RANGESTATUS_SIGMA);
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
VL53L0_COPYSTRING(pRangeStatusString,
|
||||||
|
VL53L0_STRING_RANGESTATUS_SIGNAL);
|
||||||
|
break;
|
||||||
|
case 3:
|
||||||
|
VL53L0_COPYSTRING(pRangeStatusString,
|
||||||
|
VL53L0_STRING_RANGESTATUS_MINRANGE);
|
||||||
|
break;
|
||||||
|
case 4:
|
||||||
|
VL53L0_COPYSTRING(pRangeStatusString,
|
||||||
|
VL53L0_STRING_RANGESTATUS_PHASE);
|
||||||
|
break;
|
||||||
|
case 5:
|
||||||
|
VL53L0_COPYSTRING(pRangeStatusString,
|
||||||
|
VL53L0_STRING_RANGESTATUS_HW);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default: /**/
|
||||||
|
VL53L0_COPYSTRING(pRangeStatusString,
|
||||||
|
VL53L0_STRING_RANGESTATUS_NONE);
|
||||||
|
}
|
||||||
|
|
||||||
|
LOG_FUNCTION_END(Status);
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_pal_error_string(VL53L0_Error PalErrorCode,
|
||||||
|
char *pPalErrorString)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
|
||||||
|
switch (PalErrorCode) {
|
||||||
|
case VL53L0_ERROR_NONE:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_NONE);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_CALIBRATION_WARNING:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_CALIBRATION_WARNING);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_MIN_CLIPPED:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_MIN_CLIPPED);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_UNDEFINED:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_UNDEFINED);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_INVALID_PARAMS:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_INVALID_PARAMS);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_NOT_SUPPORTED:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_NOT_SUPPORTED);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_INTERRUPT_NOT_CLEARED:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_INTERRUPT_NOT_CLEARED);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_RANGE_ERROR:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_RANGE_ERROR);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_TIME_OUT:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_TIME_OUT);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_MODE_NOT_SUPPORTED:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_MODE_NOT_SUPPORTED);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_BUFFER_TOO_SMALL:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_BUFFER_TOO_SMALL);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_GPIO_NOT_EXISTING:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_GPIO_NOT_EXISTING);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_CONTROL_INTERFACE:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_CONTROL_INTERFACE);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_INVALID_COMMAND:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_INVALID_COMMAND);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_DIVISION_BY_ZERO:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_DIVISION_BY_ZERO);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_REF_SPAD_INIT:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_REF_SPAD_INIT);
|
||||||
|
break;
|
||||||
|
case VL53L0_ERROR_NOT_IMPLEMENTED:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_ERROR_NOT_IMPLEMENTED);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
VL53L0_COPYSTRING(pPalErrorString,
|
||||||
|
VL53L0_STRING_UNKNOW_ERROR_CODE);
|
||||||
|
}
|
||||||
|
|
||||||
|
LOG_FUNCTION_END(Status);
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_pal_state_string(VL53L0_State PalStateCode,
|
||||||
|
char *pPalStateString)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
|
||||||
|
switch (PalStateCode) {
|
||||||
|
case VL53L0_STATE_POWERDOWN:
|
||||||
|
VL53L0_COPYSTRING(pPalStateString,
|
||||||
|
VL53L0_STRING_STATE_POWERDOWN);
|
||||||
|
break;
|
||||||
|
case VL53L0_STATE_WAIT_STATICINIT:
|
||||||
|
VL53L0_COPYSTRING(pPalStateString,
|
||||||
|
VL53L0_STRING_STATE_WAIT_STATICINIT);
|
||||||
|
break;
|
||||||
|
case VL53L0_STATE_STANDBY:
|
||||||
|
VL53L0_COPYSTRING(pPalStateString,
|
||||||
|
VL53L0_STRING_STATE_STANDBY);
|
||||||
|
break;
|
||||||
|
case VL53L0_STATE_IDLE:
|
||||||
|
VL53L0_COPYSTRING(pPalStateString,
|
||||||
|
VL53L0_STRING_STATE_IDLE);
|
||||||
|
break;
|
||||||
|
case VL53L0_STATE_RUNNING:
|
||||||
|
VL53L0_COPYSTRING(pPalStateString,
|
||||||
|
VL53L0_STRING_STATE_RUNNING);
|
||||||
|
break;
|
||||||
|
case VL53L0_STATE_UNKNOWN:
|
||||||
|
VL53L0_COPYSTRING(pPalStateString,
|
||||||
|
VL53L0_STRING_STATE_UNKNOWN);
|
||||||
|
break;
|
||||||
|
case VL53L0_STATE_ERROR:
|
||||||
|
VL53L0_COPYSTRING(pPalStateString,
|
||||||
|
VL53L0_STRING_STATE_ERROR);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
VL53L0_COPYSTRING(pPalStateString,
|
||||||
|
VL53L0_STRING_STATE_UNKNOWN);
|
||||||
|
}
|
||||||
|
|
||||||
|
LOG_FUNCTION_END(Status);
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_sequence_steps_info(
|
||||||
|
VL53L0_SequenceStepId SequenceStepId,
|
||||||
|
char *pSequenceStepsString)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
|
||||||
|
switch (SequenceStepId) {
|
||||||
|
case VL53L0_SEQUENCESTEP_TCC:
|
||||||
|
VL53L0_COPYSTRING(pSequenceStepsString,
|
||||||
|
VL53L0_STRING_SEQUENCESTEP_TCC);
|
||||||
|
break;
|
||||||
|
case VL53L0_SEQUENCESTEP_DSS:
|
||||||
|
VL53L0_COPYSTRING(pSequenceStepsString,
|
||||||
|
VL53L0_STRING_SEQUENCESTEP_DSS);
|
||||||
|
break;
|
||||||
|
case VL53L0_SEQUENCESTEP_MSRC:
|
||||||
|
VL53L0_COPYSTRING(pSequenceStepsString,
|
||||||
|
VL53L0_STRING_SEQUENCESTEP_MSRC);
|
||||||
|
break;
|
||||||
|
case VL53L0_SEQUENCESTEP_PRE_RANGE:
|
||||||
|
VL53L0_COPYSTRING(pSequenceStepsString,
|
||||||
|
VL53L0_STRING_SEQUENCESTEP_PRE_RANGE);
|
||||||
|
break;
|
||||||
|
case VL53L0_SEQUENCESTEP_FINAL_RANGE:
|
||||||
|
VL53L0_COPYSTRING(pSequenceStepsString,
|
||||||
|
VL53L0_STRING_SEQUENCESTEP_FINAL_RANGE);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
Status = VL53L0_ERROR_INVALID_PARAMS;
|
||||||
|
}
|
||||||
|
|
||||||
|
LOG_FUNCTION_END(Status);
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_get_limit_check_info(VL53L0_DEV Dev, uint16_t LimitCheckId,
|
||||||
|
char *pLimitCheckString)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
|
||||||
|
switch (LimitCheckId) {
|
||||||
|
case VL53L0_CHECKENABLE_SIGMA_FINAL_RANGE:
|
||||||
|
VL53L0_COPYSTRING(pLimitCheckString,
|
||||||
|
VL53L0_STRING_CHECKENABLE_SIGMA_FINAL_RANGE);
|
||||||
|
break;
|
||||||
|
case VL53L0_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE:
|
||||||
|
VL53L0_COPYSTRING(pLimitCheckString,
|
||||||
|
VL53L0_STRING_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE);
|
||||||
|
break;
|
||||||
|
case VL53L0_CHECKENABLE_SIGNAL_REF_CLIP:
|
||||||
|
VL53L0_COPYSTRING(pLimitCheckString,
|
||||||
|
VL53L0_STRING_CHECKENABLE_SIGNAL_REF_CLIP);
|
||||||
|
break;
|
||||||
|
case VL53L0_CHECKENABLE_RANGE_IGNORE_THRESHOLD:
|
||||||
|
VL53L0_COPYSTRING(pLimitCheckString,
|
||||||
|
VL53L0_STRING_CHECKENABLE_RANGE_IGNORE_THRESHOLD);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case VL53L0_CHECKENABLE_SIGNAL_RATE_MSRC:
|
||||||
|
VL53L0_COPYSTRING(pLimitCheckString,
|
||||||
|
VL53L0_STRING_CHECKENABLE_SIGNAL_RATE_MSRC);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case VL53L0_CHECKENABLE_SIGNAL_RATE_PRE_RANGE:
|
||||||
|
VL53L0_COPYSTRING(pLimitCheckString,
|
||||||
|
VL53L0_STRING_CHECKENABLE_SIGNAL_RATE_PRE_RANGE);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
VL53L0_COPYSTRING(pLimitCheckString,
|
||||||
|
VL53L0_STRING_UNKNOW_ERROR_CODE);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
LOG_FUNCTION_END(Status);
|
||||||
|
return Status;
|
||||||
|
}
|
383
drivers/input/misc/vl53L0/src/vl53l0_i2c_platform.c
Normal file
383
drivers/input/misc/vl53L0/src/vl53l0_i2c_platform.c
Normal file
|
@ -0,0 +1,383 @@
|
||||||
|
/*
|
||||||
|
* Copyright (C) 2016 STMicroelectronics Imaging Division.
|
||||||
|
*
|
||||||
|
* This program is free software; you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation; either version 2 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \file VL53L0_i2c_platform.c
|
||||||
|
* \brief Code function defintions for EWOK Platform Layer
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
#include <linux/i2c.h>
|
||||||
|
#include <linux/module.h>
|
||||||
|
#include <linux/delay.h>
|
||||||
|
#include "stmvl53l0-i2c.h"
|
||||||
|
#include "stmvl53l0-cci.h"
|
||||||
|
|
||||||
|
#include "vl53l0_platform.h"
|
||||||
|
#include "vl53l0_i2c_platform.h"
|
||||||
|
#include "vl53l0_def.h"
|
||||||
|
|
||||||
|
#include "vl53l0_platform_log.h"
|
||||||
|
|
||||||
|
#ifdef VL53L0_LOG_ENABLE
|
||||||
|
#define trace_print(level, ...) \
|
||||||
|
trace_print_module_function(TRACE_MODULE_PLATFORM, level,\
|
||||||
|
TRACE_FUNCTION_NONE, ##__VA_ARGS__)
|
||||||
|
#define trace_i2c(...) \
|
||||||
|
trace_print_module_function(TRACE_MODULE_NONE, \
|
||||||
|
TRACE_LEVEL_NONE, TRACE_FUNCTION_I2C, ##__VA_ARGS__)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @def I2C_BUFFER_CONFIG
|
||||||
|
*
|
||||||
|
* @brief Configure Device register I2C access
|
||||||
|
*
|
||||||
|
* @li 0 : one GLOBAL buffer \n
|
||||||
|
* Use one global buffer of MAX_I2C_XFER_SIZE byte in data space \n
|
||||||
|
* This solution is not multi-Device compliant nor multi-thread cpu safe \n
|
||||||
|
* It can be the best option for small 8/16 bit MCU without stack and limited
|
||||||
|
* ram (STM8s, 80C51 ...)
|
||||||
|
*
|
||||||
|
* @li 1 : ON_STACK/local \n
|
||||||
|
* Use local variable (on stack) buffer \n
|
||||||
|
* This solution is multi-thread with use of i2c resource lock or mutex see
|
||||||
|
* VL6180x_GetI2CAccess() \n
|
||||||
|
*
|
||||||
|
* @li 2 : User defined \n
|
||||||
|
* Per Device potentially dynamic allocated. Requires VL6180x_GetI2cBuffer()
|
||||||
|
* to be implemented.
|
||||||
|
* @ingroup Configuration
|
||||||
|
*/
|
||||||
|
#define I2C_BUFFER_CONFIG 1
|
||||||
|
|
||||||
|
#if I2C_BUFFER_CONFIG == 0
|
||||||
|
/* GLOBAL config buffer */
|
||||||
|
uint8_t i2c_global_buffer[VL53L0_MAX_I2C_XFER_SIZE];
|
||||||
|
|
||||||
|
#define DECL_I2C_BUFFER
|
||||||
|
#define VL53L0_GetLocalBuffer(Dev, n_byte) i2c_global_buffer
|
||||||
|
|
||||||
|
#elif I2C_BUFFER_CONFIG == 1
|
||||||
|
/* ON STACK */
|
||||||
|
uint8_t LocBuffer[VL53L0_MAX_I2C_XFER_SIZE];
|
||||||
|
#define VL53L0_GetLocalBuffer(Dev, n_byte) LocBuffer
|
||||||
|
#elif I2C_BUFFER_CONFIG == 2
|
||||||
|
/* user define buffer type declare DECL_I2C_BUFFER as access via
|
||||||
|
* VL53L0_GetLocalBuffer
|
||||||
|
*/
|
||||||
|
#define DECL_I2C_BUFFER
|
||||||
|
#else
|
||||||
|
#error "invalid I2C_BUFFER_CONFIG "
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
/* none but could be for a flag var to
|
||||||
|
* get/pass to mutex interruptible return flags and try again
|
||||||
|
*/
|
||||||
|
#define VL53L0_I2C_USER_VAR
|
||||||
|
#define VL53L0_GetI2CAccess(Dev) /* todo mutex acquire */
|
||||||
|
#define VL53L0_DoneI2CAcces(Dev) /* todo mutex release */
|
||||||
|
|
||||||
|
|
||||||
|
char debug_string[VL53L0_MAX_STRING_LENGTH_PLT];
|
||||||
|
|
||||||
|
|
||||||
|
#define MIN_COMMS_VERSION_MAJOR 1
|
||||||
|
#define MIN_COMMS_VERSION_MINOR 8
|
||||||
|
#define MIN_COMMS_VERSION_BUILD 1
|
||||||
|
#define MIN_COMMS_VERSION_REVISION 0
|
||||||
|
|
||||||
|
#define STATUS_OK 0x00
|
||||||
|
#define STATUS_FAIL 0x01
|
||||||
|
|
||||||
|
bool_t _check_min_version(void)
|
||||||
|
{
|
||||||
|
bool_t min_version_comms_dll = false;
|
||||||
|
|
||||||
|
min_version_comms_dll = true;
|
||||||
|
|
||||||
|
return min_version_comms_dll;
|
||||||
|
}
|
||||||
|
|
||||||
|
int32_t VL53L0_comms_initialise(uint8_t comms_type, uint16_t comms_speed_khz)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
|
||||||
|
return status;
|
||||||
|
}
|
||||||
|
|
||||||
|
int32_t VL53L0_comms_close(void)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
|
||||||
|
|
||||||
|
return status;
|
||||||
|
}
|
||||||
|
|
||||||
|
int32_t VL53L0_set_page(VL53L0_DEV dev, uint8_t page_data)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
uint16_t page_index = 0xFF;
|
||||||
|
uint8_t *buffer;
|
||||||
|
|
||||||
|
buffer = VL53L0_GetLocalBuffer(dev, 3);
|
||||||
|
buffer[0] = page_index >> 8;
|
||||||
|
buffer[1] = page_index & 0xff;
|
||||||
|
buffer[2] = page_data;
|
||||||
|
|
||||||
|
status = VL53L0_I2CWrite(dev, buffer, (uint8_t) 3);
|
||||||
|
return status;
|
||||||
|
}
|
||||||
|
|
||||||
|
int32_t VL53L0_write_multi(VL53L0_DEV dev, uint8_t index, uint8_t *pdata,
|
||||||
|
int32_t count)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
uint8_t *buffer;
|
||||||
|
|
||||||
|
#ifdef VL53L0_LOG_ENABLE
|
||||||
|
int32_t i = 0;
|
||||||
|
char value_as_str[VL53L0_MAX_STRING_LENGTH_PLT];
|
||||||
|
char *pvalue_as_str;
|
||||||
|
|
||||||
|
pvalue_as_str = value_as_str;
|
||||||
|
|
||||||
|
for (i = 0 ; i < count ; i++) {
|
||||||
|
snprintf(pvalue_as_str, sizeof(pvalue_as_str),
|
||||||
|
"%02X", *(pdata + i));
|
||||||
|
|
||||||
|
pvalue_as_str += 2;
|
||||||
|
}
|
||||||
|
trace_i2c("Write reg : 0x%04X, Val : 0x%s\n", index, value_as_str);
|
||||||
|
#endif
|
||||||
|
if ((count + 1) > VL53L0_MAX_I2C_XFER_SIZE)
|
||||||
|
return STATUS_FAIL;
|
||||||
|
buffer = VL53L0_GetLocalBuffer(dev, (count+1));
|
||||||
|
buffer[0] = index;
|
||||||
|
memcpy(&buffer[1], pdata, count);
|
||||||
|
status = VL53L0_I2CWrite(dev, buffer, (count+1));
|
||||||
|
|
||||||
|
return status;
|
||||||
|
}
|
||||||
|
|
||||||
|
int32_t VL53L0_read_multi(VL53L0_DEV dev, uint8_t index, uint8_t *pdata,
|
||||||
|
int32_t count)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
uint8_t *buffer;
|
||||||
|
|
||||||
|
#ifdef VL53L0_LOG_ENABLE
|
||||||
|
int32_t i = 0;
|
||||||
|
char value_as_str[VL53L0_MAX_STRING_LENGTH_PLT];
|
||||||
|
char *pvalue_as_str;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if ((count + 1) > VL53L0_MAX_I2C_XFER_SIZE)
|
||||||
|
return STATUS_FAIL;
|
||||||
|
|
||||||
|
buffer = VL53L0_GetLocalBuffer(dev, 1);
|
||||||
|
buffer[0] = index;
|
||||||
|
status = VL53L0_I2CWrite(dev, (uint8_t *)buffer, (uint8_t)1);
|
||||||
|
if (!status) {
|
||||||
|
pdata[0] = index;
|
||||||
|
status = VL53L0_I2CRead(dev, pdata, count);
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef VL53L0_LOG_ENABLE
|
||||||
|
pvalue_as_str = value_as_str;
|
||||||
|
|
||||||
|
for (i = 0 ; i < count ; i++) {
|
||||||
|
snprintf(pvalue_as_str, sizeof(value_as_str),
|
||||||
|
"%02X", *(pdata+i));
|
||||||
|
pvalue_as_str += 2;
|
||||||
|
}
|
||||||
|
|
||||||
|
trace_i2c("Read reg : 0x%04X, Val : 0x%s\n", index, value_as_str);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return status;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int32_t VL53L0_write_byte(VL53L0_DEV dev, uint8_t index, uint8_t data)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
const int32_t cbyte_count = 1;
|
||||||
|
|
||||||
|
status = VL53L0_write_multi(dev, index, &data, cbyte_count);
|
||||||
|
|
||||||
|
return status;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int32_t VL53L0_write_word(VL53L0_DEV dev, uint8_t index, uint16_t data)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
|
||||||
|
uint8_t buffer[BYTES_PER_WORD];
|
||||||
|
|
||||||
|
/* Split 16-bit word into MS and LS uint8_t */
|
||||||
|
buffer[0] = (uint8_t)(data >> 8);
|
||||||
|
buffer[1] = (uint8_t)(data & 0x00FF);
|
||||||
|
|
||||||
|
status = VL53L0_write_multi(dev, index, buffer, BYTES_PER_WORD);
|
||||||
|
|
||||||
|
return status;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int32_t VL53L0_write_dword(VL53L0_DEV dev, uint8_t index, uint32_t data)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
uint8_t buffer[BYTES_PER_DWORD];
|
||||||
|
|
||||||
|
/* Split 32-bit word into MS ... LS bytes */
|
||||||
|
buffer[0] = (uint8_t) (data >> 24);
|
||||||
|
buffer[1] = (uint8_t)((data & 0x00FF0000) >> 16);
|
||||||
|
buffer[2] = (uint8_t)((data & 0x0000FF00) >> 8);
|
||||||
|
buffer[3] = (uint8_t) (data & 0x000000FF);
|
||||||
|
|
||||||
|
status = VL53L0_write_multi(dev, index, buffer, BYTES_PER_DWORD);
|
||||||
|
|
||||||
|
return status;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int32_t VL53L0_read_byte(VL53L0_DEV dev, uint8_t index, uint8_t *pdata)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
int32_t cbyte_count = 1;
|
||||||
|
|
||||||
|
status = VL53L0_read_multi(dev, index, pdata, cbyte_count);
|
||||||
|
|
||||||
|
return status;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int32_t VL53L0_read_word(VL53L0_DEV dev, uint8_t index, uint16_t *pdata)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
uint8_t buffer[BYTES_PER_WORD];
|
||||||
|
|
||||||
|
status = VL53L0_read_multi(dev, index, buffer, BYTES_PER_WORD);
|
||||||
|
*pdata = ((uint16_t)buffer[0]<<8) + (uint16_t)buffer[1];
|
||||||
|
|
||||||
|
return status;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
int32_t VL53L0_read_dword(VL53L0_DEV dev, uint8_t index, uint32_t *pdata)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
uint8_t buffer[BYTES_PER_DWORD];
|
||||||
|
|
||||||
|
status = VL53L0_read_multi(dev, index, buffer, BYTES_PER_DWORD);
|
||||||
|
*pdata = ((uint32_t)buffer[0]<<24) + ((uint32_t)buffer[1]<<16) +
|
||||||
|
((uint32_t)buffer[2]<<8) + (uint32_t)buffer[3];
|
||||||
|
|
||||||
|
return status;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
int32_t VL53L0_platform_wait_us(int32_t wait_us)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
|
||||||
|
msleep((wait_us/1000));
|
||||||
|
|
||||||
|
#ifdef VL53L0_LOG_ENABLE
|
||||||
|
trace_i2c("Wait us : %6d\n", wait_us);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return status;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int32_t VL53L0_wait_ms(int32_t wait_ms)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
|
||||||
|
msleep(wait_ms);
|
||||||
|
|
||||||
|
#ifdef VL53L0_LOG_ENABLE
|
||||||
|
trace_i2c("Wait ms : %6d\n", wait_ms);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return status;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int32_t VL53L0_set_gpio(uint8_t level)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
#ifdef VL53L0_LOG_ENABLE
|
||||||
|
trace_i2c("// Set GPIO = %d;\n", level);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return status;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int32_t VL53L0_get_gpio(uint8_t *plevel)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
#ifdef VL53L0_LOG_ENABLE
|
||||||
|
trace_i2c("// Get GPIO = %d;\n", *plevel);
|
||||||
|
#endif
|
||||||
|
return status;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int32_t VL53L0_release_gpio(void)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
#ifdef VL53L0_LOG_ENABLE
|
||||||
|
trace_i2c("// Releasing force on GPIO\n");
|
||||||
|
#endif
|
||||||
|
return status;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
int32_t VL53L0_cycle_power(void)
|
||||||
|
{
|
||||||
|
int32_t status = STATUS_OK;
|
||||||
|
#ifdef VL53L0_LOG_ENABLE
|
||||||
|
trace_i2c("// cycle sensor power\n");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return status;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int32_t VL53L0_get_timer_frequency(int32_t *ptimer_freq_hz)
|
||||||
|
{
|
||||||
|
*ptimer_freq_hz = 0;
|
||||||
|
return STATUS_FAIL;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
int32_t VL53L0_get_timer_value(int32_t *ptimer_count)
|
||||||
|
{
|
||||||
|
*ptimer_count = 0;
|
||||||
|
return STATUS_FAIL;
|
||||||
|
}
|
242
drivers/input/misc/vl53L0/src/vl53l0_platform.c
Normal file
242
drivers/input/misc/vl53L0/src/vl53l0_platform.c
Normal file
|
@ -0,0 +1,242 @@
|
||||||
|
/*******************************************************************************
|
||||||
|
* Copyright © 2016, 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.
|
||||||
|
*******************************************************************************/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @file VL53L0_i2c.c
|
||||||
|
*
|
||||||
|
* Copyright (C) 2014 ST MicroElectronics
|
||||||
|
*
|
||||||
|
* provide variable word size byte/Word/dword VL6180x register access via i2c
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
#include "vl53l0_platform.h"
|
||||||
|
#include "vl53l0_i2c_platform.h"
|
||||||
|
#include "vl53l0_api.h"
|
||||||
|
|
||||||
|
#define LOG_FUNCTION_START(fmt, ...) \
|
||||||
|
_LOG_FUNCTION_START(TRACE_MODULE_PLATFORM, fmt, ##__VA_ARGS__)
|
||||||
|
#define LOG_FUNCTION_END(status, ...) \
|
||||||
|
_LOG_FUNCTION_END(TRACE_MODULE_PLATFORM, status, ##__VA_ARGS__)
|
||||||
|
#define LOG_FUNCTION_END_FMT(status, fmt, ...)\
|
||||||
|
_LOG_FUNCTION_END_FMT(TRACE_MODULE_PLATFORM, status,\
|
||||||
|
fmt, ##__VA_ARGS__)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_LockSequenceAccess(VL53L0_DEV Dev)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_UnlockSequenceAccess(VL53L0_DEV Dev)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* the ranging_sensor_comms.dll will take care of the page selection */
|
||||||
|
VL53L0_Error VL53L0_WriteMulti(VL53L0_DEV Dev, uint8_t index,
|
||||||
|
uint8_t *pdata, uint32_t count)
|
||||||
|
{
|
||||||
|
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
int32_t status_int = 0;
|
||||||
|
uint8_t deviceAddress;
|
||||||
|
|
||||||
|
if (count >= VL53L0_MAX_I2C_XFER_SIZE)
|
||||||
|
Status = VL53L0_ERROR_INVALID_PARAMS;
|
||||||
|
|
||||||
|
|
||||||
|
deviceAddress = Dev->I2cDevAddr;
|
||||||
|
|
||||||
|
status_int = VL53L0_write_multi(Dev, index, pdata, count);
|
||||||
|
|
||||||
|
if (status_int != 0)
|
||||||
|
Status = VL53L0_ERROR_CONTROL_INTERFACE;
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* the ranging_sensor_comms.dll will take care of the page selection */
|
||||||
|
VL53L0_Error VL53L0_ReadMulti(VL53L0_DEV Dev, uint8_t index,
|
||||||
|
uint8_t *pdata, uint32_t count)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
int32_t status_int;
|
||||||
|
uint8_t deviceAddress;
|
||||||
|
|
||||||
|
if (count >= VL53L0_MAX_I2C_XFER_SIZE)
|
||||||
|
Status = VL53L0_ERROR_INVALID_PARAMS;
|
||||||
|
|
||||||
|
|
||||||
|
deviceAddress = Dev->I2cDevAddr;
|
||||||
|
|
||||||
|
status_int = VL53L0_read_multi(Dev, index, pdata, count);
|
||||||
|
|
||||||
|
if (status_int != 0)
|
||||||
|
Status = VL53L0_ERROR_CONTROL_INTERFACE;
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_WrByte(VL53L0_DEV Dev, uint8_t index, uint8_t data)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
int32_t status_int;
|
||||||
|
uint8_t deviceAddress;
|
||||||
|
|
||||||
|
deviceAddress = Dev->I2cDevAddr;
|
||||||
|
|
||||||
|
status_int = VL53L0_write_byte(Dev, index, data);
|
||||||
|
|
||||||
|
if (status_int != 0)
|
||||||
|
Status = VL53L0_ERROR_CONTROL_INTERFACE;
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_WrWord(VL53L0_DEV Dev, uint8_t index, uint16_t data)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
int32_t status_int;
|
||||||
|
uint8_t deviceAddress;
|
||||||
|
|
||||||
|
deviceAddress = Dev->I2cDevAddr;
|
||||||
|
|
||||||
|
status_int = VL53L0_write_word(Dev, index, data);
|
||||||
|
|
||||||
|
if (status_int != 0)
|
||||||
|
Status = VL53L0_ERROR_CONTROL_INTERFACE;
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_WrDWord(VL53L0_DEV Dev, uint8_t index, uint32_t data)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
int32_t status_int;
|
||||||
|
uint8_t deviceAddress;
|
||||||
|
|
||||||
|
deviceAddress = Dev->I2cDevAddr;
|
||||||
|
|
||||||
|
status_int = VL53L0_write_dword(Dev, index, data);
|
||||||
|
|
||||||
|
if (status_int != 0)
|
||||||
|
Status = VL53L0_ERROR_CONTROL_INTERFACE;
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_UpdateByte(VL53L0_DEV Dev, uint8_t index,
|
||||||
|
uint8_t AndData, uint8_t OrData)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
int32_t status_int;
|
||||||
|
uint8_t deviceAddress;
|
||||||
|
uint8_t data;
|
||||||
|
|
||||||
|
deviceAddress = Dev->I2cDevAddr;
|
||||||
|
|
||||||
|
status_int = VL53L0_read_byte(Dev, index, &data);
|
||||||
|
|
||||||
|
if (status_int != 0)
|
||||||
|
Status = VL53L0_ERROR_CONTROL_INTERFACE;
|
||||||
|
|
||||||
|
if (Status == VL53L0_ERROR_NONE) {
|
||||||
|
data = (data & AndData) | OrData;
|
||||||
|
status_int = VL53L0_write_byte(Dev, index, data);
|
||||||
|
|
||||||
|
if (status_int != 0)
|
||||||
|
Status = VL53L0_ERROR_CONTROL_INTERFACE;
|
||||||
|
}
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_RdByte(VL53L0_DEV Dev, uint8_t index, uint8_t *data)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
int32_t status_int;
|
||||||
|
uint8_t deviceAddress;
|
||||||
|
|
||||||
|
deviceAddress = Dev->I2cDevAddr;
|
||||||
|
|
||||||
|
status_int = VL53L0_read_byte(Dev, index, data);
|
||||||
|
|
||||||
|
if (status_int != 0)
|
||||||
|
Status = VL53L0_ERROR_CONTROL_INTERFACE;
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_RdWord(VL53L0_DEV Dev, uint8_t index, uint16_t *data)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
int32_t status_int;
|
||||||
|
uint8_t deviceAddress;
|
||||||
|
|
||||||
|
deviceAddress = Dev->I2cDevAddr;
|
||||||
|
|
||||||
|
status_int = VL53L0_read_word(Dev, index, data);
|
||||||
|
|
||||||
|
if (status_int != 0)
|
||||||
|
Status = VL53L0_ERROR_CONTROL_INTERFACE;
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
VL53L0_Error VL53L0_RdDWord(VL53L0_DEV Dev, uint8_t index, uint32_t *data)
|
||||||
|
{
|
||||||
|
VL53L0_Error Status = VL53L0_ERROR_NONE;
|
||||||
|
int32_t status_int;
|
||||||
|
uint8_t deviceAddress;
|
||||||
|
|
||||||
|
deviceAddress = Dev->I2cDevAddr;
|
||||||
|
|
||||||
|
status_int = VL53L0_read_dword(Dev, index, data);
|
||||||
|
|
||||||
|
if (status_int != 0)
|
||||||
|
Status = VL53L0_ERROR_CONTROL_INTERFACE;
|
||||||
|
|
||||||
|
return Status;
|
||||||
|
}
|
||||||
|
|
||||||
|
#define VL53L0_POLLINGDELAY_LOOPNB 250
|
||||||
|
VL53L0_Error VL53L0_PollingDelay(VL53L0_DEV Dev)
|
||||||
|
{
|
||||||
|
VL53L0_Error status = VL53L0_ERROR_NONE;
|
||||||
|
|
||||||
|
LOG_FUNCTION_START("");
|
||||||
|
usleep_range(950, 1000);
|
||||||
|
LOG_FUNCTION_END(status);
|
||||||
|
return status;
|
||||||
|
}
|
155
drivers/input/misc/vl53L0/src/vl53l0_port_i2c.c
Normal file
155
drivers/input/misc/vl53L0/src/vl53l0_port_i2c.c
Normal file
|
@ -0,0 +1,155 @@
|
||||||
|
/*
|
||||||
|
* vl53l0_port_i2c.c
|
||||||
|
*
|
||||||
|
* Created on: July, 2015
|
||||||
|
* Author: Teresa Tao
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <linux/i2c.h>
|
||||||
|
#include <linux/module.h>
|
||||||
|
#include "stmvl53l0-i2c.h"
|
||||||
|
#include "stmvl53l0-cci.h"
|
||||||
|
#include "vl53l0_platform.h"
|
||||||
|
#include "vl53l0_i2c_platform.h"
|
||||||
|
#include "stmvl53l0.h"
|
||||||
|
|
||||||
|
#define I2C_M_WR 0x00
|
||||||
|
#define STATUS_OK 0x00
|
||||||
|
#define STATUS_FAIL (-1)
|
||||||
|
/** int VL53L0_I2CWrite(VL53L0_Dev_t dev, void *buff, uint8_t len);
|
||||||
|
* @brief Write data buffer to VL53L0 device via i2c
|
||||||
|
* @param dev The device to write to
|
||||||
|
* @param buff The data buffer
|
||||||
|
* @param len The length of the transaction in byte
|
||||||
|
* @return 0 on success
|
||||||
|
*/
|
||||||
|
int VL53L0_I2CWrite(VL53L0_DEV dev, uint8_t *buff, uint8_t len)
|
||||||
|
{
|
||||||
|
int err = 0;
|
||||||
|
|
||||||
|
if (dev->bus_type == CCI_BUS) {
|
||||||
|
#ifdef CAMERA_CCI
|
||||||
|
uint16_t index;
|
||||||
|
struct cci_data *cci_client_obj =
|
||||||
|
(struct cci_data *)dev->client_object;
|
||||||
|
struct msm_camera_i2c_client *client = cci_client_obj->client;
|
||||||
|
|
||||||
|
index = buff[0];
|
||||||
|
/*pr_err("%s: index: %d len: %d\n", __func__, index, len); */
|
||||||
|
|
||||||
|
if (len == 2) {
|
||||||
|
uint8_t data;
|
||||||
|
|
||||||
|
data = buff[1];
|
||||||
|
/* for byte access */
|
||||||
|
err = client->i2c_func_tbl->i2c_write(client, index,
|
||||||
|
data, MSM_CAMERA_I2C_BYTE_DATA);
|
||||||
|
if (err < 0) {
|
||||||
|
pr_err("%s:%d failed status=%d\n",
|
||||||
|
__func__, __LINE__, err);
|
||||||
|
return err;
|
||||||
|
}
|
||||||
|
} else if (len == 3) {
|
||||||
|
uint16_t data;
|
||||||
|
|
||||||
|
data = ((uint16_t)buff[1] << 8) | (uint16_t)buff[2];
|
||||||
|
err = client->i2c_func_tbl->i2c_write(client, index,
|
||||||
|
data, MSM_CAMERA_I2C_WORD_DATA);
|
||||||
|
if (err < 0) {
|
||||||
|
pr_err("%s:%d failed status=%d\n",
|
||||||
|
__func__, __LINE__, err);
|
||||||
|
return err;
|
||||||
|
}
|
||||||
|
} else if (len >= 5) {
|
||||||
|
err = client->i2c_func_tbl->i2c_write_seq(client,
|
||||||
|
index, &buff[1], (len-1));
|
||||||
|
if (err < 0) {
|
||||||
|
pr_err("%s:%d failed status=%d\n",
|
||||||
|
__func__, __LINE__, err);
|
||||||
|
return err;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#ifndef CAMERA_CCI
|
||||||
|
} else {
|
||||||
|
struct i2c_msg msg[1];
|
||||||
|
struct i2c_data *i2c_client_obj =
|
||||||
|
(struct i2c_data *)dev->client_object;
|
||||||
|
struct i2c_client *client =
|
||||||
|
(struct i2c_client *)i2c_client_obj->client;
|
||||||
|
|
||||||
|
msg[0].addr = client->addr;
|
||||||
|
msg[0].flags = I2C_M_WR;
|
||||||
|
msg[0].buf = buff;
|
||||||
|
msg[0].len = len;
|
||||||
|
|
||||||
|
err = i2c_transfer(client->adapter, msg, 1);
|
||||||
|
/* return the actual messages transfer */
|
||||||
|
if (err != 1) {
|
||||||
|
pr_err("%s: i2c_transfer err:%d, addr:0x%x, reg:0x%x\n",
|
||||||
|
__func__, err, client->addr,
|
||||||
|
(buff[0] << 8 | buff[1]));
|
||||||
|
return STATUS_FAIL;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/** int VL53L0_I2CRead(VL53L0_Dev_t dev, void *buff, uint8_t len);
|
||||||
|
* @brief Read data buffer from VL53L0 device via i2c
|
||||||
|
* @param dev The device to read from
|
||||||
|
* @param buff The data buffer to fill
|
||||||
|
* @param len The length of the transaction in byte
|
||||||
|
* @return transaction status
|
||||||
|
*/
|
||||||
|
int VL53L0_I2CRead(VL53L0_DEV dev, uint8_t *buff, uint8_t len)
|
||||||
|
{
|
||||||
|
|
||||||
|
int err = 0;
|
||||||
|
|
||||||
|
if (dev->bus_type == CCI_BUS) {
|
||||||
|
#ifdef CAMERA_CCI
|
||||||
|
uint16_t index;
|
||||||
|
struct cci_data *cci_client_obj =
|
||||||
|
(struct cci_data *)dev->client_object;
|
||||||
|
struct msm_camera_i2c_client *client = cci_client_obj->client;
|
||||||
|
|
||||||
|
index = buff[0];
|
||||||
|
/* pr_err("%s: index: %d\n", __func__, index); */
|
||||||
|
err = client->i2c_func_tbl->i2c_read_seq(client,
|
||||||
|
index, buff, len);
|
||||||
|
if (err < 0) {
|
||||||
|
pr_err("%s:%d failed status=%d\n",
|
||||||
|
__func__, __LINE__, err);
|
||||||
|
return err;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
} else {
|
||||||
|
#ifndef CAMERA_CCI
|
||||||
|
struct i2c_msg msg[1];
|
||||||
|
struct i2c_data *i2c_client_obj =
|
||||||
|
(struct i2c_data *)dev->client_object;
|
||||||
|
struct i2c_client *client =
|
||||||
|
(struct i2c_client *) i2c_client_obj->client;
|
||||||
|
|
||||||
|
msg[0].addr = client->addr;
|
||||||
|
msg[0].flags = I2C_M_RD|client->flags;
|
||||||
|
msg[0].buf = buff;
|
||||||
|
msg[0].len = len;
|
||||||
|
|
||||||
|
err = i2c_transfer(client->adapter, &msg[0], 1);
|
||||||
|
/* return the actual mesage transfer */
|
||||||
|
if (err != 1) {
|
||||||
|
pr_err("%s: Read i2c_transfer err:%d, addr:0x%x\n",
|
||||||
|
__func__, err, client->addr);
|
||||||
|
return STATUS_FAIL;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
61
drivers/input/misc/vl53L0/stmvl53l0-cci.h
Normal file
61
drivers/input/misc/vl53L0/stmvl53l0-cci.h
Normal file
|
@ -0,0 +1,61 @@
|
||||||
|
/*
|
||||||
|
* stmvl53l0-cci.h - Linux kernel modules for STM VL53L0 FlightSense TOF sensor
|
||||||
|
*
|
||||||
|
* Copyright (C) 2016 STMicroelectronics Imaging Division
|
||||||
|
*
|
||||||
|
* This program is free software; you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation; either version 2 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*/
|
||||||
|
/*
|
||||||
|
* Defines
|
||||||
|
*/
|
||||||
|
#ifndef STMVL53L0_CCI_H
|
||||||
|
#define STMVL53L0_CCI_H
|
||||||
|
#include <linux/types.h>
|
||||||
|
|
||||||
|
#ifdef CAMERA_CCI
|
||||||
|
#include <soc/qcom/camera2.h>
|
||||||
|
#include "msm_camera_i2c.h"
|
||||||
|
#include "msm_camera_dt_util.h"
|
||||||
|
#include "msm_camera_io_util.h"
|
||||||
|
#include "msm_cci.h"
|
||||||
|
|
||||||
|
#define MSM_TOF_MAX_VREGS (10)
|
||||||
|
|
||||||
|
struct msm_tof_vreg {
|
||||||
|
struct camera_vreg_t *cam_vreg;
|
||||||
|
void *data[MSM_TOF_MAX_VREGS];
|
||||||
|
int num_vreg;
|
||||||
|
};
|
||||||
|
|
||||||
|
struct cci_data {
|
||||||
|
struct msm_camera_i2c_client g_client;
|
||||||
|
struct msm_camera_i2c_client *client;
|
||||||
|
struct platform_device *pdev;
|
||||||
|
enum msm_camera_device_type_t device_type;
|
||||||
|
enum cci_i2c_master_t cci_master;
|
||||||
|
struct msm_tof_vreg vreg_cfg;
|
||||||
|
struct msm_sd_subdev msm_sd;
|
||||||
|
struct v4l2_subdev sdev;
|
||||||
|
struct v4l2_subdev_ops *subdev_ops;
|
||||||
|
char subdev_initialized;
|
||||||
|
uint32_t subdev_id;
|
||||||
|
uint8_t power_up;
|
||||||
|
struct msm_camera_gpio_conf *gconf;
|
||||||
|
struct msm_pinctrl_info pinctrl_info;
|
||||||
|
uint8_t cam_pinctrl_status;
|
||||||
|
|
||||||
|
};
|
||||||
|
int stmvl53l0_init_cci(void);
|
||||||
|
void stmvl53l0_exit_cci(void *);
|
||||||
|
int stmvl53l0_power_down_cci(void *);
|
||||||
|
int stmvl53l0_power_up_cci(void *, unsigned int *);
|
||||||
|
#endif /* CAMERA_CCI */
|
||||||
|
#endif /* STMVL53L0_CCI_H */
|
35
drivers/input/misc/vl53L0/stmvl53l0-i2c.h
Normal file
35
drivers/input/misc/vl53L0/stmvl53l0-i2c.h
Normal file
|
@ -0,0 +1,35 @@
|
||||||
|
/*
|
||||||
|
* stmvl53l0-i2c.h - Linux kernel modules for STM VL53L0 FlightSense TOF sensor
|
||||||
|
*
|
||||||
|
* Copyright (C) 2016 STMicroelectronics Imaging Division
|
||||||
|
*
|
||||||
|
* This program is free software; you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation; either version 2 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*/
|
||||||
|
/*
|
||||||
|
* Defines
|
||||||
|
*/
|
||||||
|
#ifndef STMVL53L0_I2C_H
|
||||||
|
#define STMVL53L0_I2C_H
|
||||||
|
#include <linux/types.h>
|
||||||
|
|
||||||
|
#ifndef CAMERA_CCI
|
||||||
|
struct i2c_data {
|
||||||
|
struct i2c_client *client;
|
||||||
|
struct regulator *vana;
|
||||||
|
uint8_t power_up;
|
||||||
|
};
|
||||||
|
int stmvl53l0_init_i2c(void);
|
||||||
|
void stmvl53l0_exit_i2c(void *);
|
||||||
|
int stmvl53l0_power_up_i2c(void *, unsigned int *);
|
||||||
|
int stmvl53l0_power_down_i2c(void *);
|
||||||
|
|
||||||
|
#endif /* NOT CAMERA_CCI */
|
||||||
|
#endif /* STMVL53L0_I2C_H */
|
217
drivers/input/misc/vl53L0/stmvl53l0.h
Normal file
217
drivers/input/misc/vl53L0/stmvl53l0.h
Normal file
|
@ -0,0 +1,217 @@
|
||||||
|
/*
|
||||||
|
* stmvl53l0.h - Linux kernel modules for STM VL53L0 FlightSense TOF sensor
|
||||||
|
*
|
||||||
|
* Copyright (C) 2016 STMicroelectronics Imaging Division
|
||||||
|
*
|
||||||
|
* This program is free software; you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation; either version 2 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*/
|
||||||
|
/*
|
||||||
|
* Defines
|
||||||
|
*/
|
||||||
|
#ifndef STMVL53L0_H
|
||||||
|
#define STMVL53L0_H
|
||||||
|
|
||||||
|
#include <linux/types.h>
|
||||||
|
#include <linux/mutex.h>
|
||||||
|
#include <linux/workqueue.h>
|
||||||
|
#include <linux/miscdevice.h>
|
||||||
|
#include <linux/wait.h>
|
||||||
|
|
||||||
|
|
||||||
|
#define STMVL53L0_DRV_NAME "stmvl53l0"
|
||||||
|
#define STMVL53L0_SLAVE_ADDR (0x52>>1)
|
||||||
|
|
||||||
|
#define DRIVER_VERSION "1.0.5"
|
||||||
|
#define I2C_M_WR 0x00
|
||||||
|
/* #define INT_POLLING_DELAY 20 */
|
||||||
|
|
||||||
|
/* if don't want to have output from vl53l0_dbgmsg, comment out #DEBUG macro */
|
||||||
|
#define DEBUG
|
||||||
|
#define vl53l0_dbgmsg(str, args...) \
|
||||||
|
pr_err("%s: " str, __func__, ##args)
|
||||||
|
#define vl53l0_errmsg(str, args...) \
|
||||||
|
pr_err("%s: " str, __func__, ##args)
|
||||||
|
|
||||||
|
#define VL53L0_VDD_MIN 2600000
|
||||||
|
#define VL53L0_VDD_MAX 3000000
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
NORMAL_MODE = 0,
|
||||||
|
OFFSETCALIB_MODE = 1,
|
||||||
|
XTALKCALIB_MODE = 2,
|
||||||
|
} init_mode_e;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
OFFSET_PAR = 0,
|
||||||
|
XTALKRATE_PAR = 1,
|
||||||
|
XTALKENABLE_PAR = 2,
|
||||||
|
GPIOFUNC_PAR = 3,
|
||||||
|
LOWTHRESH_PAR = 4,
|
||||||
|
HIGHTHRESH_PAR = 5,
|
||||||
|
DEVICEMODE_PAR = 6,
|
||||||
|
INTERMEASUREMENT_PAR = 7,
|
||||||
|
REFERENCESPADS_PAR = 8,
|
||||||
|
REFCALIBRATION_PAR = 9,
|
||||||
|
} parameter_name_e;
|
||||||
|
|
||||||
|
enum {
|
||||||
|
CCI_BUS = 0,
|
||||||
|
I2C_BUS = 1,
|
||||||
|
};
|
||||||
|
|
||||||
|
/*
|
||||||
|
* IOCTL register data structs
|
||||||
|
*/
|
||||||
|
struct stmvl53l0_register {
|
||||||
|
uint32_t is_read; /*1: read 0: write*/
|
||||||
|
uint32_t reg_index;
|
||||||
|
uint32_t reg_bytes;
|
||||||
|
uint32_t reg_data;
|
||||||
|
int32_t status;
|
||||||
|
};
|
||||||
|
|
||||||
|
/*
|
||||||
|
* IOCTL parameter structs
|
||||||
|
*/
|
||||||
|
struct stmvl53l0_parameter {
|
||||||
|
uint32_t is_read; /*1: Get 0: Set*/
|
||||||
|
parameter_name_e name;
|
||||||
|
int32_t value;
|
||||||
|
int32_t value2;
|
||||||
|
int32_t status;
|
||||||
|
};
|
||||||
|
|
||||||
|
/*
|
||||||
|
* IOCTL Custom Use Case
|
||||||
|
*/
|
||||||
|
struct stmvl53l0_custom_use_case {
|
||||||
|
FixPoint1616_t signalRateLimit;
|
||||||
|
FixPoint1616_t sigmaLimit;
|
||||||
|
uint32_t preRangePulsePeriod;
|
||||||
|
uint32_t finalRangePulsePeriod;
|
||||||
|
uint32_t timingBudget;
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
* driver data structs
|
||||||
|
*/
|
||||||
|
struct stmvl53l0_data {
|
||||||
|
|
||||||
|
/* !<embed ST VL53L0 Dev data as "dev_data" */
|
||||||
|
VL53L0_DevData_t Data;
|
||||||
|
/*!< i2c device address user specific field*/
|
||||||
|
uint8_t I2cDevAddr;
|
||||||
|
/*!< Type of comms : VL53L0_COMMS_I2C or VL53L0_COMMS_SPI */
|
||||||
|
uint8_t comms_type;
|
||||||
|
/*!< Comms speed [kHz] : typically 400kHz for I2C */
|
||||||
|
uint16_t comms_speed_khz;
|
||||||
|
/* CCI_BUS; I2C_BUS */
|
||||||
|
uint8_t bus_type;
|
||||||
|
|
||||||
|
void *client_object; /* cci or i2c client */
|
||||||
|
|
||||||
|
struct mutex update_lock;
|
||||||
|
struct delayed_work dwork; /* for PS work handler */
|
||||||
|
struct input_dev *input_dev_ps;
|
||||||
|
struct kobject *range_kobj;
|
||||||
|
|
||||||
|
const char *dev_name;
|
||||||
|
/* function pointer */
|
||||||
|
|
||||||
|
/* misc device */
|
||||||
|
struct miscdevice miscdev;
|
||||||
|
|
||||||
|
int irq;
|
||||||
|
unsigned int reset;
|
||||||
|
|
||||||
|
/* control flag from HAL */
|
||||||
|
unsigned int enable_ps_sensor;
|
||||||
|
|
||||||
|
/* PS parameters */
|
||||||
|
unsigned int ps_data; /* to store PS data */
|
||||||
|
|
||||||
|
/* Calibration parameters */
|
||||||
|
unsigned int offsetCalDistance;
|
||||||
|
unsigned int xtalkCalDistance;
|
||||||
|
|
||||||
|
/* Calibration values */
|
||||||
|
uint32_t refSpadCount;
|
||||||
|
uint8_t isApertureSpads;
|
||||||
|
uint8_t VhvSettings;
|
||||||
|
uint8_t PhaseCal;
|
||||||
|
int32_t OffsetMicroMeter;
|
||||||
|
FixPoint1616_t XTalkCompensationRateMegaCps;
|
||||||
|
uint32_t setCalibratedValue;
|
||||||
|
|
||||||
|
/* Custom values set by app */
|
||||||
|
FixPoint1616_t signalRateLimit;
|
||||||
|
FixPoint1616_t sigmaLimit;
|
||||||
|
uint32_t preRangePulsePeriod;
|
||||||
|
uint32_t finalRangePulsePeriod;
|
||||||
|
|
||||||
|
|
||||||
|
/* Range Data */
|
||||||
|
VL53L0_RangingMeasurementData_t rangeData;
|
||||||
|
|
||||||
|
/* Device parameters */
|
||||||
|
VL53L0_DeviceModes deviceMode;
|
||||||
|
uint32_t interMeasurems;
|
||||||
|
VL53L0_GpioFunctionality gpio_function;
|
||||||
|
VL53L0_InterruptPolarity gpio_polarity;
|
||||||
|
FixPoint1616_t low_threshold;
|
||||||
|
FixPoint1616_t high_threshold;
|
||||||
|
|
||||||
|
/* delay time in miniseconds*/
|
||||||
|
uint8_t delay_ms;
|
||||||
|
|
||||||
|
/* Timing Budget */
|
||||||
|
uint32_t timingBudget;
|
||||||
|
/* Use this threshold to force restart ranging */
|
||||||
|
uint32_t noInterruptCount;
|
||||||
|
/* Use this flag to denote use case*/
|
||||||
|
uint8_t useCase;
|
||||||
|
/* Use this flag to indicate an update of use case */
|
||||||
|
uint8_t updateUseCase;
|
||||||
|
/* Polling thread */
|
||||||
|
struct task_struct *poll_thread;
|
||||||
|
/* Wait Queue on which the poll thread blocks */
|
||||||
|
wait_queue_head_t poll_thread_wq;
|
||||||
|
|
||||||
|
/* Recent interrupt status */
|
||||||
|
uint32_t interruptStatus;
|
||||||
|
|
||||||
|
struct mutex work_mutex;
|
||||||
|
|
||||||
|
struct timer_list timer;
|
||||||
|
uint32_t flushCount;
|
||||||
|
|
||||||
|
/* Debug */
|
||||||
|
unsigned int enableDebug;
|
||||||
|
uint8_t interrupt_received;
|
||||||
|
};
|
||||||
|
|
||||||
|
/*
|
||||||
|
* function pointer structs
|
||||||
|
*/
|
||||||
|
struct stmvl53l0_module_fn_t {
|
||||||
|
int (*init)(void);
|
||||||
|
void (*deinit)(void *);
|
||||||
|
int (*power_up)(void *, unsigned int *);
|
||||||
|
int (*power_down)(void *);
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
int stmvl53l0_setup(struct stmvl53l0_data *data);
|
||||||
|
void stmvl53l0_cleanup(struct stmvl53l0_data *data);
|
||||||
|
|
||||||
|
#endif /* STMVL53L0_H */
|
509
drivers/input/misc/vl53L0/stmvl53l0_module-cci.c
Normal file
509
drivers/input/misc/vl53L0/stmvl53l0_module-cci.c
Normal file
|
@ -0,0 +1,509 @@
|
||||||
|
/*
|
||||||
|
* stmvl53l0_module-cci.c - Linux kernel modules for STM VL53L0 FlightSense TOF
|
||||||
|
* sensor
|
||||||
|
*
|
||||||
|
* Copyright (C) 2016 STMicroelectronics Imaging Division.
|
||||||
|
*
|
||||||
|
* This program is free software; you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation; either version 2 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*/
|
||||||
|
#include <linux/uaccess.h>
|
||||||
|
#include <linux/module.h>
|
||||||
|
#include <linux/init.h>
|
||||||
|
#include <linux/slab.h>
|
||||||
|
#include <linux/i2c.h>
|
||||||
|
#include <linux/mutex.h>
|
||||||
|
#include <linux/delay.h>
|
||||||
|
#include <linux/interrupt.h>
|
||||||
|
#include <linux/irq.h>
|
||||||
|
#include <linux/gpio.h>
|
||||||
|
#include <linux/input.h>
|
||||||
|
#include <linux/miscdevice.h>
|
||||||
|
#include <linux/kernel.h>
|
||||||
|
#include <linux/fs.h>
|
||||||
|
#include <linux/time.h>
|
||||||
|
#include <linux/platform_device.h>
|
||||||
|
/*
|
||||||
|
* power specific includes
|
||||||
|
*/
|
||||||
|
#include <linux/pwm.h>
|
||||||
|
#include <linux/regulator/consumer.h>
|
||||||
|
#include <linux/pinctrl/consumer.h>
|
||||||
|
#include <linux/clk.h>
|
||||||
|
#include <linux/of_gpio.h>
|
||||||
|
/*
|
||||||
|
* API includes
|
||||||
|
*/
|
||||||
|
#include "vl53l0_api.h"
|
||||||
|
#include "vl53l0_def.h"
|
||||||
|
#include "vl53l0_platform.h"
|
||||||
|
#include "stmvl53l0-cci.h"
|
||||||
|
#include "stmvl53l0-i2c.h"
|
||||||
|
#include "stmvl53l0.h"
|
||||||
|
|
||||||
|
#ifdef CAMERA_CCI
|
||||||
|
/*
|
||||||
|
* Global data
|
||||||
|
*/
|
||||||
|
static struct v4l2_file_operations msm_tof_v4l2_subdev_fops;
|
||||||
|
static struct msm_camera_i2c_fn_t msm_sensor_cci_func_tbl = {
|
||||||
|
.i2c_read = msm_camera_cci_i2c_read,
|
||||||
|
.i2c_read_seq = msm_camera_cci_i2c_read_seq,
|
||||||
|
.i2c_write = msm_camera_cci_i2c_write,
|
||||||
|
.i2c_write_seq = msm_camera_cci_i2c_write_seq,
|
||||||
|
.i2c_write_table = msm_camera_cci_i2c_write_table,
|
||||||
|
.i2c_write_seq_table = msm_camera_cci_i2c_write_seq_table,
|
||||||
|
.i2c_write_table_w_microdelay =
|
||||||
|
msm_camera_cci_i2c_write_table_w_microdelay,
|
||||||
|
.i2c_util = msm_sensor_cci_i2c_util,
|
||||||
|
.i2c_poll = msm_camera_cci_i2c_poll,
|
||||||
|
};
|
||||||
|
|
||||||
|
static int stmvl53l0_get_dt_data(struct device *dev, struct cci_data *data);
|
||||||
|
|
||||||
|
/*
|
||||||
|
* QCOM specific functions
|
||||||
|
*/
|
||||||
|
static int stmvl53l0_get_dt_data(struct device *dev, struct cci_data *data)
|
||||||
|
{
|
||||||
|
int rc = 0;
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("Enter\n");
|
||||||
|
|
||||||
|
if (dev->of_node) {
|
||||||
|
struct device_node *of_node = dev->of_node;
|
||||||
|
struct msm_tof_vreg *vreg_cfg;
|
||||||
|
|
||||||
|
if (!of_node) {
|
||||||
|
vl53l0_errmsg("failed %d\n", __LINE__);
|
||||||
|
return -EINVAL;
|
||||||
|
}
|
||||||
|
|
||||||
|
rc = of_property_read_u32(of_node,
|
||||||
|
"cell-index", &data->pdev->id);
|
||||||
|
if (rc < 0) {
|
||||||
|
vl53l0_errmsg("failed %d\n", __LINE__);
|
||||||
|
return rc;
|
||||||
|
}
|
||||||
|
vl53l0_dbgmsg("cell-index: %d\n", data->pdev->id);
|
||||||
|
rc = of_property_read_u32(of_node, "qcom,cci-master",
|
||||||
|
&data->cci_master);
|
||||||
|
if (rc < 0) {
|
||||||
|
vl53l0_errmsg("failed %d\n", __LINE__);
|
||||||
|
/* Set default master 0 */
|
||||||
|
data->cci_master = MASTER_0;
|
||||||
|
rc = 0;
|
||||||
|
}
|
||||||
|
vl53l0_dbgmsg("cci_master: %d\n", data->cci_master);
|
||||||
|
if (of_find_property(of_node, "qcom,cam-vreg-name", NULL)) {
|
||||||
|
vreg_cfg = &data->vreg_cfg;
|
||||||
|
rc = msm_camera_get_dt_vreg_data(of_node,
|
||||||
|
&vreg_cfg->cam_vreg,
|
||||||
|
&vreg_cfg->num_vreg);
|
||||||
|
if (rc < 0) {
|
||||||
|
vl53l0_errmsg("failed %d\n", __LINE__);
|
||||||
|
return rc;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
vl53l0_dbgmsg("vreg-name: %s min_volt: %d max_volt: %d",
|
||||||
|
vreg_cfg->cam_vreg->reg_name,
|
||||||
|
vreg_cfg->cam_vreg->min_voltage,
|
||||||
|
vreg_cfg->cam_vreg->max_voltage);
|
||||||
|
|
||||||
|
rc = msm_sensor_driver_get_gpio_data(&(data->gconf), of_node);
|
||||||
|
if ((rc < 0) || (data->gconf == NULL)) {
|
||||||
|
vl53l0_errmsg
|
||||||
|
("No Laser Sensor GPIOs to be configured!\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
vl53l0_dbgmsg("End rc =%d\n", rc);
|
||||||
|
|
||||||
|
return rc;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int32_t stmvl53l0_vreg_control(struct cci_data *data, int config)
|
||||||
|
{
|
||||||
|
int rc = 0, i, cnt;
|
||||||
|
struct msm_tof_vreg *vreg_cfg;
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("Enter\n");
|
||||||
|
|
||||||
|
vreg_cfg = &data->vreg_cfg;
|
||||||
|
cnt = vreg_cfg->num_vreg;
|
||||||
|
vl53l0_dbgmsg("num_vreg: %d\n", cnt);
|
||||||
|
if (!cnt) {
|
||||||
|
vl53l0_errmsg("failed %d\n", __LINE__);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (cnt >= MSM_TOF_MAX_VREGS) {
|
||||||
|
vl53l0_errmsg("failed %d cnt %d\n", __LINE__, cnt);
|
||||||
|
return -EINVAL;
|
||||||
|
}
|
||||||
|
|
||||||
|
for (i = 0; i < cnt; i++) {
|
||||||
|
rc = msm_camera_config_single_vreg(&(data->pdev->dev),
|
||||||
|
&vreg_cfg->cam_vreg[i],
|
||||||
|
(struct regulator **)
|
||||||
|
&vreg_cfg->data[i], config);
|
||||||
|
}
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("EXIT rc =%d\n", rc);
|
||||||
|
return rc;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int msm_tof_close(struct v4l2_subdev *sd, struct v4l2_subdev_fh *fh)
|
||||||
|
{
|
||||||
|
int rc = 0;
|
||||||
|
/*
|
||||||
|
* struct msm_tof_ctrl_t *tof_ctrl = v4l2_get_subdevdata(sd);
|
||||||
|
* if (!tof_ctrl) {
|
||||||
|
* pr_err("failed\n");
|
||||||
|
* return -EINVAL;
|
||||||
|
* }
|
||||||
|
* if (tof_ctrl->tof_device_type == MSM_CAMERA_PLATFORM_DEVICE) {
|
||||||
|
* rc = tof_ctrl->i2c_client.i2c_func_tbl->i2c_util(
|
||||||
|
* &tof_ctrl->i2c_client, MSM_CCI_RELEASE);
|
||||||
|
* if (rc < 0)
|
||||||
|
* pr_err("cci_init failed\n");
|
||||||
|
* }
|
||||||
|
* tof_ctrl->i2c_state = TOF_I2C_RELEASE;
|
||||||
|
*/
|
||||||
|
return rc;
|
||||||
|
}
|
||||||
|
|
||||||
|
static const struct v4l2_subdev_internal_ops msm_tof_internal_ops = {
|
||||||
|
.close = msm_tof_close,
|
||||||
|
};
|
||||||
|
|
||||||
|
static long msm_tof_subdev_ioctl(struct v4l2_subdev *sd,
|
||||||
|
unsigned int cmd, void *arg)
|
||||||
|
{
|
||||||
|
vl53l0_dbgmsg("Subdev_ioctl not handled\n");
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int32_t msm_tof_power(struct v4l2_subdev *sd, int on)
|
||||||
|
{
|
||||||
|
vl53l0_dbgmsg("TOF power called\n");
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static struct v4l2_subdev_core_ops msm_tof_subdev_core_ops = {
|
||||||
|
.ioctl = msm_tof_subdev_ioctl,
|
||||||
|
.s_power = msm_tof_power,
|
||||||
|
};
|
||||||
|
|
||||||
|
static struct v4l2_subdev_ops msm_tof_subdev_ops = {
|
||||||
|
.core = &msm_tof_subdev_core_ops,
|
||||||
|
};
|
||||||
|
|
||||||
|
static int stmvl53l0_cci_init(struct cci_data *data)
|
||||||
|
{
|
||||||
|
int rc = 0;
|
||||||
|
struct msm_camera_cci_client *cci_client = data->client->cci_client;
|
||||||
|
|
||||||
|
if (data->subdev_initialized == FALSE) {
|
||||||
|
data->client->i2c_func_tbl = &msm_sensor_cci_func_tbl;
|
||||||
|
data->client->cci_client =
|
||||||
|
kzalloc(sizeof(struct msm_camera_cci_client), GFP_KERNEL);
|
||||||
|
if (!data->client->cci_client) {
|
||||||
|
vl53l0_errmsg("%d, failed no memory\n", __LINE__);
|
||||||
|
return -ENOMEM;
|
||||||
|
}
|
||||||
|
cci_client = data->client->cci_client;
|
||||||
|
cci_client->cci_subdev = msm_cci_get_subdev();
|
||||||
|
if (cci_client->cci_subdev == NULL) {
|
||||||
|
vl53l0_errmsg("CCI subdev is not initialized!!\n");
|
||||||
|
return -ENODEV;
|
||||||
|
}
|
||||||
|
cci_client->cci_i2c_master = data->cci_master;
|
||||||
|
v4l2_subdev_init(&data->msm_sd.sd, data->subdev_ops);
|
||||||
|
v4l2_set_subdevdata(&data->msm_sd.sd, data);
|
||||||
|
data->msm_sd.sd.internal_ops = &msm_tof_internal_ops;
|
||||||
|
data->msm_sd.sd.flags |= V4L2_SUBDEV_FL_HAS_DEVNODE;
|
||||||
|
snprintf(data->msm_sd.sd.name,
|
||||||
|
ARRAY_SIZE(data->msm_sd.sd.name), "msm_tof");
|
||||||
|
media_entity_init(&data->msm_sd.sd.entity, 0, NULL, 0);
|
||||||
|
data->msm_sd.sd.entity.type = MEDIA_ENT_T_V4L2_SUBDEV;
|
||||||
|
data->msm_sd.sd.entity.group_id = MSM_CAMERA_SUBDEV_TOF;
|
||||||
|
data->msm_sd.close_seq =
|
||||||
|
MSM_SD_CLOSE_2ND_CATEGORY | 0x2;
|
||||||
|
msm_sd_register(&data->msm_sd);
|
||||||
|
msm_tof_v4l2_subdev_fops = v4l2_subdev_fops;
|
||||||
|
data->msm_sd.sd.devnode->fops =
|
||||||
|
&msm_tof_v4l2_subdev_fops;
|
||||||
|
data->subdev_initialized = TRUE;
|
||||||
|
}
|
||||||
|
|
||||||
|
cci_client->sid = 0x29;
|
||||||
|
cci_client->retries = 3;
|
||||||
|
cci_client->id_map = 0;
|
||||||
|
cci_client->cci_i2c_master = data->cci_master;
|
||||||
|
rc = data->client->i2c_func_tbl->i2c_util(data->client, MSM_CCI_INIT);
|
||||||
|
if (rc < 0) {
|
||||||
|
vl53l0_errmsg("%d: CCI Init failed\n", __LINE__);
|
||||||
|
return rc;
|
||||||
|
}
|
||||||
|
vl53l0_dbgmsg("CCI Init Succeeded\n");
|
||||||
|
|
||||||
|
data->client->addr_type = MSM_CAMERA_I2C_BYTE_ADDR;
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int32_t stmvl53l0_platform_probe(struct platform_device *pdev)
|
||||||
|
{
|
||||||
|
struct stmvl53l0_data *vl53l0_data = NULL;
|
||||||
|
struct cci_data *cci_object = NULL;
|
||||||
|
int32_t rc = 0;
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("Enter\n");
|
||||||
|
|
||||||
|
if (!pdev->dev.of_node) {
|
||||||
|
vl53l0_errmsg("of_node NULL\n");
|
||||||
|
return -EINVAL;
|
||||||
|
}
|
||||||
|
|
||||||
|
vl53l0_data = kzalloc(sizeof(struct stmvl53l0_data), GFP_KERNEL);
|
||||||
|
if (!vl53l0_data) {
|
||||||
|
rc = -ENOMEM;
|
||||||
|
return rc;
|
||||||
|
}
|
||||||
|
if (vl53l0_data) {
|
||||||
|
vl53l0_data->client_object =
|
||||||
|
kzalloc(sizeof(struct cci_data), GFP_KERNEL);
|
||||||
|
cci_object = (struct cci_data *)vl53l0_data->client_object;
|
||||||
|
}
|
||||||
|
cci_object->client =
|
||||||
|
(struct msm_camera_i2c_client *)&cci_object->g_client;
|
||||||
|
|
||||||
|
/* setup bus type */
|
||||||
|
vl53l0_data->bus_type = CCI_BUS;
|
||||||
|
|
||||||
|
/* Set platform device handle */
|
||||||
|
cci_object->subdev_ops = &msm_tof_subdev_ops;
|
||||||
|
cci_object->pdev = pdev;
|
||||||
|
rc = stmvl53l0_get_dt_data(&pdev->dev, cci_object);
|
||||||
|
if (rc < 0) {
|
||||||
|
vl53l0_errmsg("%d, failed rc %d\n", __LINE__, rc);
|
||||||
|
return rc;
|
||||||
|
}
|
||||||
|
cci_object->subdev_id = pdev->id;
|
||||||
|
|
||||||
|
/* Set device type as platform device */
|
||||||
|
cci_object->device_type = MSM_CAMERA_PLATFORM_DEVICE;
|
||||||
|
cci_object->subdev_initialized = FALSE;
|
||||||
|
|
||||||
|
/* setup device name */
|
||||||
|
vl53l0_data->dev_name = dev_name(&pdev->dev);
|
||||||
|
|
||||||
|
/* setup device data */
|
||||||
|
dev_set_drvdata(&pdev->dev, vl53l0_data);
|
||||||
|
|
||||||
|
/* setup other stuff */
|
||||||
|
rc = stmvl53l0_setup(vl53l0_data);
|
||||||
|
|
||||||
|
/* init default value */
|
||||||
|
cci_object->power_up = 0;
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("End\n");
|
||||||
|
|
||||||
|
return rc;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
static int32_t stmvl53l0_platform_remove(struct platform_device *pdev)
|
||||||
|
{
|
||||||
|
struct stmvl53l0_data *vl53l0_data = platform_get_drvdata(pdev);
|
||||||
|
|
||||||
|
stmvl53l0_cleanup(vl53l0_data);
|
||||||
|
platform_set_drvdata(pdev, NULL);
|
||||||
|
|
||||||
|
kfree(vl53l0_data->client_object);
|
||||||
|
kfree(vl53l0_data);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static const struct of_device_id st_stmvl53l0_dt_match[] = {
|
||||||
|
{.compatible = "st,stmvl53l0",},
|
||||||
|
{},
|
||||||
|
};
|
||||||
|
|
||||||
|
static struct platform_driver stmvl53l0_platform_driver = {
|
||||||
|
.probe = stmvl53l0_platform_probe,
|
||||||
|
.remove = stmvl53l0_platform_remove,
|
||||||
|
.driver = {
|
||||||
|
.name = STMVL53L0_DRV_NAME,
|
||||||
|
.owner = THIS_MODULE,
|
||||||
|
.of_match_table = st_stmvl53l0_dt_match,
|
||||||
|
},
|
||||||
|
};
|
||||||
|
|
||||||
|
int stmvl53l0_power_up_cci(void *cci_object, unsigned int *preset_flag)
|
||||||
|
{
|
||||||
|
int ret = 0;
|
||||||
|
struct cci_data *data = (struct cci_data *)cci_object;
|
||||||
|
struct gpio *gpio_tbl = NULL;
|
||||||
|
uint8_t gpio_tbl_size = 0;
|
||||||
|
int i = 0;
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("Enter");
|
||||||
|
|
||||||
|
/* need to init cci first */
|
||||||
|
ret = stmvl53l0_cci_init(data);
|
||||||
|
if (ret) {
|
||||||
|
vl53l0_errmsg("stmvl53l0_cci_init failed %d\n", __LINE__);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Check if GPIO needs to be enabled for chip select */
|
||||||
|
vl53l0_dbgmsg("Get gpio table!size: %d\n",
|
||||||
|
data->gconf->cam_gpio_req_tbl_size);
|
||||||
|
gpio_tbl = data->gconf->cam_gpio_req_tbl;
|
||||||
|
gpio_tbl_size = data->gconf->cam_gpio_req_tbl_size;
|
||||||
|
if (gpio_tbl_size > 0) {
|
||||||
|
ret = msm_camera_pinctrl_init(&(data->pinctrl_info),
|
||||||
|
&(data->pdev->dev));
|
||||||
|
if (ret < 0) {
|
||||||
|
vl53l0_errmsg("Initialization of pinctrl failed\n");
|
||||||
|
data->cam_pinctrl_status = 0;
|
||||||
|
} else {
|
||||||
|
data->cam_pinctrl_status = 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
for (i = 0; i < gpio_tbl_size; i++) {
|
||||||
|
ret = gpio_request_one(gpio_tbl[i].gpio,
|
||||||
|
gpio_tbl[i].flags,
|
||||||
|
gpio_tbl[i].label);
|
||||||
|
if (ret < 0) {
|
||||||
|
vl53l0_errmsg
|
||||||
|
("Request for GPIO %d failed! Err: %d\n",
|
||||||
|
gpio_tbl[i].gpio, ret);
|
||||||
|
} else {
|
||||||
|
if (data->cam_pinctrl_status) {
|
||||||
|
ret =
|
||||||
|
pinctrl_select_state(
|
||||||
|
data->pinctrl_info.pinctrl,
|
||||||
|
data->pinctrl_info.gpio_state_active);
|
||||||
|
if (ret < 0) {
|
||||||
|
vl53l0_errmsg(
|
||||||
|
"%s: Cannot set pin to active state!\n",
|
||||||
|
__func__);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
vl53l0_dbgmsg("Set pin %d value to 1!\n",
|
||||||
|
gpio_tbl[i].gpio);
|
||||||
|
gpio_set_value_cansleep(gpio_tbl[i].gpio, 1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* actual power up */
|
||||||
|
if (data && data->device_type == MSM_CAMERA_PLATFORM_DEVICE) {
|
||||||
|
ret = stmvl53l0_vreg_control(data, 1);
|
||||||
|
if (ret < 0) {
|
||||||
|
vl53l0_errmsg("stmvl53l0_vreg_control failed %d\n",
|
||||||
|
__LINE__);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
data->power_up = 1;
|
||||||
|
*preset_flag = 1;
|
||||||
|
vl53l0_dbgmsg("End\n");
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
int stmvl53l0_power_down_cci(void *cci_object)
|
||||||
|
{
|
||||||
|
int ret = 0;
|
||||||
|
struct cci_data *data = (struct cci_data *)cci_object;
|
||||||
|
int i = 0;
|
||||||
|
struct gpio *gpio_tbl = NULL;
|
||||||
|
uint8_t gpio_tbl_size = 0;
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("Enter\n");
|
||||||
|
if (data->power_up) {
|
||||||
|
/* need to release cci first */
|
||||||
|
ret = data->client->i2c_func_tbl->i2c_util(data->client,
|
||||||
|
MSM_CCI_RELEASE);
|
||||||
|
if (ret < 0)
|
||||||
|
vl53l0_errmsg("CCI Release failed rc %d\n", ret);
|
||||||
|
|
||||||
|
/* actual power down */
|
||||||
|
if (data->device_type == MSM_CAMERA_PLATFORM_DEVICE) {
|
||||||
|
ret = stmvl53l0_vreg_control(data, 0);
|
||||||
|
if (ret < 0) {
|
||||||
|
vl53l0_errmsg
|
||||||
|
("stmvl53l0_vreg_control failed %d\n",
|
||||||
|
__LINE__);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* reset GPIO pins */
|
||||||
|
gpio_tbl = data->gconf->cam_gpio_req_tbl;
|
||||||
|
gpio_tbl_size = data->gconf->cam_gpio_req_tbl_size;
|
||||||
|
if (gpio_tbl_size > 0) {
|
||||||
|
for (i = 0; i < gpio_tbl_size; i++)
|
||||||
|
gpio_set_value_cansleep(gpio_tbl[i].gpio, 0);
|
||||||
|
if (data->cam_pinctrl_status) {
|
||||||
|
ret =
|
||||||
|
pinctrl_select_state(data->pinctrl_info.
|
||||||
|
pinctrl,
|
||||||
|
data->pinctrl_info.
|
||||||
|
gpio_state_suspend);
|
||||||
|
if (ret < 0) {
|
||||||
|
vl53l0_errmsg(
|
||||||
|
"Error setting gpio pin to supsend state!\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
devm_pinctrl_put(data->pinctrl_info.pinctrl);
|
||||||
|
data->cam_pinctrl_status = 0;
|
||||||
|
gpio_free_array(gpio_tbl, gpio_tbl_size);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
data->power_up = 0;
|
||||||
|
vl53l0_dbgmsg("End\n");
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
int stmvl53l0_init_cci(void)
|
||||||
|
{
|
||||||
|
int ret = 0;
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("Enter\n");
|
||||||
|
|
||||||
|
/* register as a platform device */
|
||||||
|
ret = platform_driver_register(&stmvl53l0_platform_driver);
|
||||||
|
if (ret)
|
||||||
|
vl53l0_errmsg("%d, error ret:%d\n", __LINE__, ret);
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("End\n");
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
void stmvl53l0_exit_cci(void *cci_object)
|
||||||
|
{
|
||||||
|
struct cci_data *data = (struct cci_data *)cci_object;
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("Enter\n");
|
||||||
|
|
||||||
|
if (data && data->client->cci_client)
|
||||||
|
kfree(data->client->cci_client);
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("End\n");
|
||||||
|
}
|
||||||
|
#endif /* end of CAMERA_CCI */
|
266
drivers/input/misc/vl53L0/stmvl53l0_module-i2c.c
Normal file
266
drivers/input/misc/vl53L0/stmvl53l0_module-i2c.c
Normal file
|
@ -0,0 +1,266 @@
|
||||||
|
/*
|
||||||
|
* stmvl53l0_module-i2c.c - Linux kernel modules for STM VL53L0 FlightSense TOF
|
||||||
|
* sensor
|
||||||
|
*
|
||||||
|
* Copyright (C) 2016 STMicroelectronics Imaging Division.
|
||||||
|
*
|
||||||
|
* This program is free software; you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation; either version 2 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*/
|
||||||
|
#include <linux/uaccess.h>
|
||||||
|
#include <linux/module.h>
|
||||||
|
#include <linux/init.h>
|
||||||
|
#include <linux/slab.h>
|
||||||
|
#include <linux/i2c.h>
|
||||||
|
#include <linux/mutex.h>
|
||||||
|
#include <linux/delay.h>
|
||||||
|
#include <linux/interrupt.h>
|
||||||
|
#include <linux/irq.h>
|
||||||
|
#include <linux/gpio.h>
|
||||||
|
#include <linux/input.h>
|
||||||
|
#include <linux/miscdevice.h>
|
||||||
|
#include <linux/kernel.h>
|
||||||
|
#include <linux/fs.h>
|
||||||
|
#include <linux/time.h>
|
||||||
|
#include <linux/platform_device.h>
|
||||||
|
/*
|
||||||
|
* power specific includes
|
||||||
|
*/
|
||||||
|
#include <linux/pwm.h>
|
||||||
|
#include <linux/regulator/consumer.h>
|
||||||
|
#include <linux/pinctrl/consumer.h>
|
||||||
|
#include <linux/clk.h>
|
||||||
|
#include <linux/of_gpio.h>
|
||||||
|
/*
|
||||||
|
* API includes
|
||||||
|
*/
|
||||||
|
#include "vl53l0_api.h"
|
||||||
|
#include "vl53l0_def.h"
|
||||||
|
#include "vl53l0_platform.h"
|
||||||
|
#include "stmvl53l0-i2c.h"
|
||||||
|
#include "stmvl53l0-cci.h"
|
||||||
|
#include "stmvl53l0.h"
|
||||||
|
#ifndef CAMERA_CCI
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Global data
|
||||||
|
*/
|
||||||
|
static int stmvl53l0_parse_vdd(struct device *dev, struct i2c_data *data);
|
||||||
|
|
||||||
|
/*
|
||||||
|
* QCOM specific functions
|
||||||
|
*/
|
||||||
|
static int stmvl53l0_parse_vdd(struct device *dev, struct i2c_data *data)
|
||||||
|
{
|
||||||
|
int ret = 0;
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("Enter\n");
|
||||||
|
|
||||||
|
if (dev->of_node) {
|
||||||
|
data->vana = regulator_get(dev, "vdd");
|
||||||
|
if (IS_ERR(data->vana)) {
|
||||||
|
vl53l0_errmsg("vdd supply is not provided\n");
|
||||||
|
ret = -1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
vl53l0_dbgmsg("End\n");
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int stmvl53l0_probe(struct i2c_client *client,
|
||||||
|
const struct i2c_device_id *id)
|
||||||
|
{
|
||||||
|
int rc = 0;
|
||||||
|
struct stmvl53l0_data *vl53l0_data = NULL;
|
||||||
|
struct i2c_data *i2c_object = NULL;
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("Enter\n");
|
||||||
|
|
||||||
|
if (!i2c_check_functionality(client->adapter, I2C_FUNC_SMBUS_BYTE)) {
|
||||||
|
rc = -EIO;
|
||||||
|
return rc;
|
||||||
|
}
|
||||||
|
|
||||||
|
vl53l0_data = kzalloc(sizeof(struct stmvl53l0_data), GFP_KERNEL);
|
||||||
|
if (!vl53l0_data) {
|
||||||
|
rc = -ENOMEM;
|
||||||
|
return rc;
|
||||||
|
}
|
||||||
|
if (vl53l0_data) {
|
||||||
|
vl53l0_data->client_object =
|
||||||
|
kzalloc(sizeof(struct i2c_data), GFP_KERNEL);
|
||||||
|
i2c_object = (struct i2c_data *)vl53l0_data->client_object;
|
||||||
|
}
|
||||||
|
i2c_object->client = client;
|
||||||
|
|
||||||
|
/* setup bus type */
|
||||||
|
vl53l0_data->bus_type = I2C_BUS;
|
||||||
|
|
||||||
|
/* setup regulator */
|
||||||
|
stmvl53l0_parse_vdd(&i2c_object->client->dev, i2c_object);
|
||||||
|
|
||||||
|
/* setup device name */
|
||||||
|
vl53l0_data->dev_name = dev_name(&client->dev);
|
||||||
|
|
||||||
|
/* setup device data */
|
||||||
|
dev_set_drvdata(&client->dev, vl53l0_data);
|
||||||
|
|
||||||
|
/* setup client data */
|
||||||
|
i2c_set_clientdata(client, vl53l0_data);
|
||||||
|
|
||||||
|
/* setup other stuff */
|
||||||
|
rc = stmvl53l0_setup(vl53l0_data);
|
||||||
|
|
||||||
|
/* init default value */
|
||||||
|
i2c_object->power_up = 0;
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("End\n");
|
||||||
|
return rc;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int stmvl53l0_remove(struct i2c_client *client)
|
||||||
|
{
|
||||||
|
struct stmvl53l0_data *data = i2c_get_clientdata(client);
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("Enter\n");
|
||||||
|
|
||||||
|
/* Power down the device */
|
||||||
|
stmvl53l0_power_down_i2c(data->client_object);
|
||||||
|
stmvl53l0_cleanup(data);
|
||||||
|
kfree(data->client_object);
|
||||||
|
kfree(data);
|
||||||
|
vl53l0_dbgmsg("End\n");
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static const struct i2c_device_id stmvl53l0_id[] = {
|
||||||
|
{STMVL53L0_DRV_NAME, 0},
|
||||||
|
{},
|
||||||
|
};
|
||||||
|
|
||||||
|
MODULE_DEVICE_TABLE(i2c, stmvl53l0_id);
|
||||||
|
|
||||||
|
static const struct of_device_id st_stmvl53l0_dt_match[] = {
|
||||||
|
{.compatible = "st,stmvl53l0",},
|
||||||
|
{},
|
||||||
|
};
|
||||||
|
|
||||||
|
static struct i2c_driver stmvl53l0_driver = {
|
||||||
|
.driver = {
|
||||||
|
.name = STMVL53L0_DRV_NAME,
|
||||||
|
.owner = THIS_MODULE,
|
||||||
|
.of_match_table = st_stmvl53l0_dt_match,
|
||||||
|
},
|
||||||
|
.probe = stmvl53l0_probe,
|
||||||
|
.remove = stmvl53l0_remove,
|
||||||
|
.id_table = stmvl53l0_id,
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
int stmvl53l0_power_up_i2c(void *i2c_object, unsigned int *preset_flag)
|
||||||
|
{
|
||||||
|
int ret = 0;
|
||||||
|
#ifndef STM_TEST
|
||||||
|
struct i2c_data *data = (struct i2c_data *)i2c_object;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("Enter\n");
|
||||||
|
|
||||||
|
/* actual power on */
|
||||||
|
#ifndef STM_TEST
|
||||||
|
ret = regulator_set_voltage(data->vana, VL53L0_VDD_MIN, VL53L0_VDD_MAX);
|
||||||
|
if (ret < 0) {
|
||||||
|
vl53l0_errmsg("set_vol(%p) fail %d\n", data->vana, ret);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
ret = regulator_enable(data->vana);
|
||||||
|
|
||||||
|
usleep_range(2950, 3000);
|
||||||
|
if (ret < 0) {
|
||||||
|
vl53l0_errmsg("reg enable(%p) failed.rc=%d\n", data->vana, ret);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
data->power_up = 1;
|
||||||
|
*preset_flag = 1;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("End\n");
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
int stmvl53l0_power_down_i2c(void *i2c_object)
|
||||||
|
{
|
||||||
|
int ret = 0;
|
||||||
|
#ifndef STM_TEST
|
||||||
|
struct i2c_data *data = (struct i2c_data *)i2c_object;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("Enter\n");
|
||||||
|
#ifndef STM_TEST
|
||||||
|
usleep_range(2950, 3000);
|
||||||
|
ret = regulator_disable(data->vana);
|
||||||
|
if (ret < 0)
|
||||||
|
vl53l0_errmsg("reg disable(%p) failed.rc=%d\n",
|
||||||
|
data->vana, ret);
|
||||||
|
|
||||||
|
data->power_up = 0;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("End\n");
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
int stmvl53l0_init_i2c(void)
|
||||||
|
{
|
||||||
|
int ret = 0;
|
||||||
|
|
||||||
|
#ifdef STM_TEST
|
||||||
|
struct i2c_client *client = NULL;
|
||||||
|
struct i2c_adapter *adapter;
|
||||||
|
struct i2c_board_info info = {
|
||||||
|
.type = "stmvl53l0",
|
||||||
|
.addr = STMVL53L0_SLAVE_ADDR,
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("Enter\n");
|
||||||
|
|
||||||
|
/* register as a i2c client device */
|
||||||
|
ret = i2c_add_driver(&stmvl53l0_driver);
|
||||||
|
if (ret)
|
||||||
|
vl53l0_errmsg("%d erro ret:%d\n", __LINE__, ret);
|
||||||
|
|
||||||
|
#ifdef STM_TEST
|
||||||
|
if (!ret) {
|
||||||
|
adapter = i2c_get_adapter(4);
|
||||||
|
if (!adapter)
|
||||||
|
ret = -EINVAL;
|
||||||
|
else
|
||||||
|
client = i2c_new_device(adapter, &info);
|
||||||
|
if (!client)
|
||||||
|
ret = -EINVAL;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("End with rc:%d\n", ret);
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
void stmvl53l0_exit_i2c(void *i2c_object)
|
||||||
|
{
|
||||||
|
vl53l0_dbgmsg("Enter\n");
|
||||||
|
i2c_del_driver(&stmvl53l0_driver);
|
||||||
|
|
||||||
|
vl53l0_dbgmsg("End\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* end of NOT CAMERA_CCI */
|
2878
drivers/input/misc/vl53L0/stmvl53l0_module.c
Normal file
2878
drivers/input/misc/vl53L0/stmvl53l0_module.c
Normal file
File diff suppressed because it is too large
Load diff
Loading…
Add table
Reference in a new issue