Paparazzi UAS  v5.18.0_stable
Paparazzi is a free software Unmanned Aircraft System.
vl53l1x_api.h
Go to the documentation of this file.
1 /*
2 * Copyright (c) 2017, STMicroelectronics - All Rights Reserved
3 *
4 * This file : part of VL53L1 Core and : dual licensed,
5 * either 'STMicroelectronics
6 * Proprietary license'
7 * or 'BSD 3-clause "New" or "Revised" License' , at your option.
8 *
9 ********************************************************************************
10 *
11 * 'STMicroelectronics Proprietary license'
12 *
13 ********************************************************************************
14 *
15 * License terms: STMicroelectronics Proprietary in accordance with licensing
16 * terms at www.st.com/sla0081
17 *
18 * STMicroelectronics confidential
19 * Reproduction and Communication of this document : strictly prohibited unless
20 * specifically authorized in writing by STMicroelectronics.
21 *
22 *
23 ********************************************************************************
24 *
25 * Alternatively, VL53L1 Core may be distributed under the terms of
26 * 'BSD 3-clause "New" or "Revised" License', in which case the following
27 * provisions apply instead of the ones mentioned above :
28 *
29 ********************************************************************************
30 *
31 * License terms: BSD 3-clause "New" or "Revised" License.
32 *
33 * Redistribution and use in source and binary forms, with or without
34 * modification, are permitted provided that the following conditions are met:
35 *
36 * 1. Redistributions of source code must retain the above copyright notice, this
37 * list of conditions and the following disclaimer.
38 *
39 * 2. Redistributions in binary form must reproduce the above copyright notice,
40 * this list of conditions and the following disclaimer in the documentation
41 * and/or other materials provided with the distribution.
42 *
43 * 3. Neither the name of the copyright holder nor the names of its contributors
44 * may be used to endorse or promote products derived from this software
45 * without specific prior written permission.
46 *
47 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
48 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
49 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
50 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
51 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
52 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
53 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
54 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
55 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
56 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
57 *
58 *
59 ********************************************************************************
60 *
61 */
62 
68 #ifndef VL53L1X_API_H_
69 #define VL53L1X_API_H_
70 
71 #include "vl53l1_platform.h"
72 
73 #define VL53L1X_IMPLEMENTATION_VER_MAJOR 3
74 #define VL53L1X_IMPLEMENTATION_VER_MINOR 3
75 #define VL53L1X_IMPLEMENTATION_VER_SUB 0
76 #define VL53L1X_IMPLEMENTATION_VER_REVISION 0000
77 
79 
80 #define SOFT_RESET 0x0000
81 #define VL53L1_I2C_SLAVE__DEVICE_ADDRESS 0x0001
82 #define VL53L1_VHV_CONFIG__TIMEOUT_MACROP_LOOP_BOUND 0x0008
83 #define ALGO__CROSSTALK_COMPENSATION_PLANE_OFFSET_KCPS 0x0016
84 #define ALGO__CROSSTALK_COMPENSATION_X_PLANE_GRADIENT_KCPS 0x0018
85 #define ALGO__CROSSTALK_COMPENSATION_Y_PLANE_GRADIENT_KCPS 0x001A
86 #define ALGO__PART_TO_PART_RANGE_OFFSET_MM 0x001E
87 #define MM_CONFIG__INNER_OFFSET_MM 0x0020
88 #define MM_CONFIG__OUTER_OFFSET_MM 0x0022
89 #define GPIO_HV_MUX__CTRL 0x0030
90 #define GPIO__TIO_HV_STATUS 0x0031
91 #define SYSTEM__INTERRUPT_CONFIG_GPIO 0x0046
92 #define PHASECAL_CONFIG__TIMEOUT_MACROP 0x004B
93 #define RANGE_CONFIG__TIMEOUT_MACROP_A_HI 0x005E
94 #define RANGE_CONFIG__VCSEL_PERIOD_A 0x0060
95 #define RANGE_CONFIG__VCSEL_PERIOD_B 0x0063
96 #define RANGE_CONFIG__TIMEOUT_MACROP_B_HI 0x0061
97 #define RANGE_CONFIG__TIMEOUT_MACROP_B_LO 0x0062
98 #define RANGE_CONFIG__SIGMA_THRESH 0x0064
99 #define RANGE_CONFIG__MIN_COUNT_RATE_RTN_LIMIT_MCPS 0x0066
100 #define RANGE_CONFIG__VALID_PHASE_HIGH 0x0069
101 #define VL53L1_SYSTEM__INTERMEASUREMENT_PERIOD 0x006C
102 #define SYSTEM__THRESH_HIGH 0x0072
103 #define SYSTEM__THRESH_LOW 0x0074
104 #define SD_CONFIG__WOI_SD0 0x0078
105 #define SD_CONFIG__INITIAL_PHASE_SD0 0x007A
106 #define ROI_CONFIG__USER_ROI_CENTRE_SPAD 0x007F
107 #define ROI_CONFIG__USER_ROI_REQUESTED_GLOBAL_XY_SIZE 0x0080
108 #define SYSTEM__SEQUENCE_CONFIG 0x0081
109 #define VL53L1_SYSTEM__GROUPED_PARAMETER_HOLD 0x0082
110 #define SYSTEM__INTERRUPT_CLEAR 0x0086
111 #define SYSTEM__MODE_START 0x0087
112 #define VL53L1_RESULT__RANGE_STATUS 0x0089
113 #define VL53L1_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0 0x008C
114 #define RESULT__AMBIENT_COUNT_RATE_MCPS_SD 0x0090
115 #define VL53L1_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0 0x0096
116 #define VL53L1_RESULT__PEAK_SIGNAL_COUNT_RATE_CROSSTALK_CORRECTED_MCPS_SD0 0x0098
117 #define VL53L1_RESULT__OSC_CALIBRATE_VAL 0x00DE
118 #define VL53L1_FIRMWARE__SYSTEM_STATUS 0x00E5
119 #define VL53L1_IDENTIFICATION__MODEL_ID 0x010F
120 #define VL53L1_ROI_CONFIG__MODE_ROI_CENTRE_SPAD 0x013E
121 
122 /****************************************
123  * PRIVATE define do not edit
124  ****************************************/
125 
129 typedef struct {
130  uint8_t major;
131  uint8_t minor;
132  uint8_t build;
133  uint32_t revision;
135 
139 typedef struct {
146 
151 
156 
163 
168 void VL53L1X_BootDevice(VL53L1_DEV dev, uint16_t TimingBudgetInMs, uint16_t DistanceMode, uint32_t InterMeasurementInMs);
169 
175 
181 
187 
194 
199 
205 
211 
216 
223 
228 
235  uint32_t InterMeasurementInMs);
236 
241 
246 
251 
256 
262 
267 
272 
277 
282 
288 
293 
299 
304 
310 
315 
330  uint16_t ThreshHigh, uint8_t Window,
331  uint8_t IntOnNoTarget);
332 
337 
342 
347 
355 
360 
366 
371 
376 
381 
386 
391 
398 
399 #endif
uint16_t
unsigned short uint16_t
Definition: types.h:16
VL53L1X_GetROICenter
VL53L1X_ERROR VL53L1X_GetROICenter(VL53L1_DEV dev, uint8_t *ROICenter)
This function returns the current user ROI center.
Definition: vl53l1x_api.c:792
VL53L1X_CheckForDataReady
VL53L1X_ERROR VL53L1X_CheckForDataReady(VL53L1_DEV dev, uint8_t *isDataReady)
This function checks if the new ranging data is available by polling the dedicated register.
Definition: vl53l1x_api.c:324
VL53L1X_GetROI_XY
VL53L1X_ERROR VL53L1X_GetROI_XY(VL53L1_DEV dev, uint16_t *ROI_X, uint16_t *ROI_Y)
This function returns width X and height Y.
Definition: vl53l1x_api.c:822
VL53L1X_SetROI
VL53L1X_ERROR VL53L1X_SetROI(VL53L1_DEV dev, uint16_t X, uint16_t Y)
This function programs the ROI (Region of Interest) The ROI position is centered, only the ROI size c...
Definition: vl53l1x_api.c:801
VL53L1X_GetDistance
VL53L1X_ERROR VL53L1X_GetDistance(VL53L1_DEV dev, uint16_t *distance)
This function returns the distance measured by the sensor in mm.
Definition: vl53l1x_api.c:584
VL53L1X_StartTemperatureUpdate
VL53L1X_ERROR VL53L1X_StartTemperatureUpdate(VL53L1_DEV dev)
This function performs the temperature calibration.
Definition: vl53l1x_api.c:875
VL53L1X_GetSensorId
VL53L1X_ERROR VL53L1X_GetSensorId(VL53L1_DEV dev, uint16_t *id)
This function returns the sensor id, sensor Id must be 0xEEAC.
Definition: vl53l1x_api.c:574
VL53L1X_GetInterMeasurementInMs
VL53L1X_ERROR VL53L1X_GetInterMeasurementInMs(VL53L1_DEV dev, uint16_t *pIM)
This function returns the Intermeasurement period in ms.
Definition: vl53l1x_api.c:550
VL53L1X_ClearInterrupt
VL53L1X_ERROR VL53L1X_ClearInterrupt(VL53L1_DEV dev)
This function clears the interrupt, to be called after a ranging data reading to arm the interrupt fo...
Definition: vl53l1x_api.c:278
VL53L1X_GetRangeStatus
VL53L1X_ERROR VL53L1X_GetRangeStatus(VL53L1_DEV dev, uint8_t *rangeStatus)
This function returns the ranging status error (0:no error, 1:sigma failed, 2:signal failed,...
Definition: vl53l1x_api.c:651
VL53L1X_Result_t::Ambient
uint16_t Ambient
Definition: vl53l1x_api.h:142
VL53L1X_GetInterruptPolarity
VL53L1X_ERROR VL53L1X_GetInterruptPolarity(VL53L1_DEV dev, uint8_t *pIntPol)
This function returns the current interrupt polarity 1=active high (default), 0=active low.
Definition: vl53l1x_api.c:297
uint32_t
unsigned long uint32_t
Definition: types.h:18
VL53L1X_SensorInit
VL53L1X_ERROR VL53L1X_SensorInit(VL53L1_DEV dev)
This function loads the 135 bytes default values to initialize the sensor.
Definition: vl53l1x_api.c:238
VL53L1X_SetI2CAddress
VL53L1X_ERROR VL53L1X_SetI2CAddress(VL53L1_DEV, uint8_t new_address)
This function sets the sensor I2C address used in case multiple devices application,...
Definition: vl53l1x_api.c:229
VL53L1X_BootState
VL53L1X_ERROR VL53L1X_BootState(VL53L1_DEV dev, uint8_t *state)
This function returns the boot state of the device (1:booted, 0:not booted)
Definition: vl53l1x_api.c:564
VL53L1X_GetAmbientRate
VL53L1X_ERROR VL53L1X_GetAmbientRate(VL53L1_DEV dev, uint16_t *ambRate)
This function returns the ambient rate in kcps.
Definition: vl53l1x_api.c:641
VL53L1X_GetXtalk
VL53L1X_ERROR VL53L1X_GetXtalk(VL53L1_DEV dev, uint16_t *Xtalk)
This function returns the current programmed xtalk correction value in cps.
Definition: vl53l1x_api.c:725
VL53L1X_SetDistanceThreshold
VL53L1X_ERROR VL53L1X_SetDistanceThreshold(VL53L1_DEV dev, uint16_t ThreshLow, uint16_t ThreshHigh, uint8_t Window, uint8_t IntOnNoTarget)
This function programs the threshold detection mode Example: VL53L1X_SetDistanceThreshold(dev,...
Definition: vl53l1x_api.c:735
VL53L1X_GetSignalRate
VL53L1X_ERROR VL53L1X_GetSignalRate(VL53L1_DEV dev, uint16_t *signalRate)
This function returns the returned signal in kcps.
Definition: vl53l1x_api.c:619
VL53L1X_Result_t::NumSPADs
uint16_t NumSPADs
Definition: vl53l1x_api.h:144
VL53L1X_GetDistanceThresholdHigh
VL53L1X_ERROR VL53L1X_GetDistanceThresholdHigh(VL53L1_DEV dev, uint16_t *high)
This function returns the high threshold in mm.
Definition: vl53l1x_api.c:775
VL53L1X_StopRanging
VL53L1X_ERROR VL53L1X_StopRanging(VL53L1_DEV dev)
This function stops the ranging.
Definition: vl53l1x_api.c:316
VL53L1X_GetDistanceThresholdWindow
VL53L1X_ERROR VL53L1X_GetDistanceThresholdWindow(VL53L1_DEV dev, uint16_t *window)
This function returns the window detection mode (0=below; 1=above; 2=out; 3=in)
Definition: vl53l1x_api.c:756
VL53L1X_SetSigmaThreshold
VL53L1X_ERROR VL53L1X_SetSigmaThreshold(VL53L1_DEV dev, uint16_t sigma)
This function programs a new sigma threshold in mm (default=15 mm)
Definition: vl53l1x_api.c:852
VL53L1X_GetSWVersion
VL53L1X_ERROR VL53L1X_GetSWVersion(VL53L1X_Version_t *pVersion)
This function returns the SW driver version.
Definition: vl53l1x_api.c:218
VL53L1X_Result_t
defines packed reading results type
Definition: vl53l1x_api.h:139
VL53L1X_GetSigmaThreshold
VL53L1X_ERROR VL53L1X_GetSigmaThreshold(VL53L1_DEV dev, uint16_t *signal)
This function returns the current sigma threshold in mm.
Definition: vl53l1x_api.c:864
VL53L1X_SetTimingBudgetInMs
VL53L1X_ERROR VL53L1X_SetTimingBudgetInMs(VL53L1_DEV dev, uint16_t TimingBudgetInMs)
This function programs the timing budget in ms.
Definition: vl53l1x_api.c:343
dev
static const struct usb_device_descriptor dev
Definition: usb_ser_hw.c:74
VL53L1X_SetSignalThreshold
VL53L1X_ERROR VL53L1X_SetSignalThreshold(VL53L1_DEV dev, uint16_t signal)
This function programs a new signal threshold in kcps (default=1024 kcps .
Definition: vl53l1x_api.c:833
VL53L1X_GetOffset
VL53L1X_ERROR VL53L1X_GetOffset(VL53L1_DEV dev, int16_t *Offset)
This function returns the programmed offset correction value in mm.
Definition: vl53l1x_api.c:698
int16_t
signed short int16_t
Definition: types.h:17
VL53L1X_GetSignalThreshold
VL53L1X_ERROR VL53L1X_GetSignalThreshold(VL53L1_DEV dev, uint16_t *signal)
This function returns the current signal threshold in kcps.
Definition: vl53l1x_api.c:841
VL53L1X_GetDistanceThresholdLow
VL53L1X_ERROR VL53L1X_GetDistanceThresholdLow(VL53L1_DEV dev, uint16_t *low)
This function returns the low threshold in mm.
Definition: vl53l1x_api.c:765
uint8_t
unsigned char uint8_t
Definition: types.h:14
VL53L1X_BootDevice
void VL53L1X_BootDevice(VL53L1_DEV dev, uint16_t TimingBudgetInMs, uint16_t DistanceMode, uint32_t InterMeasurementInMs)
Implement boot sequence of VL53L1 device as described in documentation See VL53L1X_SetTimingBudgetInM...
Definition: vl53l1x_api.c:262
VL53L1X_GetDistanceMode
VL53L1X_ERROR VL53L1X_GetDistanceMode(VL53L1_DEV dev, uint16_t *pDistanceMode)
This function returns the current distance mode (1=short, 2=long).
Definition: vl53l1x_api.c:523
VL53L1X_Result_t::SigPerSPAD
uint16_t SigPerSPAD
Definition: vl53l1x_api.h:143
VL53L1X_ERROR
int8_t VL53L1X_ERROR
Definition: vl53l1x_api.h:78
VL53L1X_GetAmbientPerSpad
VL53L1X_ERROR VL53L1X_GetAmbientPerSpad(VL53L1_DEV dev, uint16_t *amb)
This function returns the ambient per SPAD in kcps/SPAD.
Definition: vl53l1x_api.c:608
VL53L1X_SetXtalk
VL53L1X_ERROR VL53L1X_SetXtalk(VL53L1_DEV dev, uint16_t XtalkValue)
This function programs the xtalk correction value in cps (Count Per Second).
Definition: vl53l1x_api.c:710
int8_t
signed char int8_t
Definition: types.h:15
VL53L1X_SetDistanceMode
VL53L1X_ERROR VL53L1X_SetDistanceMode(VL53L1_DEV dev, uint16_t DistanceMode)
This function programs the distance mode (1=short, 2=long(default)).
Definition: vl53l1x_api.c:486
VL53L1X_SetInterruptPolarity
VL53L1X_ERROR VL53L1X_SetInterruptPolarity(VL53L1_DEV dev, uint8_t IntPol)
This function programs the interrupt polarity 1=active high (default), 0=active low.
Definition: vl53l1x_api.c:286
VL53L1X_Version_t
defines SW Version
Definition: vl53l1x_api.h:129
VL53L1X_GetTimingBudgetInMs
VL53L1X_ERROR VL53L1X_GetTimingBudgetInMs(VL53L1_DEV dev, uint16_t *pTimingBudgetInMs)
This function returns the current timing budget in ms.
Definition: vl53l1x_api.c:445
vl53l1_platform.h
Those platform functions are platform dependent and have to be implemented by the user.
VL53L1X_GetSignalPerSpad
VL53L1X_ERROR VL53L1X_GetSignalPerSpad(VL53L1_DEV dev, uint16_t *signalPerSp)
This function returns the returned signal per SPAD in kcps/SPAD.
Definition: vl53l1x_api.c:595
VL53L1X_SetROICenter
VL53L1X_ERROR VL53L1X_SetROICenter(VL53L1_DEV dev, uint8_t ROICenter)
This function programs the new user ROI center, please to be aware that there is no check in this fun...
Definition: vl53l1x_api.c:785
VL53L1X_Result_t::Status
uint8_t Status
Definition: vl53l1x_api.h:140
VL53L1X_SetOffset
VL53L1X_ERROR VL53L1X_SetOffset(VL53L1_DEV dev, int16_t OffsetValue)
This function programs the offset correction in mm.
Definition: vl53l1x_api.c:685
VL53L1X_SetInterMeasurementInMs
VL53L1X_ERROR VL53L1X_SetInterMeasurementInMs(VL53L1_DEV dev, uint32_t InterMeasurementInMs)
This function programs the Intermeasurement period in ms Intermeasurement period must be >/= timing b...
Definition: vl53l1x_api.c:537
VL53L1X_GetSpadNb
VL53L1X_ERROR VL53L1X_GetSpadNb(VL53L1_DEV dev, uint16_t *spNb)
This function returns the current number of enabled SPADs.
Definition: vl53l1x_api.c:630
state
struct State state
Definition: state.c:36
VL53L1_Dev_t
Definition: vl53l1_platform.h:50
mesonh.mesonh_atmosphere.Y
int Y
Definition: mesonh_atmosphere.py:44
VL53L1X_Result_t::Distance
uint16_t Distance
Definition: vl53l1x_api.h:141
VL53L1X_GetResult
VL53L1X_ERROR VL53L1X_GetResult(VL53L1_DEV dev, VL53L1X_Result_t *pResult)
This function returns measurements and the range status in a single read access.
Definition: vl53l1x_api.c:665
mesonh.mesonh_atmosphere.X
int X
Definition: mesonh_atmosphere.py:43
VL53L1X_StartRanging
VL53L1X_ERROR VL53L1X_StartRanging(VL53L1_DEV dev)
This function starts the ranging distance operation The ranging operation is continuous.
Definition: vl53l1x_api.c:308