84 #ifdef VL53L1_LOG_ENABLE 88 #define LOG_FUNCTION_START(fmt, ...) \ 89 _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_CORE, fmt, ##__VA_ARGS__) 90 #define LOG_FUNCTION_END(status, ...) \ 91 _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_CORE, status, ##__VA_ARGS__) 92 #define LOG_FUNCTION_END_FMT(status, fmt, ...) \ 93 _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_CORE, status, \ 96 #define trace_print(level, ...) \ 97 _LOG_TRACE_PRINT(VL53L1_TRACE_MODULE_CORE, \ 98 level, VL53L1_TRACE_FUNCTION_NONE, ##__VA_ARGS__) 100 #define VL53L1_MAX_I2C_XFER_SIZE 256 206 #ifndef VL53L1_NOCALIB 213 #ifndef VL53L1_NOCALIB 229 #ifndef VL53L1_NOCALIB 266 #ifdef VL53L1_LOG_ENABLE 270 VL53L1_print_static_nvm_managed(
272 "data_init():pdev->lldata.stat_nvm.",
273 VL53L1_TRACE_MODULE_DATA_INIT);
275 VL53L1_print_customer_nvm_managed(
277 "data_init():pdev->lldata.customer.",
278 VL53L1_TRACE_MODULE_DATA_INIT);
280 VL53L1_print_nvm_copy_data(
282 "data_init():pdev->lldata.nvm_copy_data.",
283 VL53L1_TRACE_MODULE_DATA_INIT);
285 VL53L1_print_additional_offset_cal_data(
287 "data_init():pdev->lldata.add_off_cal_data.",
288 VL53L1_TRACE_MODULE_DATA_INIT);
290 VL53L1_print_user_zone(
292 "data_init():pdev->lldata.mm_roi.",
293 VL53L1_TRACE_MODULE_DATA_INIT);
295 VL53L1_print_optical_centre(
297 "data_init():pdev->lldata.optical_centre.",
298 VL53L1_TRACE_MODULE_DATA_INIT);
300 VL53L1_print_cal_peak_rate_map(
302 "data_init():pdev->lldata.cal_peak_rate_map.",
303 VL53L1_TRACE_MODULE_DATA_INIT);
370 VL53L1_TRACE_LEVEL_WARNING,
371 "\nInvalid %s value (0x%04X) - forcing to 0x%04X\n\n",
372 "pdev->stat_nvm.osc_measured__fast_osc__frequency",
519 if (tempu32 > 0xFFFF) {
602 uint32_t inter_measurement_period_ms)
619 inter_measurement_period_ms *
631 uint32_t *pinter_measurement_period_ms)
646 *pinter_measurement_period_ms = \
647 pdev->tim_cfg.system__intermeasurement_period /
659 uint32_t phasecal_config_timeout_us,
685 phasecal_config_timeout_us,
686 mm_config_timeout_us,
687 range_config_timeout_us,
701 uint32_t *pphasecal_config_timeout_us,
732 *pphasecal_config_timeout_us =
741 timeout_encoded = (timeout_encoded << 8) +
744 *pmm_config_timeout_us =
753 timeout_encoded = (timeout_encoded << 8) +
756 *prange_config_timeout_us =
794 uint16_t *pcal_config__repeat_period)
826 uint8_t clr_mask = 0xFF - bit_mask;
827 uint8_t bit_value = value & bit_mask;
832 bit_mask = 0x01 << bit_id;
833 bit_value = bit_value << bit_id;
834 clr_mask = 0xFF - bit_mask;
869 bit_mask = 0x01 << bit_id;
876 *pvalue = *pvalue >> bit_id;
901 VL53L1_DEVICEINTERRUPTPOLARITY_CLEAR_MASK) | \
902 (interrupt_polarity & \
910 #ifndef VL53L1_NOCALIB 941 #ifndef VL53L1_NOCALIB 974 uint8_t range_ignore_thresh_mult,
975 uint16_t range_ignore_threshold_mcps)
986 range_ignore_threshold_mcps;
989 range_ignore_thresh_mult;
997 uint8_t *prange_ignore_thresh_mult,
998 uint16_t *prange_ignore_threshold_mcps_internal,
999 uint16_t *prange_ignore_threshold_mcps_current)
1014 *prange_ignore_thresh_mult =
1017 *prange_ignore_threshold_mcps_current =
1020 *prange_ignore_threshold_mcps_internal =
1041 *pinterrupt_polarity = \
1042 pdev->stat_cfg.gpio_hv_mux__ctrl & \
1043 VL53L1_DEVICEINTERRUPTPOLARITY_BIT_MASK ;
1105 &(puser_zone->
width),
1151 pmm_roi->
height = xy_size >> 4;
1152 pmm_roi->
width = xy_size & 0x0F;
1162 uint16_t *pdss_config__target_total_rate_mcps,
1163 uint32_t *pphasecal_config_timeout_us,
1165 uint32_t *prange_config_timeout_us)
1173 switch (device_preset_mode) {
1181 *pdss_config__target_total_rate_mcps =
1183 *pphasecal_config_timeout_us =
1185 *pmm_config_timeout_us =
1187 *prange_config_timeout_us =
1195 *pdss_config__target_total_rate_mcps =
1197 *pphasecal_config_timeout_us =
1199 *pmm_config_timeout_us =
1201 *prange_config_timeout_us =
1208 *pdss_config__target_total_rate_mcps =
1210 *pphasecal_config_timeout_us =
1212 *pmm_config_timeout_us =
1214 *prange_config_timeout_us =
1233 uint16_t dss_config__target_total_rate_mcps,
1234 uint32_t phasecal_config_timeout_us,
1237 uint32_t inter_measurement_period_ms)
1273 switch (device_preset_mode) {
1305 #ifndef VL53L1_NOCALIB 1421 dss_config__target_total_rate_mcps;
1423 dss_config__target_total_rate_mcps;
1436 phasecal_config_timeout_us,
1437 mm_config_timeout_us,
1438 range_config_timeout_us);
1444 inter_measurement_period_ms);
1472 if (tempu32 > 0xFFFF) {
1514 uint8_t *pcrosstalk_compensation_enable)
1533 *pcrosstalk_compensation_enable =
1729 *plite_mincountrate =
1812 (vhv_loopbound * 4);
1878 ((vhv_init_en & 0x01) << 7) +
1879 (vhv_init_value & 0x7F);
1921 uint8_t *pbuffer = &buffer[0];
1924 uint16_t i2c_buffer_offset_bytes = 0;
1925 uint16_t i2c_buffer_size_bytes = 0;
1972 if (device_config_level <
1974 device_config_level =
1995 switch (device_config_level) {
2021 i2c_buffer_size_bytes = \
2028 pbuffer = &buffer[0];
2029 for (i = 0 ; i < i2c_buffer_size_bytes ; i++) {
2038 i2c_buffer_offset_bytes = \
2039 VL53L1_STATIC_NVM_MANAGED_I2C_INDEX - i2c_index;
2045 &buffer[i2c_buffer_offset_bytes]);
2051 i2c_buffer_offset_bytes = \
2052 VL53L1_CUSTOMER_NVM_MANAGED_I2C_INDEX - i2c_index;
2058 &buffer[i2c_buffer_offset_bytes]);
2064 i2c_buffer_offset_bytes = \
2065 VL53L1_STATIC_CONFIG_I2C_INDEX - i2c_index;
2071 &buffer[i2c_buffer_offset_bytes]);
2077 i2c_buffer_offset_bytes =
2084 &buffer[i2c_buffer_offset_bytes]);
2090 i2c_buffer_offset_bytes = \
2091 VL53L1_TIMING_CONFIG_I2C_INDEX - i2c_index;
2097 &buffer[i2c_buffer_offset_bytes]);
2103 i2c_buffer_offset_bytes = \
2104 VL53L1_DYNAMIC_CONFIG_I2C_INDEX - i2c_index;
2118 &buffer[i2c_buffer_offset_bytes]);
2123 i2c_buffer_offset_bytes = \
2124 VL53L1_SYSTEM_CONTROL_I2C_INDEX - i2c_index;
2130 &buffer[i2c_buffer_offset_bytes]);
2218 uint16_t i2c_buffer_offset_bytes = 0;
2219 uint16_t i2c_buffer_size_bytes = 0;
2225 switch (device_results_level) {
2227 i2c_buffer_size_bytes =
2233 i2c_buffer_size_bytes =
2239 i2c_buffer_size_bytes =
2259 i2c_buffer_offset_bytes =
2265 &buffer[i2c_buffer_offset_bytes],
2272 i2c_buffer_offset_bytes =
2278 &buffer[i2c_buffer_offset_bytes],
2284 i2c_buffer_offset_bytes = 0;
2288 &buffer[i2c_buffer_offset_bytes],
2329 device_results_level);
2383 #ifdef VL53L1_LOG_ENABLE 2385 VL53L1_print_range_results(
2387 "get_device_results():pdev->llresults.range_results.",
2388 VL53L1_TRACE_MODULE_RANGE_RESULTS_DATA);
2450 pdata = &(presults->
data[0]);
2452 for (i = 0 ; i < 2 ; i++) {
2491 if (tmpu32 > 0xFFFF) {
2505 range_mm *= gain_factor;
2536 if (tmpu32 > 0xFFFF) {
2550 range_mm *= gain_factor;
2611 uint8_t intr_new_measure_ready,
3022 switch (tuning_parm_key) {
3025 *ptuning_parm_value =
3029 *ptuning_parm_value =
3033 *ptuning_parm_value =
3037 *ptuning_parm_value =
3041 *ptuning_parm_value =
3045 *ptuning_parm_value =
3049 *ptuning_parm_value =
3053 *ptuning_parm_value =
3057 *ptuning_parm_value =
3061 *ptuning_parm_value =
3065 *ptuning_parm_value =
3069 *ptuning_parm_value =
3073 *ptuning_parm_value =
3077 *ptuning_parm_value =
3081 *ptuning_parm_value =
3085 *ptuning_parm_value =
3089 *ptuning_parm_value =
3093 *ptuning_parm_value =
3097 *ptuning_parm_value =
3101 *ptuning_parm_value =
3105 *ptuning_parm_value =
3109 *ptuning_parm_value =
3113 *ptuning_parm_value =
3117 *ptuning_parm_value =
3121 *ptuning_parm_value =
3125 *ptuning_parm_value =
3129 *ptuning_parm_value =
3133 *ptuning_parm_value =
3137 *ptuning_parm_value =
3141 *ptuning_parm_value =
3145 *ptuning_parm_value =
3149 *ptuning_parm_value =
3153 *ptuning_parm_value =
3157 *ptuning_parm_value =
3161 *ptuning_parm_value =
3165 *ptuning_parm_value =
3169 *ptuning_parm_value =
3173 *ptuning_parm_value =
3177 *ptuning_parm_value =
3181 *ptuning_parm_value =
3185 *ptuning_parm_value =
3189 *ptuning_parm_value =
3193 *ptuning_parm_value =
3197 *ptuning_parm_value =
3201 *ptuning_parm_value =
3205 *ptuning_parm_value =
3209 *ptuning_parm_value =
3213 *ptuning_parm_value =
3217 *ptuning_parm_value =
3221 *ptuning_parm_value =
3225 *ptuning_parm_value =
3229 *ptuning_parm_value =
3233 *ptuning_parm_value =
3237 *ptuning_parm_value =
3241 *ptuning_parm_value =
3245 *ptuning_parm_value =
3249 *ptuning_parm_value =
3255 *ptuning_parm_value = 0x7FFFFFFF;
3284 switch (tuning_parm_key) {
VL53L1_Error VL53L1_set_preset_mode(VL53L1_DEV Dev, VL53L1_DevicePresetModes device_preset_mode, uint16_t dss_config__target_total_rate_mcps, uint32_t phasecal_config_timeout_us, uint32_t mm_config_timeout_us, uint32_t range_config_timeout_us, uint32_t inter_measurement_period_ms)
Initialises the configuration data structures for the selected preset mode.
uint16_t result__final_crosstalk_corrected_range_mm_sd0
uint32_t result_core__ranging_total_events_sd0
uint32_t tp_mm_timeout_timed_us
VL53L1_ll_driver_state_t ll_state
VL53L1_optical_centre_t optical_centre
#define VL53L1_TIMING_CONFIG_I2C_INDEX
#define VL53L1_DEVICESTATE_UNKNOWN
VL53L1_Error VL53L1_update_ll_driver_rd_state(VL53L1_DEV Dev)
Update LL Driver Read State.
uint16_t vl53l1_tuningparm_version
uint16_t result__osc_calibrate_val
uint16_t range_config__min_count_rate_rtn_limit_mcps
#define VL53L1_DEVICECONFIGLEVEL_FULL
uint8_t tp_timed_seed_cfg
VL53L1_user_zone_t mm_roi
uint32_t vl53l1_tuningparm_refspadchar_phasecal_timeout_us
uint16_t vl53l1_tuningparm_refspadchar_min_countrate_limit_mcps
#define VL53L1_TUNINGPARM_OFFSET_CAL_MM1_SAMPLES
#define VL53L1_TUNINGPARM_LITE_LONG_MIN_COUNT_RATE_RTN_MCPS
uint8_t vl53l1_tuningparm_vhv_loopbound
uint32_t vl53l1_tuningparm_lite_mm_config_timeout_us
VL53L1_Error VL53L1_i2c_encode_customer_nvm_managed(VL53L1_customer_nvm_managed_t *pdata, uint16_t buf_size, uint8_t *pbuffer)
Encodes data structure VL53L1_customer_nvm_managed_t into a I2C write buffer.
VL53L1_Error VL53L1_get_lite_xtalk_margin_kcps(VL53L1_DEV Dev, int16_t *pxtalk_margin)
Get function for Xtalk Margin setting Histogram Mode version.
uint8_t VL53L1_encode_GPIO_interrupt_config(VL53L1_GPIO_interrupt_config_t *pintconf)
Encodes VL53L1_GPIO_interrupt_config_t structure to FW register format.
uint16_t vl53l1_tuningparm_lite_short_min_count_rate_rtn_mcps
VL53L1 LL Driver ST private data structure .
uint16_t max_count_rate_limit_mcps
VL53L1_static_nvm_managed_t stat_nvm
#define VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_MED_RANGE
VL53L1_Error VL53L1_set_range_ignore_threshold(VL53L1_DEV Dev, uint8_t range_ignore_thresh_mult, uint16_t range_ignore_threshold_mcps)
Set the Range Ignore Threshold Rate value.
Reference SPAD Characterization (RefSpadChar) Config.
uint8_t vl53l1_tuningparm_lowpowerauto_vhv_loop_bound
uint8_t tp_lite_sigma_est_pulse_width_ns
#define VL53L1_TUNINGPARM_TIMED_MM_CONFIG_TIMEOUT_US
uint32_t inter_measurement_period_ms
VL53L1_Error VL53L1_disable_firmware(VL53L1_DEV Dev)
Disables MCU firmware.
#define VL53L1_TUNINGPARM_OFFSET_CAL_PRE_SAMPLES
#define VL53L1_TUNINGPARM_LITE_XTALK_MARGIN_KCPS
VL53L1_Error VL53L1_set_inter_measurement_period_ms(VL53L1_DEV Dev, uint32_t inter_measurement_period_ms)
Gets the tuning parm part to part data.
uint8_t mm_config__timeout_macrop_a_lo
#define VL53L1_SOFTWARE_RESET_DURATION_US
VL53L1_core_results_t core_results
int16_t algo__crosstalk_compensation_x_plane_gradient_kcps
void VL53L1_get_xtalk_compensation_enable(VL53L1_DEV Dev, uint8_t *pcrosstalk_compensation_enable)
Simple function to retrieve xtalk compensation status.
uint8_t roi_config__user_roi_centre_spad
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
#define VL53L1_OFFSETCALIBRATIONMODE__MM1_MM2__STANDARD
uint16_t result__phase_sd1
uint32_t result_core__total_periods_elapsed_sd1
#define VL53L1_DEVICEREPORTSTATUS_MM2
uint32_t total_periods_elapsed
uint32_t VL53L1_calc_timeout_us(uint32_t timeout_mclks, uint32_t macro_period_us)
Calculates the timeout in us based on the input timeout im macro periods value and the macro period i...
#define VL53L1_TUNINGPARM_TIMED_PHASECAL_CONFIG_TIMEOUT_US
VL53L1_Error VL53L1_set_user_zone(VL53L1_DEV Dev, VL53L1_user_zone_t *puser_zone)
Sets the current user Zone (ROI) configuration structure data.
#define VL53L1_TUNINGPARM_VHV_LOOPBOUND
#define VL53L1_CUSTOMER_NVM_MANAGED_I2C_INDEX
VL53L1_gain_calibration_data_t gain_cal
#define VL53L1_TUNINGPARM_TIMED_RANGE_CONFIG_TIMEOUT_US
uint16_t vl53l1_tuningparm_spadmap_rate_limit_mcps
uint8_t range_config__timeout_macrop_a_hi
#define VL53L1_TUNINGPARM_SPADMAP_RATE_LIMIT_MCPS
VL53L1_Error VL53L1_i2c_decode_core_results(uint16_t buf_size, uint8_t *pbuffer, VL53L1_core_results_t *pdata)
Encodes data structure VL53L1_core_results_t into a I2C write buffer.
#define VL53L1_STATIC_CONFIG_I2C_SIZE_BYTES
#define VL53L1_TUNINGPARM_REFSPADCHAR_MIN_COUNTRATE_LIMIT_MCPS
uint8_t tp_init_phase_ref_lite_med
uint16_t result__avg_signal_count_rate_mcps_sd0
#define VL53L1_TUNINGPARM_LITE_SEED_CONFIG
uint16_t min_count_rate_limit_mcps
Device register setting defines.
uint32_t vl53l1_tuningparm_timed_mm_config_timeout_us
uint8_t tp_lite_quantifier
Define defaults for tuning parm list.
VL53L1_Error VL53L1_set_tuning_parm(VL53L1_DEV Dev, VL53L1_TuningParms tuning_parm_key, int32_t tuning_parm_value)
Generic Tuning Parameter set function.
uint16_t result__sigma_sd0
uint32_t tp_mm_timeout_lpa_us
int16_t algo__part_to_part_range_offset_mm
#define VL53L1_TUNINGPARM_OFFSET_CAL_PHASECAL_TIMEOUT_US
uint32_t vl53l1_tuningparm_offset_cal_phasecal_timeout_us
VL53L1_Error VL53L1_set_refspadchar_config_struct(VL53L1_DEV Dev, VL53L1_refspadchar_config_t *pdata)
Extract the Ref spad char cfg struct from pdev.
VL53L1_Error VL53L1_init_refspadchar_config_struct(VL53L1_refspadchar_config_t *pdata)
Initializes Ref SPAD Char Configuration Parameters.
uint8_t tp_lite_sigma_ref_mm
#define VL53L1_TUNINGPARM_LITE_MED_SIGMA_THRESH_MM
VL53L1_Error VL53L1_preset_mode_timed_ranging_long_range(VL53L1_static_config_t *pstatic, VL53L1_general_config_t *pgeneral, VL53L1_timing_config_t *ptiming, VL53L1_dynamic_config_t *pdynamic, VL53L1_system_control_t *psystem, VL53L1_tuning_parm_storage_t *ptuning_parms)
Initializes static and dynamic configuration settings for preset mode VL53L1_DEVICEPRESETMODE_TIMED_R...
#define VL53L1_TUNINGPARM_LOWPOWERAUTO_RANGE_CONFIG_TIMEOUT_US
VL53L1_Error VL53L1_restore_xtalk_nvm_default(VL53L1_DEV Dev)
Function to restore the plane_offset, x gradient and y gradient values to original NVM values...
VL53L1_OffsetCorrectionMode offset_correction_mode
VL53L1_OffsetCalibrationMode offset_calibration_mode
#define VL53L1_CORE_RESULTS_I2C_SIZE_BYTES
VL53L1_Error VL53L1_init_xtalk_config_struct(VL53L1_customer_nvm_managed_t *pnvm, VL53L1_xtalk_config_t *pdata)
Initializes Xtalk Configuration Parameters.
#define VL53L1_TUNINGPARM_LITE_PHASECAL_CONFIG_TIMEOUT_US
#define VL53L1_OFFSETCORRECTIONMODE__MM1_MM2_OFFSETS
uint8_t VL53L1_DeviceConfigLevel
VL53L1_Error VL53L1_set_lite_sigma_threshold(VL53L1_DEV Dev, uint16_t lite_sigma)
Set function for Lite Mode Max Sigma Threshold parameter, used to filter and validate ranges based on...
uint32_t tp_range_timeout_lpa_us
void VL53L1_copy_rtn_good_spads_to_buffer(VL53L1_nvm_copy_data_t *pdata, uint8_t *pbuffer)
Convenience function to copy return SPAD enables to buffer.
uint8_t phasecal_config__timeout_macrop
#define VL53L1_DEVICEERROR_VCSELWATCHDOGTESTFAILURE
int16_t mm_config__outer_offset_mm
#define VL53L1_SYSTEM_RESULTS_I2C_SIZE_BYTES
VL53L1_Error VL53L1_i2c_encode_timing_config(VL53L1_timing_config_t *pdata, uint16_t buf_size, uint8_t *pbuffer)
Gets general_config register group.
uint8_t tp_init_phase_ref_lite_long
VL53L1_additional_offset_cal_data_t add_off_cal_data
uint16_t result__sigma_sd1
VL53L1_Error VL53L1_set_vhv_config(VL53L1_DEV Dev, uint8_t vhv_init_en, uint8_t vhv_init_value)
Set function for VHV Config values sets two parms into individual internal byte.
#define VL53L1_TUNINGPARM_REFSPADCHAR_VCSEL_PERIOD
uint8_t vl53l1_tuningparm_offset_cal_mm2_samples
#define VL53L1_TUNINGPARM_LITE_DSS_CONFIG_TARGET_TOTAL_RATE_MCPS
VL53L1_Error VL53L1_preset_mode_standard_ranging(VL53L1_static_config_t *pstatic, VL53L1_general_config_t *pgeneral, VL53L1_timing_config_t *ptiming, VL53L1_dynamic_config_t *pdynamic, VL53L1_system_control_t *psystem, VL53L1_tuning_parm_storage_t *ptuning_parms)
Initializes static and dynamic configuration settings for preset mode VL53L1_DEVICEPRESETMODE_STANDAR...
uint16_t vl53l1_tuningparm_refspadchar_max_countrate_limit_mcps
uint16_t ambient_count_rate_mcps
#define VL53L1_TUNINGPARM_LITE_SIGMA_EST_PULSE_WIDTH
uint16_t dss_config__target_total_rate_mcps
VL53L1_refspadchar_config_t refspadchar
uint32_t nvm_default__crosstalk_compensation_plane_offset_kcps
#define VL53L1_TUNINGPARM_OFFSET_CAL_DSS_RATE_MCPS
#define VL53L1_SYSTEM_RESULTS_I2C_INDEX
VL53L1_Error VL53L1_get_range_ignore_threshold(VL53L1_DEV Dev, uint8_t *prange_ignore_thresh_mult, uint16_t *prange_ignore_threshold_mcps_internal, uint16_t *prange_ignore_threshold_mcps_current)
Get the Range Ignore Threshold Rate value.
VL53L1_Error VL53L1_clear_interrupt_and_enable_next_range(VL53L1_DEV Dev, uint8_t measurement_mode)
Sends the ranging handshake to clear the interrupt allow the device to move onto the next range...
int16_t lite_mode_crosstalk_margin_kcps
VL53L1_timing_config_t tim_cfg
VL53L1_GPIO_interrupt_config_t VL53L1_decode_GPIO_interrupt_config(uint8_t system__interrupt_config)
Decodes FW register to VL53L1_GPIO_interrupt_config_t structure.
short int16_t
Typedef defining 16 bit short type. The developer should modify this to suit the platform being deplo...
VL53L1_Error VL53L1_preset_mode_standard_ranging_short_range(VL53L1_static_config_t *pstatic, VL53L1_general_config_t *pgeneral, VL53L1_timing_config_t *ptiming, VL53L1_dynamic_config_t *pdynamic, VL53L1_system_control_t *psystem, VL53L1_tuning_parm_storage_t *ptuning_parms)
Initializes static and dynamic configuration settings for preset mode VL53L1_DEVICEPRESETMODE_STANDAR...
uint8_t tp_init_phase_rtn_lite_med
VL53L1_Error VL53L1_init_tuning_parm_storage_struct(VL53L1_tuning_parm_storage_t *pdata)
Initializes Tuning Parameter Storage Values.
uint32_t mm_config_timeout_us
#define VL53L1_RANGE_STATUS__RANGE_STATUS_MASK
uint16_t algo__crosstalk_compensation_plane_offset_kcps
uint8_t system__grouped_parameter_hold_0
uint8_t roi_config__user_roi_requested_global_xy_size
uint16_t tp_tuning_parm_key_table_version
uint16_t tp_lite_med_sigma_thresh_mm
#define VL53L1_TUNINGPARM_LITE_RANGING_GAIN_FACTOR
#define VL53L1_DEVICEERROR_RANGECOMPLETE
#define VL53L1_DYNAMIC_CONFIG_I2C_SIZE_BYTES
uint32_t ambient_window_events
void VL53L1_copy_sys_and_core_results_to_range_results(int32_t gain_factor, VL53L1_system_results_t *psys, VL53L1_core_results_t *pcore, VL53L1_range_results_t *presults)
Copies system and core results to range results data structure.
#define VL53L1_TUNINGPARM_VHV_LOOPBOUND_DEFAULT
void VL53L1_encode_row_col(uint8_t row, uint8_t col, uint8_t *pspad_number)
Encodes a (col,row) coord value into ByteIndex.BitIndex format.
uint16_t result__final_crosstalk_corrected_range_mm_sd1
uint8_t vl53l1_tuningparm_timed_seed_config
VL53L1_additional_offset_cal_data_t add_off_cal_data
#define VL53L1_TUNINGPARM_SPADMAP_VCSEL_START
uint16_t vl53l1_tuningparm_lite_short_sigma_thresh_mm
void VL53L1_init_version(VL53L1_DEV Dev)
Initialise version info in pdev.
Defines User Zone(ROI) parameters.
#define VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_MEDIUM_RANGE
#define VL53L1_DYNAMIC_CONFIG_I2C_INDEX
#define VL53L1_SEQUENCE_MM1_EN
uint32_t result_core__ambient_window_events_sd1
VL53L1_Error VL53L1_get_timeouts_us(VL53L1_DEV Dev, uint32_t *pphasecal_config_timeout_us, uint32_t *pmm_config_timeout_us, uint32_t *prange_config_timeout_us)
Gets the phasecal, mode mitigation and ranging timeouts for the VL53L1_timing_config_t structure...
uint8_t vl53l1_tuningparm_spadmap_vcsel_period
#define VL53L1_TUNINGPARM_KEY_TABLE_VERSION_DEFAULT
VL53L1_Error VL53L1_low_power_auto_setup_manual_calibration(VL53L1_DEV Dev)
Setup ranges after the first one in low power auto mode by turning off FW calibration steps and progr...
uint16_t tp_dss_target_timed_mcps
#define VL53L1_DEVICEERROR_USERROICLIP
VL53L1_Error VL53L1_enable_firmware(VL53L1_DEV Dev)
Enables MCU firmware.
uint8_t range_config__vcsel_period_a
uint8_t tp_lite_sigma_est_amb_width_ns
uint8_t low_power_auto_range_count
VL53L1_general_config_t gen_cfg
#define VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_SHORT_RANGE
VL53L1_DeviceState rd_device_state
VL53L1_DeviceState rd_device_state
#define VL53L1_DEVICECONFIGLEVEL_GENERAL_ONWARDS
uint16_t tp_cal_repeat_rate
uint16_t result__ambient_count_rate_mcps_sd0
uint16_t dss_config__target_total_rate_mcps
VL53L1_Error VL53L1_set_sequence_config_bit(VL53L1_DEV Dev, VL53L1_DeviceSequenceConfig bit_id, uint8_t value)
Set system sequence config bit value.
uint16_t threshold_distance_high
uint16_t result__mm_inner_actual_effective_spads_sd0
#define VL53L1_TUNINGPARM_LOWPOWERAUTO_MM_CONFIG_TIMEOUT_US
VL53L1_GPIO_interrupt_config_t gpio_interrupt_config
uint8_t tp_consistency_lite_phase_tolerance
VL53L1_Error VL53L1_low_power_auto_data_init(VL53L1_DEV Dev)
Initialize the Low Power Auto data structure.
uint32_t vl53l1_tuningparm_offset_cal_mm_timeout_us
VL53L1_Error VL53L1_get_measurement_results(VL53L1_DEV Dev, VL53L1_DeviceResultsLevel device_results_level)
Get range measurement result data.
#define VL53L1_SEQUENCE_MM2_EN
VL53L1_Error VL53L1_read_p2p_data(VL53L1_DEV Dev)
For C-API one time initialization only reads device G02 registers containing data copied from NVM...
VL53L1_GPIO_Interrupt_Mode intr_mode_rate
#define VL53L1_TUNINGPARM_LITE_MIN_CLIP_MM
uint32_t ranging_total_events
VL53L1_range_data_t data[2]
#define VL53L1_TUNINGPARM_PHASECAL_TARGET
uint8_t vl53l1_tuningparm_lite_quantifier
VL53L1_gain_calibration_data_t gain_cal
uint32_t system__intermeasurement_period
VL53L1_Error VL53L1_preset_mode_standard_ranging_mm2_cal(VL53L1_static_config_t *pstatic, VL53L1_general_config_t *pgeneral, VL53L1_timing_config_t *ptiming, VL53L1_dynamic_config_t *pdynamic, VL53L1_system_control_t *psystem, VL53L1_tuning_parm_storage_t *ptuning_parms)
Initializes static and dynamic configuration settings for preset mode VL53L1_DEVICEPRESETMODE_STANDAR...
#define VL53L1_TUNINGPARM_REFSPADCHAR_DEVICE_TEST_MODE
#define VL53L1_TUNINGPARM_KEY_TABLE_VERSION
#define VL53L1_GENERAL_CONFIG_I2C_INDEX
uint16_t vl53l1_tuningparm_lite_med_sigma_thresh_mm
int32_t signal_total_events
VL53L1_Error VL53L1_i2c_encode_dynamic_config(VL53L1_dynamic_config_t *pdata, uint16_t buf_size, uint8_t *pbuffer)
Decodes data structure VL53L1_timing_config_t from the input I2C read buffer.
uint16_t result__mm_outer_actual_effective_spads_sd0
NVM Map definitions for EwokPlus25 NVM Interface Functions.
#define VL53L1_SOFT_RESET
uint32_t tp_phasecal_timeout_timed_us
uint8_t result__range_status
uint8_t vhv_config__timeout_macrop_loop_bound
#define VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM1_CAL
VL53L1_Error VL53L1_preset_mode_olt(VL53L1_static_config_t *pstatic, VL53L1_general_config_t *pgeneral, VL53L1_timing_config_t *ptiming, VL53L1_dynamic_config_t *pdynamic, VL53L1_system_control_t *psystem, VL53L1_tuning_parm_storage_t *ptuning_parms)
Initializes static and dynamic configuration settings for preset mode VL53L1_DEVICEPRESETMODE_OLT.
#define VL53L1_LL_CALIBRATION_DATA_STRUCT_VERSION
#define VL53L1_SYSTEM_CONTROL_I2C_SIZE_BYTES
VL53L1_system_results_t sys_results
#define VL53L1_DEVICESTATE_SW_STANDBY
uint8_t range_config__timeout_macrop_a_lo
VL53L1_Error VL53L1_low_power_auto_data_stop_range(VL53L1_DEV Dev)
Reset internal state but leave low_power_auto mode intact.
#define VL53L1_STATIC_NVM_MANAGED_I2C_SIZE_BYTES
uint16_t algo__range_ignore_threshold_mcps
uint16_t peak_signal_count_rate_mcps
uint32_t vl53l1_tuningparm_timed_range_config_timeout_us
VL53L1_Error VL53L1_get_tuning_parm(VL53L1_DEV Dev, VL53L1_TuningParms tuning_parm_key, int32_t *ptuning_parm_value)
Generic Tuning Parameter extraction function.
void VL53L1_decode_zone_size(uint8_t encoded_xy_size, uint8_t *pwidth, uint8_t *pheight)
Decodes encoded zone size format into width and height values.
VL53L1_Error VL53L1_stop_range(VL53L1_DEV Dev)
Sends an abort command to stop the in progress range. Also clears all of the measurement mode bits...
VL53L1_Error VL53L1_set_GPIO_interrupt_config(VL53L1_DEV Dev, VL53L1_GPIO_Interrupt_Mode intr_mode_distance, VL53L1_GPIO_Interrupt_Mode intr_mode_rate, uint8_t intr_new_measure_ready, uint8_t intr_no_target, uint8_t intr_combined_mode, uint16_t thresh_distance_high, uint16_t thresh_distance_low, uint16_t thresh_rate_high, uint16_t thresh_rate_low)
Configure the GPIO interrupt config, from the given input.
VL53L1_Error VL53L1_preset_mode_low_power_auto_long_ranging(VL53L1_static_config_t *pstatic, VL53L1_general_config_t *pgeneral, VL53L1_timing_config_t *ptiming, VL53L1_dynamic_config_t *pdynamic, VL53L1_system_control_t *psystem, VL53L1_tuning_parm_storage_t *ptuning_parms, VL53L1_low_power_auto_data_t *plpadata)
Initializes static and dynamic configuration settings for preset mode VL53L1_DEVICEPRESETMODE_LOWPOWE...
void VL53L1_encode_zone_size(uint8_t width, uint8_t height, uint8_t *pencoded_xy_size)
Encodes a zone width & height into encoded size format.
uint16_t system__thresh_high
VL53L1_Error VL53L1_wait_for_boot_completion(VL53L1_DEV Dev)
Wait for initial firmware boot to finish.
VL53L1_xtalk_config_t xtalk_cfg
uint8_t system__grouped_parameter_hold_1
VL53L1_Error VL53L1_get_interrupt_polarity(VL53L1_DEV Dev, VL53L1_DeviceInterruptPolarity *pinterrupt_polarity)
Get the interrupt polarity bit state.
uint16_t threshold_distance_low
uint8_t vl53l1_tuningparm_lite_min_clip_mm
VL53L1 Register Map definitions.
int16_t algo__crosstalk_compensation_x_plane_gradient_kcps
uint16_t vl53l1_tuningparm_lite_dss_config_target_total_rate_mcps
#define VL53L1_STATIC_CONFIG_I2C_INDEX
#define VL53L1_ERROR_TUNING_PARM_KEY_MISMATCH
LL Driver Device specific defines. To be adapted by implementer for the targeted device.
uint16_t tp_lite_short_sigma_thresh_mm
#define VL53L1_ERROR_NONE
#define VL53L1_TUNINGPARM_LITE_LONG_SIGMA_THRESH_MM
int16_t algo__crosstalk_compensation_y_plane_gradient_kcps
uint8_t tp_phasecal_target
uint32_t tp_range_timeout_lite_us
uint8_t vl53l1_tuningparm_offset_cal_pre_samples
VL53L1_Error VL53L1_preset_mode_low_power_auto_short_ranging(VL53L1_static_config_t *pstatic, VL53L1_general_config_t *pgeneral, VL53L1_timing_config_t *ptiming, VL53L1_dynamic_config_t *pdynamic, VL53L1_system_control_t *psystem, VL53L1_tuning_parm_storage_t *ptuning_parms, VL53L1_low_power_auto_data_t *plpadata)
Initializes static and dynamic configuration settings for preset mode VL53L1_DEVICEPRESETMODE_LOWPOWE...
uint16_t system__thresh_rate_high
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
uint8_t vl53l1_tuningparm_lite_rit_mult
uint32_t algo__crosstalk_compensation_plane_offset_kcps
EwokPlus25 low level API function definitions.
VL53L1_Error VL53L1_i2c_encode_general_config(VL53L1_general_config_t *pdata, uint16_t buf_size, uint8_t *pbuffer)
Gets static_config register group.
uint8_t VL53L1_OffsetCorrectionMode
#define VL53L1_DEVICEPRESETMODE_TIMED_RANGING_LONG_RANGE
#define VL53L1_WAIT_METHOD_BLOCKING
EwokPlus25 API core function definition.
uint8_t intr_new_measure_ready
#define VL53L1_TUNINGPARM_LITE_QUANTIFIER
Type definitions for VL53L1 LL Driver.
int16_t nvm_default__crosstalk_compensation_y_plane_gradient_kcps
uint32_t result_core__total_periods_elapsed_sd0
#define VL53L1_MCU_GENERAL_PURPOSE__GP_0
uint16_t result__dss_actual_effective_spads_sd1
#define LOG_FUNCTION_END(status,...)
VL53L1_Error VL53L1_update_ll_driver_cfg_state(VL53L1_DEV Dev)
Update LL Driver Configuration State.
uint8_t vl53l1_tuningparm_initial_phase_rtn_lite_med_range
#define VL53L1_DEBUG_RESULTS_I2C_SIZE_BYTES
VL53L1_system_control_t sys_ctrl
#define VL53L1_STATIC_NVM_MANAGED_I2C_INDEX
uint8_t mm1_num_of_samples
uint8_t system__sequence_config
#define VL53L1_TUNINGPARM_TIMED_SEED_CONFIG
VL53L1_Error VL53L1_get_part_to_part_data(VL53L1_DEV Dev, VL53L1_calibration_data_t *pcal_data)
Gets the customer part to part data.
#define VL53L1_DEBUG_RESULTS_I2C_INDEX
uint16_t crosstalk_range_ignore_threshold_rate_mcps
VL53L1_Error VL53L1_enable_xtalk_compensation(VL53L1_DEV Dev)
Simple function to enable xtalk compensation.
VL53L1_Error VL53L1_set_timeouts_us(VL53L1_DEV Dev, uint32_t phasecal_config_timeout_us, uint32_t mm_config_timeout_us, uint32_t range_config_timeout_us)
Sets the phasecal, mode mitigation and ranging timeouts in the VL53L1_timing_config_t structure...
#define VL53L1_TUNINGPARM_CONSISTENCY_LITE_PHASE_TOLERANCE
#define VL53L1_DEVICEPRESETMODE_TIMED_RANGING_SHORT_RANGE
#define VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK
#define VL53L1_DEVICEERROR_NOVHVVALUEFOUND
VL53L1_Error VL53L1_set_lite_xtalk_margin_kcps(VL53L1_DEV Dev, int16_t xtalk_margin)
Set function for Xtalk Margin setting Histogram Mode version.
uint16_t result__dss_actual_effective_spads_sd0
VL53L1_Error VL53L1_get_lite_sigma_threshold(VL53L1_DEV Dev, uint16_t *plite_sigma)
Get function for Lite Mode Max Sigma Threshold parameter, used to filter and validate ranges based on...
Contains the driver state information.
#define VL53L1_TUNINGPARM_LITE_RANGING_GAIN_FACTOR_DEFAULT
#define VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_LONG_RANGE
Defines the parameters of the LL driver Get Version Functions.
VL53L1_Error VL53L1_get_GPIO_interrupt_config(VL53L1_DEV Dev, VL53L1_GPIO_interrupt_config_t *pintconf)
Retrieves the GPIO interrupt config structure currently programmed into the API.
uint32_t vl53l1_tuningparm_timed_phasecal_config_timeout_us
uint8_t vl53l1_tuningparm_lite_sigma_ref_mm
VL53L1_Error VL53L1_get_inter_measurement_period_ms(VL53L1_DEV Dev, uint32_t *pinter_measurement_period_ms)
Gets inter measurement period from the VL53L1_timing_config_t structure.
int int32_t
Typedef defining 32 bit int type. The developer should modify this to suit the platform being deploye...
uint16_t tp_dss_target_lite_mcps
uint8_t crosstalk_range_ignore_threshold_mult
#define LOG_FUNCTION_START(fmt,...)
#define VL53L1_DEVICERESULTSLEVEL_UPTO_CORE
VL53L1_Error VL53L1_preset_mode_standard_ranging_long_range(VL53L1_static_config_t *pstatic, VL53L1_general_config_t *pgeneral, VL53L1_timing_config_t *ptiming, VL53L1_dynamic_config_t *pdynamic, VL53L1_system_control_t *psystem, VL53L1_tuning_parm_storage_t *ptuning_parms)
Initializes static and dynamic configuration settings for preset mode VL53L1_DEVICEPRESETMODE_STANDAR...
VL53L1_Error VL53L1_disable_xtalk_compensation(VL53L1_DEV Dev)
Simple function to disable xtalk compensation.
uint16_t dss_config__target_total_rate_mcps
uint8_t gpio_hv_mux__ctrl
uint8_t result__report_status
VL53L1_ssc_config_t ssc_cfg
VL53L1_Error VL53L1_set_customer_nvm_managed(VL53L1_DEV Dev, VL53L1_customer_nvm_managed_t *pdata)
Sets customer_nvm_managed register group.
#define VL53L1_MAX_I2C_XFER_SIZE
uint8_t vl53l1_tuningparm_lite_sigma_est_pulse_width
VL53L1_Error VL53L1_get_nvm_copy_data(VL53L1_DEV Dev, VL53L1_nvm_copy_data_t *pdata)
Sets nvm_copy_data register group.
EwokPlus25 low level silicon specific API function definitions.
uint32_t tp_phasecal_timeout_lite_us
uint8_t vl53l1_tuningparm_offset_cal_mm1_samples
uint8_t vl53l1_tuningparm_lite_seed_config
EwokPlus25 low level Driver wait function definitions.
uint16_t avg_signal_count_rate_mcps
uint8_t vl53l1_tuningparm_initial_phase_ref_lite_long_range
#define VL53L1_TUNINGPARM_LLD_VERSION
VL53L1_optical_centre_t optical_centre
VL53L1_Error VL53L1_low_power_auto_update_DSS(VL53L1_DEV Dev)
Do a DSS calculation and update manual config.
#define VL53L1_DEVICESEQUENCECONFIG_RANGE
VL53L1_static_config_t stat_cfg
#define VL53L1_ERROR_INVALID_PARAMS
#define VL53L1_DEVICEMEASUREMENTMODE_ABORT
#define VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_LONG_RANGE
#define VL53L1_TIMING_CONFIG_I2C_SIZE_BYTES
uint16_t VL53L1_TuningParms
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_Error VL53L1_get_vhv_config(VL53L1_DEV Dev, uint8_t *pvhv_init_en, uint8_t *pvhv_init_value)
Get function for VHV Config values extracts two parms from individual internal byte.
uint16_t tp_lite_long_sigma_thresh_mm
VL53L1 Register Function declarations.
uint32_t range_config_timeout_us
uint8_t roi_config__mode_roi_centre_spad
VL53L1_DeviceState cfg_device_state
#define VL53L1_DEVICECONFIGLEVEL_DYNAMIC_ONWARDS
uint8_t intr_combined_mode
VL53L1_Error VL53L1_preset_mode_timed_ranging(VL53L1_static_config_t *pstatic, VL53L1_general_config_t *pgeneral, VL53L1_timing_config_t *ptiming, VL53L1_dynamic_config_t *pdynamic, VL53L1_system_control_t *psystem, VL53L1_tuning_parm_storage_t *ptuning_parms)
Initializes static and dynamic configuration settings for preset mode VL53L1_DEVICEPRESETMODE_TIMED_R...
VL53L1_debug_results_t dbg_results
EwokPlus25 core function definitions.
uint8_t VL53L1_DeviceInterruptPolarity
VL53L1_Error VL53L1_i2c_encode_static_config(VL53L1_static_config_t *pdata, uint16_t buf_size, uint8_t *pbuffer)
Encodes data structure VL53L1_static_config_t into a I2C write buffer.
#define VL53L1_DEVICEINTERRUPTPOLARITY_BIT_MASK
uint8_t saved_interrupt_config
uint32_t vl53l1_tuningparm_lowpowerauto_mm_config_timeout_us
#define VL53L1_SYSTEM_CONTROL_I2C_INDEX
VL53L1_Error VL53L1_init_ssc_config_struct(VL53L1_ssc_config_t *pdata)
Initializes SPAD Self Check (SSC) Configuration Parameters.
uint8_t vl53l1_tuningparm_lite_first_order_select
VL53L1_DeviceMeasurementModes measurement_mode
VL53L1_Error VL53L1_preset_mode_singleshot_ranging(VL53L1_static_config_t *pstatic, VL53L1_general_config_t *pgeneral, VL53L1_timing_config_t *ptiming, VL53L1_dynamic_config_t *pdynamic, VL53L1_system_control_t *psystem, VL53L1_tuning_parm_storage_t *ptuning_parms)
Initializes static and dynamic configuration settings for preset mode VL53L1_DEVICEPRESETMODE_SINGLES...
uint16_t VL53L1_calc_range_ignore_threshold(uint32_t central_rate, int16_t x_gradient, int16_t y_gradient, uint8_t rate_mult)
Calculates the Xtalk Range Ignore Threshold rate per spad in 3.13Mcps.
VL53L1_Error VL53L1_get_refspadchar_config_struct(VL53L1_DEV Dev, VL53L1_refspadchar_config_t *pdata)
Set the Ref spad char cfg struct internal to pdev.
#define VL53L1_TUNINGPARM_REFSPADCHAR_TARGET_COUNT_RATE_MCPS
int16_t vl53l1_tuningparm_lite_xtalk_margin_kcps
Structure to configure conditions when GPIO interrupt is trigerred.
VL53L1_Error VL53L1_i2c_encode_system_control(VL53L1_system_control_t *pdata, uint16_t buf_size, uint8_t *pbuffer)
Gets dynamic_config register group.
int32_t result_core__signal_total_events_sd1
#define VL53L1_TUNINGPARM_LOWPOWERAUTO_VHV_LOOP_BOUND
#define VL53L1_TUNINGPARM_OFFSET_CAL_MM2_SAMPLES
uint32_t tp_mm_timeout_lite_us
uint8_t rtn_good_spads[VL53L1_RTN_SPAD_BUFFER_SIZE]
VL53L1_Error VL53L1_get_static_nvm_managed(VL53L1_DEV Dev, VL53L1_static_nvm_managed_t *pdata)
Gets static_nvm_managed register group.
#define VL53L1_DEVICEMEASUREMENTMODE_STOP
uint16_t vl53l1_tuningparm_timed_dss_config_target_total_rate_mcps
uint32_t VL53L1_calc_decoded_timeout_us(uint16_t timeout_encoded, uint32_t macro_period_us)
Calculates the decoded timeout in us based on the input encoded timeout register value and the macro ...
VL53L1_Error VL53L1_get_device_results(VL53L1_DEV Dev, VL53L1_DeviceResultsLevel device_results_level, VL53L1_range_results_t *prange_results)
Get device system results, updates GPH registers and clears interrupt and configures SYSTEM__MODE_STA...
#define VL53L1_TUNINGPARM_LITE_RIT_MULT
#define VL53L1_TUNINGPARM_LITE_FIRST_ORDER_SELECT
VL53L1_low_power_auto_data_t low_power_auto_data
uint16_t vl53l1_tuningparm_lite_long_sigma_thresh_mm
uint16_t result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0
uint16_t tp_tuning_parm_version
uint16_t vl53l1_tuningparm_key_table_version
VL53L1_range_results_t range_results
VL53L1_Error VL53L1_software_reset(VL53L1_DEV Dev)
Performs device software reset and then waits for the firmware to finish booting. ...
uint16_t threshold_rate_high
VL53L1_nvm_copy_data_t nvm_copy_data
uint8_t VL53L1_GPIO_Interrupt_Mode
#define VL53L1_DEVICEMEASUREMENTMODE_STOP_MASK
#define VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM2_CAL
uint8_t VL53L1_DeviceResultsLevel
VL53L1_Error VL53L1_init_offset_cal_config_struct(VL53L1_offsetcal_config_t *pdata)
Initializes Offset Calibration Configuration Parameters.
#define VL53L1_TUNINGPARM_OFFSET_CAL_MM_TIMEOUT_US
#define VL53L1_DEVICEREPORTSTATUS_MM1
#define VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_SHORT_RANGE
uint8_t roi_config__mode_roi_xy_size
uint16_t tp_lite_long_min_count_rate_rtn_mcps
VL53L1_Error VL53L1_set_offset_correction_mode(VL53L1_DEV Dev, VL53L1_OffsetCorrectionMode offset_cor_mode)
Set function for offset correction mode.
#define VL53L1_DEVICEPRESETMODE_OLT
VL53L1_Error VL53L1_set_GPIO_thresholds_from_struct(VL53L1_DEV Dev, VL53L1_GPIO_interrupt_config_t *pintconf)
SET GPIO thresholds from structure. Sets both rate and distance thresholds.
uint8_t global_crosstalk_compensation_enable
uint16_t threshold_rate_low
uint16_t result__peak_signal_count_rate_mcps_sd1
VL53L1_Error VL53L1_check_ll_driver_rd_state(VL53L1_DEV Dev)
Checks if the LL Driver Read state and expected stream count matches the state and stream count recei...
uint8_t is_low_power_auto_mode
uint8_t system__interrupt_config_gpio
#define VL53L1_DEVICEERROR_VCSELCONTINUITYTESTFAILURE
uint16_t standard_ranging_gain_factor
VL53L1_DeviceState cfg_device_state
#define VL53L1_TUNINGPARM_LITE_SIGMA_REF_MM
uint16_t tp_lite_med_min_count_rate_rtn_mcps
uint32_t result_core__ranging_total_events_sd1
VL53L1_Error VL53L1_get_sequence_config_bit(VL53L1_DEV Dev, VL53L1_DeviceSequenceConfig bit_id, uint8_t *pvalue)
Get system sequence config bit value.
#define VL53L1_TUNINGPARM_LITE_MED_MIN_COUNT_RATE_RTN_MCPS
#define VL53L1_TUNINGPARM_LITE_SHORT_SIGMA_THRESH_MM
#define VL53L1_DEVICECONFIGLEVEL_STATIC_ONWARDS
uint8_t tp_init_phase_rtn_lite_short
#define VL53L1_DEVICECONFIGLEVEL_TIMING_ONWARDS
VL53L1_Error VL53L1_set_lite_min_count_rate(VL53L1_DEV Dev, uint16_t lite_mincountrate)
Set function for Lite Mode Minimum Count Rate parameter, used to filter and validate ranges based on ...
uint16_t result__phase_sd0
VL53L1_offsetcal_config_t offsetcal_cfg
#define VL53L1_DEVICECONFIGLEVEL_CUSTOMER_ONWARDS
#define VL53L1_TUNINGPARM_LITE_CAL_REPEAT_RATE
VL53L1_customer_nvm_managed_t customer
#define VL53L1_CORE_RESULTS_I2C_INDEX
VL53L1_Error VL53L1_get_customer_nvm_managed(VL53L1_DEV Dev, VL53L1_customer_nvm_managed_t *pdata)
Gets customer_nvm_managed register group.
uint32_t phasecal_config_timeout_us
#define VL53L1_TUNINGPARM_REFSPADCHAR_PHASECAL_TIMEOUT_US
#define VL53L1_DEVICEERROR_NOUPDATE
VL53L1_Error VL53L1_i2c_decode_debug_results(uint16_t buf_size, uint8_t *pbuffer, VL53L1_debug_results_t *pdata)
Sets core_results register group.
#define VL53L1_TUNINGPARM_OFFSET_CAL_RANGE_TIMEOUT_US
#define VL53L1_DEVICEERROR_MULTCLIPFAIL
uint8_t vl53l1_tuningparm_lite_sigma_est_amb_width_ns
VL53L1_Error VL53L1_preset_mode_standard_ranging_mm1_cal(VL53L1_static_config_t *pstatic, VL53L1_general_config_t *pgeneral, VL53L1_timing_config_t *ptiming, VL53L1_dynamic_config_t *pdynamic, VL53L1_system_control_t *psystem, VL53L1_tuning_parm_storage_t *ptuning_parms)
Initializes static and dynamic configuration settings for preset mode VL53L1_DEVICEPRESETMODE_STANDAR...
VL53L1_Error VL53L1_set_calibration_repeat_period(VL53L1_DEV Dev, uint16_t cal_config__repeat_period)
Sets the 12-bit calibration repeat period value.
VL53L1_Error VL53L1_set_interrupt_polarity(VL53L1_DEV Dev, VL53L1_DeviceInterruptPolarity interrupt_polarity)
Set the interrupt polarity bit in.
VL53L1_Error VL53L1_get_preset_mode_timing_cfg(VL53L1_DEV Dev, VL53L1_DevicePresetModes device_preset_mode, uint16_t *pdss_config__target_total_rate_mcps, uint32_t *pphasecal_config_timeout_us, uint32_t *pmm_config_timeout_us, uint32_t *prange_config_timeout_us)
Gets the requested preset mode configuration tuning parameters.
Tuning Parameters Debug data.
#define VL53L1_DEVICEPRESETMODE_TIMED_RANGING
VL53L1_Error VL53L1_set_system_control(VL53L1_DEV Dev, VL53L1_system_control_t *pdata)
Decodes data structure VL53L1_system_control_t from the input I2C read buffer.
#define VL53L1_TUNINGPARM_LITE_MM_CONFIG_TIMEOUT_US
VL53L1_Error VL53L1_get_lite_min_count_rate(VL53L1_DEV Dev, uint16_t *plite_mincountrate)
Get function for Lite Mode Minimum Count Rate parameter, used to filter and validate ranges based on ...
uint32_t mm_config_timeout_us
VL53L1_Error VL53L1_set_vhv_loopbound(VL53L1_DEV Dev, uint8_t vhv_loopbound)
Set function for VHV loopbound config.
uint32_t vl53l1_tuningparm_offset_cal_range_timeout_us
VL53L1_Error VL53L1_init_and_start_range(VL53L1_DEV Dev, uint8_t measurement_mode, VL53L1_DeviceConfigLevel device_config_level)
Builds and sends the I2C buffer to initialize the device and start a range measurement.
VL53L1_Error VL53L1_get_vhv_loopbound(VL53L1_DEV Dev, uint8_t *pvhv_loopbound)
Get function for VHV loopbound config.
uint32_t result_core__ambient_window_events_sd0
VL53L1_cal_peak_rate_map_t cal_peak_rate_map
uint8_t VL53L1_DeviceSequenceConfig
uint16_t cal_config__repeat_rate
uint8_t system__mode_start
uint16_t actual_effective_spads
VL53L1_tuning_parm_storage_t tuning_parms
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
VL53L1_Error VL53L1_set_GPIO_interrupt_config_struct(VL53L1_DEV Dev, VL53L1_GPIO_interrupt_config_t intconf)
Configure the GPIO interrupt config, from the given structure.
VL53L1_Error VL53L1_get_offset_correction_mode(VL53L1_DEV Dev, VL53L1_OffsetCorrectionMode *poffset_cor_mode)
Get function for offset correction mode.
uint16_t range_config__sigma_thresh
uint8_t vl53l1_tuningparm_initial_phase_ref_lite_short_range
VL53L1 LL Driver ST private results structure.
VL53L1_Error VL53L1_get_offset_calibration_mode(VL53L1_DEV Dev, VL53L1_OffsetCalibrationMode *poffset_cal_mode)
Get function for offset calibration mode.
uint8_t VL53L1_DevicePresetModes
uint16_t result__ambient_count_rate_mcps_sd1
uint32_t vl53l1_tuningparm_lowpowerauto_range_config_timeout_us
int16_t algo__crosstalk_compensation_y_plane_gradient_kcps
uint8_t tp_lite_first_order_select
VL53L1_Error VL53L1_i2c_decode_system_results(uint16_t buf_size, uint8_t *pbuffer, VL53L1_system_results_t *pdata)
Gets system_control register group.
VL53L1_GPIO_Interrupt_Mode intr_mode_distance
#define VL53L1_TUNINGPARM_VERSION
VL53L1_customer_nvm_managed_t customer
#define VL53L1_RESULT__OSC_CALIBRATE_VAL
uint16_t tp_tuning_parm_lld_version
uint16_t osc_measured__fast_osc__frequency
#define VL53L1_TUNINGPARM_LITE_SHORT_MIN_COUNT_RATE_RTN_MCPS
#define VL53L1_TUNINGPARM_INITIAL_PHASE_RTN_LITE_MED_RANGE
Additional Offset Calibration Data.
uint16_t system__thresh_rate_low
VL53L1_Error VL53L1_i2c_encode_static_nvm_managed(VL53L1_static_nvm_managed_t *pdata, uint16_t buf_size, uint8_t *pbuffer)
Encodes data structure VL53L1_static_nvm_managed_t into a I2C write buffer.
uint8_t result__stream_count
VL53L1_Error VL53L1_set_part_to_part_data(VL53L1_DEV Dev, VL53L1_calibration_data_t *pcal_data)
Sets the customer part to part data.
uint16_t vl53l1_tuningparm_lld_version
#define VL53L1_TUNINGPARM_REFSPADCHAR_MAX_COUNTRATE_LIMIT_MCPS
uint8_t vl53l1_tuningparm_initial_phase_rtn_lite_long_range
uint8_t system__grouped_parameter_hold
#define trace_print(level,...)
Structure for storing the set of range results.
VL53L1_Error VL53L1_preset_mode_low_power_auto_ranging(VL53L1_static_config_t *pstatic, VL53L1_general_config_t *pgeneral, VL53L1_timing_config_t *ptiming, VL53L1_dynamic_config_t *pdynamic, VL53L1_system_control_t *psystem, VL53L1_tuning_parm_storage_t *ptuning_parms, VL53L1_low_power_auto_data_t *plpadata)
Initializes static and dynamic configuration settings for preset mode VL53L1_DEVICEPRESETMODE_LOWPOWE...
Per Part calibration data.
uint16_t vl53l1_tuningparm_offset_cal_dss_rate_mcps
int32_t result_core__signal_total_events_sd0
#define VL53L1_TUNINGPARM_SPADMAP_VCSEL_PERIOD
#define VL53L1_TUNINGPARM_LITE_RANGE_CONFIG_TIMEOUT_US
#define VL53L1_DEVICEPRESETMODE_LOWPOWERAUTO_LONG_RANGE
uint32_t tp_range_timeout_timed_us
#define VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_LONG_RANGE
VL53L1_Error VL53L1_get_mode_mitigation_roi(VL53L1_DEV Dev, VL53L1_user_zone_t *pmm_roi)
Gets the current mode mitigation zone (ROI) configuration structure data.
VL53L1_Error VL53L1_data_init(VL53L1_DEV Dev, uint8_t read_p2p_data)
Get LL Driver version information.
VL53L1_Error VL53L1_calc_timeout_register_values(uint32_t phasecal_config_timeout_us, uint32_t mm_config_timeout_us, uint32_t range_config_timeout_us, uint16_t fast_osc_frequency, VL53L1_general_config_t *pgeneral, VL53L1_timing_config_t *ptiming)
Converts the input MM and range timeouts in [us] into the appropriate register values.
uint16_t target_count_rate_mcps
uint16_t system__thresh_low
void VL53L1_init_ll_driver_state(VL53L1_DEV Dev, VL53L1_DeviceState device_state)
Initialise LL Driver State.
#define VL53L1_ERROR_DIVISION_BY_ZERO
#define VL53L1_TUNINGPARM_INITIAL_PHASE_REF_LITE_SHORT_RANGE
VL53L1_Error VL53L1_set_offset_calibration_mode(VL53L1_DEV Dev, VL53L1_OffsetCalibrationMode offset_cal_mode)
Set function for offset calibration mode.
VL53L1_ll_version_t version
#define VL53L1_TUNINGPARM_TIMED_DSS_CONFIG_TARGET_TOTAL_RATE_MCPS
unsigned short uint16_t
Typedef defining 16 bit unsigned short type. The developer should modify this to suit the platform be...
#define VL53L1_DEVICERESULTSLEVEL_FULL
VL53L1_Error VL53L1_get_calibration_repeat_period(VL53L1_DEV Dev, uint16_t *pcal_config__repeat_period)
Gets the current 12-bit calibration repeat period value.
VL53L1_cal_peak_rate_map_t cal_peak_rate_map
uint32_t range_config_timeout_us
uint8_t pre_num_of_samples
uint8_t mm_config__timeout_macrop_a_hi
#define VL53L1_GENERAL_CONFIG_I2C_SIZE_BYTES
uint8_t tp_init_phase_rtn_lite_long
uint8_t vl53l1_tuningparm_spadmap_vcsel_start
#define VL53L1_CUSTOMER_NVM_MANAGED_I2C_SIZE_BYTES
uint32_t VL53L1_calc_macro_period_us(uint16_t fast_osc_frequency, uint8_t vcsel_period)
Forces shadow stream count to zero.
uint32_t vl53l1_tuningparm_lite_phasecal_config_timeout_us
uint32_t phasecal_config_timeout_us
VL53L1_Error VL53L1_get_user_zone(VL53L1_DEV Dev, VL53L1_user_zone_t *puser_zone)
Gets the current user zone (ROI) configuration structure data.
uint16_t vl53l1_tuningparm_lite_long_min_count_rate_rtn_mcps
void VL53L1_decode_row_col(uint8_t spad_number, uint8_t *prow, uint8_t *pcol)
Decodes the Byte.Bit coord encoding into an (x,y) coord value.
EwokPlus25 low level API function definitions.
#define VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_SHORT_RANGE
#define VL53L1_DEVICEPRESETMODE_SINGLESHOT_RANGING
int16_t nvm_default__crosstalk_compensation_x_plane_gradient_kcps
uint8_t tp_init_phase_ref_lite_short
#define VL53L1_DEVICEPRESETMODE_STANDARD_RANGING
uint8_t mm2_num_of_samples
uint32_t VL53L1_calc_crosstalk_plane_offset_with_margin(uint32_t plane_offset_kcps, int16_t margin_offset_kcps)
Function to add signed margin to the xtalk plane offset value, dealing with signed and unsigned value...
unsigned char uint8_t
Typedef defining 8 bit unsigned char type. The developer should modify this to suit the platform bein...
Internal data structure for storing post processed ranges.
#define VL53L1_DEVICEERROR_RANGECOMPLETE_NO_WRAP_CHECK
#define VL53L1_TUNINGPARM_LITE_SIGMA_EST_AMB_WIDTH_NS
unsigned int uint32_t
Typedef defining 32 bit unsigned int type. The developer should modify this to suit the platform bein...
uint16_t tp_lite_short_min_count_rate_rtn_mcps
VL53L1_Error VL53L1_preset_mode_timed_ranging_short_range(VL53L1_static_config_t *pstatic, VL53L1_general_config_t *pgeneral, VL53L1_timing_config_t *ptiming, VL53L1_dynamic_config_t *pdynamic, VL53L1_system_control_t *psystem, VL53L1_tuning_parm_storage_t *ptuning_parms)
Initializes static and dynamic configuration settings for preset mode VL53L1_DEVICEPRESETMODE_TIMED_R...