vl53l1_ll_def.h
Go to the documentation of this file.
1 /*
2 * Copyright (c) 2017, STMicroelectronics - All Rights Reserved
3 *
4 * This file is part of VL53L1 Core and is 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 is 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 
71 #ifndef _VL53L1_LL_DEF_H_
72 #define _VL53L1_LL_DEF_H_
73 
74 #include "vl53l1_ll_device.h"
75 #include "vl53l1_error_codes.h"
80 
81 #ifdef __cplusplus
82 extern "C" {
83 #endif
84 
91 #define VL53L1_LL_API_IMPLEMENTATION_VER_MAJOR 1
92 
93 #define VL53L1_LL_API_IMPLEMENTATION_VER_MINOR 2
94 
95 #define VL53L1_LL_API_IMPLEMENTATION_VER_SUB 10
96 
97 #define VL53L1_LL_API_IMPLEMENTATION_VER_REVISION 1840
98 
99 #define VL53L1_LL_API_IMPLEMENTATION_VER_STRING "1.2.11.1840"
100 
102 #define VL53L1_FIRMWARE_VER_MINIMUM 398
103 #define VL53L1_FIRMWARE_VER_MAXIMUM 400
104 
105 
106 /****************************************
107  * PRIVATE define do not edit
108  ****************************************/
109 
110 #define VL53L1_LL_CALIBRATION_DATA_STRUCT_VERSION 0xECAB0102
111 
113 /* Start Patch_ZoneCalDataStructVersion_11854 */
114 
115 #define VL53L1_LL_ZONE_CALIBRATION_DATA_STRUCT_VERSION 0xECAE0101
116 
118 /* End Patch_ZoneCalDataStructVersion_11854 */
119 
120 #define VL53L1_MAX_OFFSET_RANGE_RESULTS 3
121 
125 #define VL53L1_NVM_MAX_FMT_RANGE_DATA 4
126 
128 #define VL53L1_NVM_PEAK_RATE_MAP_SAMPLES 25
129 
130 #define VL53L1_NVM_PEAK_RATE_MAP_WIDTH 5
131 
132 #define VL53L1_NVM_PEAK_RATE_MAP_HEIGHT 5
133 
140 #define VL53L1_ERROR_DEVICE_FIRMWARE_TOO_OLD ((VL53L1_Error) - 80)
141 
142 #define VL53L1_ERROR_DEVICE_FIRMWARE_TOO_NEW ((VL53L1_Error) - 85)
143 
144 #define VL53L1_ERROR_UNIT_TEST_FAIL ((VL53L1_Error) - 90)
145 
146 #define VL53L1_ERROR_FILE_READ_FAIL ((VL53L1_Error) - 95)
147 
148 #define VL53L1_ERROR_FILE_WRITE_FAIL ((VL53L1_Error) - 96)
149 
157 typedef struct {
163 
164 
168 typedef struct {
169 
181 
182 
187 typedef struct {
188 
207 
208 
212 typedef struct {
213 
214 
243 
244 
254 typedef struct {
255 
256 
394 
395 
396 
401 typedef struct {
402 
407 
408 
413 typedef struct {
414 
421 
422 
430 typedef struct {
431 
434 
437 
442 
445 
451 
452  /* -- thresholds -- */
453  /* The struct holds a copy of the thresholds but they are written when
454  * this structure is set using VL53L1_set_GPIO_interrupt_config/_struct
455  * */
456 
459 
462 
465 
468 
470 
471 /* Start Patch_LowPowerAutoMode */
480 typedef struct {
481 
487 
490 
494 
497 
500 
503 
506 
509 
512 
514 
515 /* End Patch_LowPowerAutoMode */
516 
523 typedef struct {
524 
525  /* Info size */
526 
554  /* Event counts */
555 
565  /* Rates */
566 
578  /* Sigma */
579 
583  /* Phase */
584 
588  /* Range */
589 
595  /* Range status */
596 
598 
600 
601 
608 typedef struct {
609 
624 
633 typedef struct {
634 
656 
657 
665 typedef struct {
666 
682 
692 typedef struct {
693 
704 
705 
714 typedef struct {
715 
728 
729 
737 typedef struct {
738 
743 
744 
752 typedef struct {
753 
774 
778 typedef struct {
779 
804 
805 
806 
814 typedef struct {
815 
846 
849 
852 
860 
863 
866 
872 
882 
885 
889 
890  /* Start Patch_LowPowerAutoMode */
893  /* End Patch_LowPowerAutoMode */
894 
895 #ifdef PAL_EXTENDED
896  /* Patch Debug Data */
897  VL53L1_patch_results_t patch_results;
898  VL53L1_shadow_core_results_t shadow_core_results;
899  VL53L1_shadow_system_results_t shadow_sys_results;
900  VL53L1_prev_shadow_core_results_t prev_shadow_core_results;
901  VL53L1_prev_shadow_system_results_t prev_shadow_sys_results;
902 #endif
903 
905 
906 
914 typedef struct {
915 
916  /* Private last range results */
918 
920 
928 typedef struct {
929 
936 
938 
939 
947 typedef struct {
1006 
1007 
1019 typedef struct {
1020 
1035 
1036 
1037 /* Start Patch_AdditionalDebugData_11823 */
1038 
1046 typedef struct {
1047 
1065 
1066 /* End Patch_AdditionalDebugData_11823 */
1067 
1068 
1072 #define SUPPRESS_UNUSED_WARNING(x) \
1073  ((void) (x))
1074 
1075 
1076 #define IGNORE_STATUS(__FUNCTION_ID__, __ERROR_STATUS_CHECK__, __STATUS__) \
1077  do { \
1078  DISABLE_WARNINGS(); \
1079  if (__FUNCTION_ID__) { \
1080  if (__STATUS__ == __ERROR_STATUS_CHECK__) { \
1081  __STATUS__ = VL53L1_ERROR_NONE; \
1082  WARN_OVERRIDE_STATUS(__FUNCTION_ID__); \
1083  } \
1084  } \
1085  ENABLE_WARNINGS(); \
1086  } \
1087  while (0)
1088 
1089 #define VL53L1_COPYSTRING(str, ...) \
1090  (strncpy(str, ##__VA_ARGS__, VL53L1_MAX_STRING_LENGTH-1))
1091 
1092 #ifdef __cplusplus
1093 }
1094 #endif
1095 
1096 #endif /* _VL53L1_LL_DEF_H_ */
1097 
1098 
Error Code definitions for VL53L1 API.
VL53L1_ll_driver_state_t ll_state
VL53L1_optical_centre_t optical_centre
VL53L1_DeviceSscArray array_select
VL53L1_user_zone_t mm_roi
uint32_t vl53l1_tuningparm_refspadchar_phasecal_timeout_us
uint16_t vl53l1_tuningparm_refspadchar_min_countrate_limit_mcps
uint32_t vl53l1_tuningparm_lite_mm_config_timeout_us
uint16_t vl53l1_tuningparm_lite_short_min_count_rate_rtn_mcps
VL53L1 LL Driver ST private data structure .
VL53L1_static_nvm_managed_t stat_nvm
Reference SPAD Characterization (RefSpadChar) Config.
uint8_t vl53l1_tuningparm_lowpowerauto_vhv_loop_bound
uint32_t inter_measurement_period_ms
VL53L1_core_results_t core_results
Structure to hold state, tuning and output variables for the low power auto mode (Presence) ...
uint16_t vl53l1_tuningparm_lite_med_min_count_rate_rtn_mcps
uint32_t total_periods_elapsed
VL53L1_gain_calibration_data_t gain_cal
uint16_t vl53l1_tuningparm_spadmap_rate_limit_mcps
uint32_t vl53l1_tuningparm_timed_mm_config_timeout_us
uint32_t vl53l1_tuningparm_offset_cal_phasecal_timeout_us
VL53L1_OffsetCorrectionMode offset_correction_mode
VL53L1_OffsetCalibrationMode offset_calibration_mode
EwokPlus25 LL Driver definitions for control of error handling in LL driver.
VL53L1_additional_offset_cal_data_t add_off_cal_data
uint8_t vl53l1_tuningparm_offset_cal_mm2_samples
uint16_t vl53l1_tuningparm_refspadchar_max_countrate_limit_mcps
uint16_t ambient_count_rate_mcps
uint16_t dss_config__target_total_rate_mcps
VL53L1_refspadchar_config_t refspadchar
uint32_t nvm_default__crosstalk_compensation_plane_offset_kcps
int16_t lite_mode_crosstalk_margin_kcps
VL53L1_timing_config_t tim_cfg
short int16_t
Typedef defining 16 bit short type. The developer should modify this to suit the platform being deplo...
Definition: vl53l1_types.h:128
uint16_t zero_distance_phase
All end user OS/platform/application definitions.
SPAD Rate Data output by SSC.
uint32_t ambient_window_events
uint8_t vl53l1_tuningparm_timed_seed_config
VL53L1_additional_offset_cal_data_t add_off_cal_data
uint16_t vl53l1_tuningparm_lite_short_sigma_thresh_mm
int8_t VL53L1_Error
Defines User Zone(ROI) parameters.
VL53L1_offset_range_results_t offset_results
uint8_t vl53l1_tuningparm_spadmap_vcsel_period
VL53L1_general_config_t gen_cfg
VL53L1_DeviceState rd_device_state
VL53L1_DeviceState rd_device_state
uint16_t dss_config__target_total_rate_mcps
VL53L1_DeviceMeasurementModes measurement_mode
VL53L1_GPIO_interrupt_config_t gpio_interrupt_config
uint32_t fw_ready_poll_duration_ms
uint32_t vl53l1_tuningparm_offset_cal_mm_timeout_us
uint16_t vl53l1_tuningparm_lite_cal_repeat_rate
VL53L1_GPIO_Interrupt_Mode intr_mode_rate
VL53L1_DevicePresetModes preset_mode
uint32_t ranging_total_events
VL53L1_gain_calibration_data_t gain_cal
uint16_t vl53l1_tuningparm_lite_med_sigma_thresh_mm
Structure for storing the set of range results required for the offset calibration functions...
VL53L1_system_results_t sys_results
uint16_t peak_signal_count_rate_mcps
uint32_t vl53l1_tuningparm_timed_range_config_timeout_us
uint16_t vl53l1_tuningparm_lite_ranging_gain_factor
VL53L1_xtalk_config_t xtalk_cfg
uint8_t vl53l1_tuningparm_lite_min_clip_mm
int16_t algo__crosstalk_compensation_x_plane_gradient_kcps
uint16_t vl53l1_tuningparm_lite_dss_config_target_total_rate_mcps
#define VL53L1_NO_OF_SPAD_ENABLES
LL Driver Device specific defines. To be adapted by implementer for the targeted device.
uint8_t vl53l1_tuningparm_offset_cal_pre_samples
VL53L1_DevicePresetModes preset_mode
uint8_t vl53l1_tuningparm_initial_phase_ref_lite_med_range
uint8_t vl53l1_tuningparm_refspadchar_vcsel_period
uint8_t vl53l1_tuningparm_refspadchar_device_test_mode
uint32_t algo__crosstalk_compensation_plane_offset_kcps
uint8_t VL53L1_OffsetCorrectionMode
int16_t nvm_default__crosstalk_compensation_y_plane_gradient_kcps
uint32_t peak_rate_per_spad_kcps
uint8_t vl53l1_tuningparm_initial_phase_rtn_lite_med_range
VL53L1_system_control_t sys_ctrl
uint16_t crosstalk_range_ignore_threshold_rate_mcps
Contains the driver state information.
Defines the parameters of the LL driver Get Version Functions.
Xtalk Extraction and Paramter Config.
uint32_t vl53l1_tuningparm_timed_phasecal_config_timeout_us
uint8_t vl53l1_tuningparm_lite_sigma_ref_mm
int int32_t
Typedef defining 32 bit int type. The developer should modify this to suit the platform being deploye...
Definition: vl53l1_types.h:118
uint8_t crosstalk_range_ignore_threshold_mult
uint16_t dss_config__manual_effective_spads_select
#define VL53L1_NVM_PEAK_RATE_MAP_SAMPLES
VL53L1_ssc_config_t ssc_cfg
uint8_t vl53l1_tuningparm_lite_sigma_est_pulse_width
uint8_t vl53l1_tuningparm_offset_cal_mm1_samples
uint8_t vl53l1_tuningparm_lite_seed_config
uint16_t avg_signal_count_rate_mcps
uint8_t vl53l1_tuningparm_initial_phase_ref_lite_long_range
VL53L1_optical_centre_t optical_centre
VL53L1_static_config_t stat_cfg
VL53L1_dynamic_config_t dyn_cfg
Structure for storing the calibration peak rate map Used by DMAX to understand the spatial roll off i...
VL53L1_DeviceState cfg_device_state
#define VL53L1_RTN_SPAD_BUFFER_SIZE
VL53L1_debug_results_t dbg_results
uint16_t fast_osc_frequency
uint32_t vl53l1_tuningparm_lowpowerauto_mm_config_timeout_us
uint8_t vl53l1_tuningparm_lite_first_order_select
VL53L1_DeviceMeasurementModes measurement_mode
int16_t vl53l1_tuningparm_lite_xtalk_margin_kcps
Structure to configure conditions when GPIO interrupt is trigerred.
uint8_t VL53L1_DeviceState
uint16_t vl53l1_tuningparm_timed_dss_config_target_total_rate_mcps
VL53L1_low_power_auto_data_t low_power_auto_data
uint16_t vl53l1_tuningparm_lite_long_sigma_thresh_mm
uint16_t vl53l1_tuningparm_key_table_version
VL53L1_range_results_t range_results
VL53L1_nvm_copy_data_t nvm_copy_data
uint8_t VL53L1_GPIO_Interrupt_Mode
uint16_t tp_lite_long_min_count_rate_rtn_mcps
uint8_t global_crosstalk_compensation_enable
VL53L1_DeviceState cfg_device_state
uint16_t tp_lite_med_min_count_rate_rtn_mcps
Additional debug data.
VL53L1_offsetcal_config_t offsetcal_cfg
uint16_t dss_config__target_total_rate_mcps
#define VL53L1_MAX_OFFSET_RANGE_RESULTS
Structure for storing the set of range results required for the mm1 and mm2 offset calibration functi...
VL53L1_customer_nvm_managed_t customer
SPAD Self Check (SSC) Config data structure.
uint8_t vl53l1_tuningparm_lite_sigma_est_amb_width_ns
Optical Centre data.
Tuning Parameters Debug data.
EwokPlus compile time user modifiable configuration.
uint32_t vl53l1_tuningparm_offset_cal_range_timeout_us
VL53L1_cal_peak_rate_map_t cal_peak_rate_map
uint16_t actual_effective_spads
VL53L1_tuning_parm_storage_t tuning_parms
uint8_t vl53l1_tuningparm_consistency_lite_phase_tolerance
uint8_t VL53L1_OffsetCalibrationMode
uint16_t vl53l1_tuningparm_refspadchar_target_count_rate_mcps
uint32_t vl53l1_tuningparm_lite_range_config_timeout_us
uint8_t vl53l1_tuningparm_initial_phase_rtn_lite_short_range
uint8_t vl53l1_tuningparm_initial_phase_ref_lite_short_range
VL53L1 LL Driver ST private results structure.
uint8_t VL53L1_DevicePresetModes
Gain calibration data.
uint8_t VL53L1_DeviceSscArray
uint32_t vl53l1_tuningparm_lowpowerauto_range_config_timeout_us
int16_t algo__crosstalk_compensation_y_plane_gradient_kcps
VL53L1_GPIO_Interrupt_Mode intr_mode_distance
VL53L1_customer_nvm_managed_t customer
uint8_t VL53L1_DeviceMeasurementModes
TuningParameter Storage.
Additional Offset Calibration Data.
uint8_t vl53l1_tuningparm_initial_phase_rtn_lite_long_range
uint16_t total_rate_per_spad_mcps
VL53L1 Register Structure definitions.
Structure for storing the set of range results.
Per Part calibration data.
uint16_t vl53l1_tuningparm_offset_cal_dss_rate_mcps
Run Offset Cal Function (offsetcal) Config.
VL53L1_ll_version_t version
unsigned short uint16_t
Typedef defining 16 bit unsigned short type. The developer should modify this to suit the platform be...
Definition: vl53l1_types.h:123
VL53L1_cal_peak_rate_map_t cal_peak_rate_map
uint32_t range_config_timeout_us
uint8_t vl53l1_tuningparm_spadmap_vcsel_start
uint32_t vl53l1_tuningparm_lite_phasecal_config_timeout_us
uint32_t phasecal_config_timeout_us
uint16_t vl53l1_tuningparm_lite_long_min_count_rate_rtn_mcps
int16_t nvm_default__crosstalk_compensation_x_plane_gradient_kcps
unsigned char uint8_t
Typedef defining 8 bit unsigned char type. The developer should modify this to suit the platform bein...
Definition: vl53l1_types.h:133
Internal data structure for storing post processed ranges.
unsigned int uint32_t
Typedef defining 32 bit unsigned int type. The developer should modify this to suit the platform bein...
Definition: vl53l1_types.h:113
uint16_t tp_lite_short_min_count_rate_rtn_mcps


vl53l1x
Author(s):
autogenerated on Sat Dec 10 2022 03:15:50