Go to the documentation of this file.
81 #include "vl53l1_debug.h"
82 #include "vl53l1_register_debug.h"
85 #define LOG_FUNCTION_START(fmt, ...) \
86 _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_CORE, fmt, ##__VA_ARGS__)
87 #define LOG_FUNCTION_END(status, ...) \
88 _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_CORE, status, ##__VA_ARGS__)
89 #define LOG_FUNCTION_END_FMT(status, fmt, ...) \
90 _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_CORE, \
91 status, fmt, ##__VA_ARGS__)
93 #define trace_print(level, ...) \
94 _LOG_TRACE_PRINT(VL53L1_TRACE_MODULE_CORE, \
95 level, VL53L1_TRACE_FUNCTION_NONE, ##__VA_ARGS__)
158 #ifdef VL53L1_LOGGING
159 VL53L1_print_ll_driver_state(pstate);
245 #ifdef VL53L1_LOGGING
246 VL53L1_print_ll_driver_state(pstate);
272 uint8_t device_range_status = 0;
273 uint8_t device_stream_count = 0;
278 #ifdef VL53L1_LOGGING
279 VL53L1_print_ll_driver_state(pstate);
282 device_range_status =
309 if (device_range_status !=
322 if (pstate->
rd_gph_id != device_gph_id) {
324 #ifdef VL53L1_LOGGING
326 " RDSTATECHECK: Check failed: rd_gph_id: %d, device_gph_id: %d\n",
331 #ifdef VL53L1_LOGGING
333 " RDSTATECHECK: Check passed: rd_gph_id: %d, device_gph_id: %d\n",
364 #ifdef VL53L1_LOGGING
365 VL53L1_print_ll_driver_state(pstate);
427 #ifdef VL53L1_LOGGING
428 VL53L1_print_ll_driver_state(pstate);
534 for (i = 0; i < count ; i++) {
535 pbuffer[count-i-1] = (
uint8_t)(data & 0x00FF);
551 while (count-- > 0) {
552 value = (value << 8) | (
uint16_t)*pbuffer++;
574 for (i = 0; i < count ; i++) {
575 pbuffer[count-i-1] = (
uint8_t)(data & 0x00FF);
592 if (*pbuffer >= 0x80) {
596 while (count-- > 0) {
597 value = (value << 8) | (
int16_t)*pbuffer++;
618 for (i = 0; i < count ; i++) {
619 pbuffer[count-i-1] = (
uint8_t)(data & 0x00FF);
635 while (count-- > 0) {
636 value = (value << 8) | (
uint32_t)*pbuffer++;
658 while (count-- > 0) {
659 value = (value << 8) | (
uint32_t)*pbuffer++;
663 value = value & bit_mask;
664 if (down_shift > 0) {
665 value = value >> down_shift;
669 value = value + offset;
690 for (i = 0; i < count ; i++) {
691 pbuffer[count-i-1] = (
uint8_t)(data & 0x00FF);
708 if (*pbuffer >= 0x80) {
712 while (count-- > 0) {
713 value = (value << 8) | (
int32_t)*pbuffer++;
720 #ifndef VL53L1_NOCALIB
932 uint8_t vcsel_period_pclks = 0;
964 macro_period_us = macro_period_us >> 6;
966 macro_period_us = macro_period_us * (
uint32_t)vcsel_period_pclks;
967 macro_period_us = macro_period_us >> 6;
969 #ifdef VL53L1_LOGGING
971 " %-48s : %10u\n",
"pll_period_us",
974 " %-48s : %10u\n",
"vcsel_period_pclks",
977 " %-48s : %10u\n",
"macro_period_us",
983 return macro_period_us;
1007 int32_t range_ignore_thresh_int = 0;
1008 uint16_t range_ignore_thresh_kcps = 0;
1017 central_rate_int = ((
int32_t)central_rate * (1 << 4)) / (1000);
1019 if (x_gradient < 0) {
1020 x_gradient_int = x_gradient * -1;
1023 if (y_gradient < 0) {
1024 y_gradient_int = y_gradient * -1;
1031 range_ignore_thresh_int = (8 * x_gradient_int * 4) + (8 * y_gradient_int * 4);
1035 range_ignore_thresh_int = range_ignore_thresh_int / 1000;
1039 range_ignore_thresh_int = range_ignore_thresh_int + central_rate_int;
1043 range_ignore_thresh_int = (
int32_t)rate_mult * range_ignore_thresh_int;
1045 range_ignore_thresh_int = (range_ignore_thresh_int + (1<<4)) / (1<<5);
1049 if (range_ignore_thresh_int > 0xFFFF) {
1050 range_ignore_thresh_kcps = 0xFFFF;
1052 range_ignore_thresh_kcps = (
uint16_t)range_ignore_thresh_int;
1055 #ifdef VL53L1_LOGGING
1057 " %-48s : %10u\n",
"range_ignore_thresh_kcps",
1058 range_ignore_thresh_kcps);
1063 return range_ignore_thresh_kcps;
1085 ((timeout_us << 12) + (macro_period_us>>1)) /
1090 return timeout_mclks;
1118 #ifdef VL53L1_LOGGING
1120 " %-48s : %10u (0x%04X)\n",
"timeout_mclks",
1121 timeout_mclks, timeout_mclks);
1123 " %-48s : %10u (0x%04X)\n",
"timeout_encoded",
1124 timeout_encoded, timeout_encoded);
1129 return timeout_encoded;
1157 #ifdef VL53L1_LOGGING
1159 " %-48s : %10u (0x%04X)\n",
"timeout_mclks",
1160 timeout_mclks, timeout_mclks);
1163 " %-48s : %10u us\n",
"timeout_us",
1164 timeout_us, timeout_us);
1176 uint32_t plane_offset_with_margin = 0;
1177 int32_t plane_offset_kcps_temp = 0;
1181 plane_offset_kcps_temp =
1185 if (plane_offset_kcps_temp < 0) {
1186 plane_offset_kcps_temp = 0;
1188 if (plane_offset_kcps_temp > 0x3FFFF) {
1189 plane_offset_kcps_temp = 0x3FFFF;
1193 plane_offset_with_margin = (
uint32_t) plane_offset_kcps_temp;
1197 return plane_offset_with_margin;
1241 if (timeout_mclks > 0) {
1242 ls_byte = timeout_mclks - 1;
1244 while ((ls_byte & 0xFFFFFF00) > 0) {
1245 ls_byte = ls_byte >> 1;
1249 encoded_timeout = (ms_byte << 8)
1250 + (
uint16_t) (ls_byte & 0x000000FF);
1253 return encoded_timeout;
1266 timeout_macro_clks = ((
uint32_t) (encoded_timeout & 0x00FF)
1267 << (
uint32_t) ((encoded_timeout & 0xFF00) >> 8)) + 1;
1269 return timeout_macro_clks;
1274 uint32_t phasecal_config_timeout_us,
1296 if (fast_osc_frequency == 0) {
1308 phasecal_config_timeout_us,
1312 if (timeout_mclks > 0xFF)
1313 timeout_mclks = 0xFF;
1321 mm_config_timeout_us,
1325 (
uint8_t)((timeout_encoded & 0xFF00) >> 8);
1327 (
uint8_t) (timeout_encoded & 0x00FF);
1332 range_config_timeout_us,
1336 (
uint8_t)((timeout_encoded & 0xFF00) >> 8);
1338 (
uint8_t) (timeout_encoded & 0x00FF);
1349 mm_config_timeout_us,
1353 (
uint8_t)((timeout_encoded & 0xFF00) >> 8);
1355 (
uint8_t) (timeout_encoded & 0x00FF);
1359 range_config_timeout_us,
1363 (
uint8_t)((timeout_encoded & 0xFF00) >> 8);
1365 (
uint8_t) (timeout_encoded & 0x00FF);
1384 vcsel_period_reg = (vcsel_period_pclks >> 1) - 1;
1386 return vcsel_period_reg;
1401 for (i = 0 ; i < no_of_bytes ; i++) {
1402 decoded_value = (decoded_value << 8) + (
uint32_t)pbuffer[i];
1405 return decoded_value;
1422 for (i = 0; i < no_of_bytes ; i++) {
1423 pbuffer[no_of_bytes-i-1] = data & 0x00FF;
1444 *pbyte_index = spad_number >> 3;
1445 *pbit_index = spad_number & 0x07;
1446 *pbit_mask = 0x01 << *pbit_index;
1461 *pspad_number = 128 + (col << 3) + (15-row);
1463 *pspad_number = ((15-col) << 3) + row;
1483 *pheight = encoded_xy_size >> 4;
1484 *pwidth = encoded_xy_size & 0x0F;
1503 *pencoded_xy_size = (height << 4) + width;
1547 *px_ur = *px_ll + (
int16_t)width;
1555 *py_ur = *py_ll + (
int16_t)height;
1573 if (mod_row == 0 && mod_col == 2)
1576 if (mod_row == 2 && mod_col == 0)
1584 uint8_t encoded_mm_roi_centre,
1590 uint16_t *pmm_inner_effective_spads,
1591 uint16_t *pmm_outer_effective_spads)
1623 encoded_mm_roi_centre,
1624 encoded_mm_roi_size,
1631 encoded_zone_centre,
1645 *pmm_inner_effective_spads = 0;
1646 *pmm_outer_effective_spads = 0;
1648 for (y = zone_y_ll ; y <= zone_y_ur ; y++) {
1649 for (x = zone_x_ll ; x <= zone_x_ur ; x++) {
1672 if ((pgood_spads[byte_index] & bit_mask) > 0) {
1679 if (is_aperture > 0)
1680 spad_attenuation = aperture_attenuation;
1682 spad_attenuation = 0x0100;
1689 if (x >= mm_x_ll && x <= mm_x_ur &&
1690 y >= mm_y_ll && y <= mm_y_ur)
1691 *pmm_inner_effective_spads +=
1694 *pmm_outer_effective_spads +=
1709 uint8_t system__interrupt_config;
1717 return system__interrupt_config;
1725 uint8_t system__interrupt_config)
1818 #ifndef VL53L1_NOCALIB
1824 uint16_t max_count_rate_rtn_limit_mcps,
1825 uint16_t min_count_rate_rtn_limit_mcps,
1855 timeout_mclks = phasecal_timeout_us << 12;
1856 timeout_mclks = timeout_mclks + (macro_period_us>>1);
1857 timeout_mclks = timeout_mclks / macro_period_us;
1859 if (timeout_mclks > 0xFF)
1906 total_rate_target_mcps;
1913 total_rate_target_mcps);
1920 max_count_rate_rtn_limit_mcps);
1927 min_count_rate_rtn_limit_mcps);
1990 buffer[0] = (
uint8_t)((timeout_encoded & 0x0000FF00) >> 8);
1991 buffer[1] = (
uint8_t) (timeout_encoded & 0x000000FF);
2038 #ifndef VL53L1_NOCALIB
2198 VL53L1_SEQUENCE_VHV_EN | \
2199 VL53L1_SEQUENCE_PHASECAL_EN | \
2200 VL53L1_SEQUENCE_DSS1_EN | \
2280 if (utemp32a > 0xFFFF)
2285 utemp32a = utemp32a << 16;
2292 utemp32a = utemp32a /
2309 utemp32a = utemp32a /
2313 if (utemp32a > 0xFFFF)
uint8_t global_config__spad_enables_rtn_20
uint16_t system__thresh_rate_high
#define VL53L1_DEVICEDSSMODE__REQUESTED_EFFFECTIVE_SPADS
void VL53L1_init_ll_driver_state(VL53L1_DEV Dev, VL53L1_DeviceState device_state)
Initialise LL Driver State.
uint16_t result__dss_actual_effective_spads_sd1
uint8_t mm_config__timeout_macrop_b_lo
uint32_t VL53L1_i2c_decode_with_mask(uint16_t count, uint8_t *pbuffer, uint32_t bit_mask, uint32_t down_shift, uint32_t offset)
Decodes an integer register value from an I2C read buffer.
Structure to hold state, tuning and output variables for the low power auto mode (Presence)
Type definitions for VL53L1 LL Driver.
uint32_t VL53L1_calc_macro_period_us(uint16_t fast_osc_frequency, uint8_t vcsel_period)
Forces shadow stream count to zero.
uint16_t system__thresh_low
unsigned int uint32_t
Typedef defining 32 bit unsigned int type. The developer should modify this to suit the platform bein...
unsigned char uint8_t
Typedef defining 8 bit unsigned char type. The developer should modify this to suit the platform bein...
uint8_t mm_config__timeout_macrop_a_lo
EwokPlus25 low level API function definitions.
VL53L1_ll_version_t version
#define VL53L1_DEVICESTATE_RANGING_OUTPUT_DATA
uint8_t global_config__spad_enables_rtn_5
#define VL53L1_SEQUENCE_RANGE_EN
VL53L1_DeviceSscArray array_select
#define LOG_FUNCTION_START(fmt,...)
uint16_t result__phase_sd1
void VL53L1_i2c_encode_uint32_t(uint32_t ip_value, uint16_t count, uint8_t *pbuffer)
Encodes a uint32_t register value into an I2C write buffer.
uint16_t result__final_crosstalk_corrected_range_mm_sd0
uint8_t power_management__go1_power_force
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.
#define VL53L1_LL_API_IMPLEMENTATION_VER_SUB
unsigned long long uint64_t
void VL53L1_i2c_encode_uint16_t(uint16_t ip_value, uint16_t count, uint8_t *pbuffer)
Encodes a uint16_t register value into an I2C write buffer.
uint16_t system__thresh_high
#define VL53L1_FIRMWARE__ENABLE
VL53L1_ll_driver_state_t ll_state
#define VL53L1_NVM_BIST__CTRL
#define VL53L1_SHADOW_RESULT__STREAM_COUNT
uint8_t system__mode_start
uint8_t range_config__vcsel_period_a
uint8_t global_config__spad_enables_rtn_17
uint8_t VL53L1_decode_vcsel_period(uint8_t vcsel_period_reg)
Decodes VCSEL period register value into the real period in PLL clocks.
uint16_t threshold_distance_high
VL53L1_Error VL53L1_set_ssc_config(VL53L1_DEV Dev, VL53L1_ssc_config_t *pssc_cfg, uint16_t fast_osc_frequency)
Applies SSC (SPAD Self Check) configuration to device.
#define VL53L1_RANGE_CONFIG__SIGMA_THRESH
uint16_t dss_config__manual_effective_spads_select
VL53L1_Error VL53L1_get_spad_rate_data(VL53L1_DEV Dev, VL53L1_spad_rate_data_t *pspad_rates)
Gets the 256 return array SSC rates from the Patch RAM.
uint16_t result__ambient_count_rate_mcps_sd0
uint8_t range_config__timeout_macrop_a_lo
VL53L1_Error VL53L1_update_ll_driver_rd_state(VL53L1_DEV Dev)
Update LL Driver Read State.
uint16_t dss_config__target_total_rate_mcps
uint8_t range_config__timeout_macrop_a_hi
uint16_t VL53L1_calc_encoded_timeout(uint32_t timeout_us, uint32_t macro_period_us)
Calculates the encoded timeout register value based on the input timeout period in milliseconds and t...
uint8_t low_power_auto_range_count
#define VL53L1_LL_API_IMPLEMENTATION_VER_MAJOR
VL53L1_Error VL53L1_clear_interrupt(VL53L1_DEV Dev)
Clears Ranging Interrupt.
VL53L1_Error VL53L1_set_GPIO_rate_threshold(VL53L1_DEV Dev, uint16_t threshold_high, uint16_t threshold_low)
SET GPIO rate threshold.
#define VL53L1_RANGE_CONFIG__MIN_COUNT_RATE_RTN_LIMIT_MCPS
uint8_t dss_config__roi_mode_control
uint8_t VL53L1_encode_GPIO_interrupt_config(VL53L1_GPIO_interrupt_config_t *pintconf)
Encodes VL53L1_GPIO_interrupt_config_t structure to FW register format.
uint8_t VL53L1_DeviceState
uint16_t dss__required_spads
Device register setting defines.
EwokPlus25 API core function definition.
#define VL53L1_GROUPEDPARAMETERHOLD_ID_MASK
VL53L1_Error VL53L1_enable_firmware(VL53L1_DEV Dev)
Enables MCU firmware.
SPAD Rate Data output by SSC.
uint8_t global_config__spad_enables_rtn_8
#define VL53L1_ERROR_GPH_ID_CHECK_FAIL
#define VL53L1_SD_CONFIG__WOI_SD0
uint16_t result__spare_1_sd1
uint32_t VL53L1_i2c_decode_uint32_t(uint16_t count, uint8_t *pbuffer)
Decodes a uint32_t register value from an I2C read buffer.
uint8_t phasecal_config__override
SPAD Self Check (SSC) Config data structure.
uint8_t global_config__spad_enables_rtn_0
uint8_t global_config__spad_enables_rtn_25
#define VL53L1_LL_API_IMPLEMENTATION_VER_MINOR
#define VL53L1_TUNINGPARM_LOWPOWERAUTO_VHV_LOOP_BOUND_DEFAULT
VL53L1_Error VL53L1_low_power_auto_data_stop_range(VL53L1_DEV Dev)
Reset internal state but leave low_power_auto mode intact.
#define VL53L1_TEST_MODE__CTRL
uint8_t saved_vhv_timeout
EwokPlus25 core function definitions.
uint16_t result__peak_signal_count_rate_crosstalk_corrected_mcps_sd0
#define VL53L1_PRIVATE__PATCH_BASE_ADDR_RSLV
uint8_t global_config__spad_enables_rtn_6
VL53L1_timing_config_t tim_cfg
Structure to configure conditions when GPIO interrupt is trigerred.
uint16_t result__spare_0_sd1
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.
VL53L1_Error VL53L1_update_ll_driver_cfg_state(VL53L1_DEV Dev)
Update LL Driver Configuration State.
uint16_t result__phase_sd0
uint8_t vhv_config__timeout_macrop_loop_bound
uint8_t global_config__spad_enables_rtn_27
void VL53L1_init_version(VL53L1_DEV Dev)
Initialise version info in pdev.
uint16_t result__peak_signal_count_rate_mcps_sd1
VL53L1_Error VL53L1_set_powerforce_register(VL53L1_DEV Dev, uint8_t value)
Set power force register.
uint8_t global_config__spad_enables_rtn_4
uint32_t VL53L1_calc_timeout_mclks(uint32_t timeout_us, uint32_t macro_period_us)
Calculates the timeout value in macro period based on the input timeout period in milliseconds and th...
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.
VL53L1 Register Function declarations.
#define VL53L1_ERROR_STREAM_COUNT_CHECK_FAIL
uint16_t result__sigma_sd1
void VL53L1_calc_mm_effective_spads(uint8_t encoded_mm_roi_centre, uint8_t encoded_mm_roi_size, uint8_t encoded_zone_centre, uint8_t encoded_zone_size, uint8_t *pgood_spads, uint16_t aperture_attenuation, uint16_t *pmm_inner_effective_spads, uint16_t *pmm_outer_effective_spads)
Calculates the effective SPAD counts for the MM inner and outer regions based on the input MM ROI,...
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.
#define VL53L1_DEVICEERROR_GPHSTREAMCOUNT0READY
VL53L1_Error VL53L1_low_power_auto_data_init(VL53L1_DEV Dev)
Initialize the Low Power Auto data structure.
VL53L1_GPIO_Interrupt_Mode intr_mode_rate
uint8_t system__interrupt_clear
short int16_t
Typedef defining 16 bit short type. The developer should modify this to suit the platform being deplo...
VL53L1_general_config_t gen_cfg
#define LOG_FUNCTION_END(status,...)
VL53L1_dynamic_config_t dyn_cfg
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 VL53L1_i2c_decode_uint16_t(uint16_t count, uint8_t *pbuffer)
Decodes a uint16_t register value from an I2C read buffer.
uint8_t global_config__spad_enables_rtn_3
uint8_t range_config__timeout_macrop_b_hi
uint16_t result__spare_2_sd1
uint8_t global_config__spad_enables_rtn_13
#define VL53L1_CAL_CONFIG__VCSEL_START
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.
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.
uint8_t intr_combined_mode
VL53L1_DeviceState cfg_device_state
uint8_t global_config__spad_enables_rtn_1
uint8_t global_config__spad_enables_rtn_26
uint8_t saved_interrupt_config
VL53L1 Register Map definitions.
uint8_t global_config__spad_enables_rtn_2
#define trace_print(level,...)
#define VL53L1_DEVICESTATE_RANGING_DSS_AUTO
uint8_t first_run_phasecal_result
uint8_t cal_config__vcsel_start
VL53L1_Error VL53L1_start_test(VL53L1_DEV Dev, uint8_t test_mode__ctrl)
Triggers the start of the provided test_mode.
uint8_t global_config__spad_enables_rtn_7
uint8_t VL53L1_encode_vcsel_period(uint8_t vcsel_period_pclks)
Encodes the real period in PLL clocks into the register value.
uint16_t VL53L1_encode_timeout(uint32_t timeout_mclks)
Encode timeout in (LSByte * 2^MSByte) + 1 register format.
VL53L1_debug_results_t dbg_results
uint16_t result__avg_signal_count_rate_mcps_sd0
#define VL53L1_PHASECAL_CONFIG__TIMEOUT_MACROP
VL53L1_Error VL53L1_set_firmware_enable_register(VL53L1_DEV Dev, uint8_t value)
Set firmware enable register.
uint8_t phasecal_result__vcsel_start
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...
uint16_t threshold_rate_low
VL53L1_DeviceState rd_device_state
uint16_t threshold_distance_low
uint8_t range_config__timeout_macrop_b_lo
uint16_t ref_spad_char__total_rate_target_mcps
uint8_t result__stream_count
uint8_t result__spare_3_sd1
uint8_t system__sequence_config
#define VL53L1_ERROR_NONE
uint8_t global_config__spad_enables_rtn_23
#define VL53L1_CLEAR_RANGE_INT
uint8_t global_config__spad_enables_rtn_9
#define VL53L1_SPAD_ARRAY_HEIGHT
uint16_t result__mm_inner_actual_effective_spads_sd0
#define VL53L1_INTERRUPT_STATUS__GPH_ID_INT_STATUS_MASK
uint8_t intr_new_measure_ready
#define VL53L1_RANGE_CONFIG__TIMEOUT_MACROP_B_HI
VL53L1_system_results_t sys_results
uint16_t system__thresh_rate_low
VL53L1_Error VL53L1_set_ref_spad_char_config(VL53L1_DEV Dev, uint8_t vcsel_period_a, uint32_t phasecal_timeout_us, uint16_t total_rate_target_mcps, uint16_t max_count_rate_rtn_limit_mcps, uint16_t min_count_rate_rtn_limit_mcps, uint16_t fast_osc_frequency)
Set Ref SPAD Characterisation Config.
uint8_t global_config__spad_enables_rtn_31
VL53L1_Error VL53L1_low_power_auto_update_DSS(VL53L1_DEV Dev)
Do a DSS calculation and update manual config.
uint8_t global_config__spad_enables_rtn_22
VL53L1_Error VL53L1_set_GPIO_distance_threshold(VL53L1_DEV Dev, uint16_t threshold_high, uint16_t threshold_low)
SET GPIO distance threshold.
void VL53L1_i2c_encode_int16_t(int16_t ip_value, uint16_t count, uint8_t *pbuffer)
Encodes a int16_t register value into an I2C write buffer.
uint8_t global_config__spad_enables_rtn_12
uint8_t mm_config__timeout_macrop_b_hi
uint32_t VL53L1_calc_pll_period_us(uint16_t fast_osc_frequency)
Calculates the PLL period in [us] from the input fast_osc_frequency.
#define VL53L1_GLOBAL_CONFIG__VCSEL_WIDTH
VL53L1_Error VL53L1_enable_powerforce(VL53L1_DEV Dev)
Enables power force.
uint8_t global_config__spad_enables_rtn_24
uint8_t result__range_status
Define defaults for tuning parm list.
#define VL53L1_SPAD_ARRAY_WIDTH
uint8_t global_config__spad_enables_rtn_30
int int32_t
Typedef defining 32 bit int type. The developer should modify this to suit the platform being deploye...
#define VL53L1_RANGE_CONFIG__VCSEL_PERIOD_A
uint16_t result__ambient_count_rate_mcps_sd1
void VL53L1_i2c_encode_int32_t(int32_t ip_value, uint16_t count, uint8_t *pbuffer)
Encodes a int32_t register value into an I2C write buffer.
uint8_t global_config__spad_enables_rtn_14
uint8_t global_config__spad_enables_rtn_21
VL53L1_customer_nvm_managed_t customer
VL53L1_GPIO_Interrupt_Mode intr_mode_distance
uint16_t result__dss_actual_effective_spads_sd0
void VL53L1_spad_number_to_byte_bit_index(uint8_t spad_number, uint8_t *pbyte_index, uint8_t *pbit_index, uint8_t *pbit_mask)
Get the SPAD number, byte index (0-31) and bit index (0-7) for.
uint16_t rate_data[VL53L1_NO_OF_SPAD_ENABLES]
#define VL53L1_DEVICESTATE_SW_STANDBY
uint8_t global_config__spad_enables_rtn_29
uint32_t VL53L1_decode_timeout(uint16_t encoded_timeout)
Decode 16-bit timeout register value.
uint8_t system__grouped_parameter_hold
int32_t VL53L1_i2c_decode_int32_t(uint16_t count, uint8_t *pbuffer)
Decodes a int32_t register value from an I2C read buffer.
#define VL53L1_ERROR_DIVISION_BY_ZERO
uint16_t threshold_rate_high
VL53L1_Error VL53L1_disable_powerforce(VL53L1_DEV Dev)
Disables power force.
uint8_t global_config__spad_enables_rtn_19
VL53L1_Error VL53L1_config_low_power_auto_mode(VL53L1_general_config_t *pgeneral, VL53L1_dynamic_config_t *pdynamic, VL53L1_low_power_auto_data_t *plpadata)
Initialize the config strcutures when low power auto preset modes are selected.
uint8_t result__report_status
VL53L1_system_control_t sys_ctrl
uint8_t cfg_timing_status
#define VL53L1_ERROR_GPH_SYNC_CHECK_FAIL
uint8_t global_config__spad_enables_rtn_28
void VL53L1_decode_zone_limits(uint8_t encoded_xy_centre, uint8_t encoded_xy_size, int16_t *px_ll, int16_t *py_ll, int16_t *px_ur, int16_t *py_ur)
Decodes encoded zone info into min/max limits.
VL53L1_low_power_auto_data_t low_power_auto_data
#define VL53L1_POWER_MANAGEMENT__GO1_POWER_FORCE
#define VL53L1_DEVICESTATE_RANGING_GATHER_DATA
uint8_t global_config__spad_enables_rtn_16
LL Driver Device specific defines. To be adapted by implementer for the targeted device.
VL53L1_static_config_t stat_cfg
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.
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 ...
int16_t VL53L1_i2c_decode_int16_t(uint16_t count, uint8_t *pbuffer)
Decodes a int16_t register value from an I2C read buffer.
#define VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK
#define VL53L1_DEVICESTATE_RANGING_WAIT_GPH_SYNC
void VL53L1_init_system_results(VL53L1_system_results_t *pdata)
Initialise system results structure to all ones.
VL53L1 LL Driver ST private data structure .
#define VL53L1_NO_OF_SPAD_ENABLES
uint16_t result__peak_signal_count_rate_mcps_sd0
#define VL53L1_REF_SPAD_CHAR__TOTAL_RATE_TARGET_MCPS
uint16_t result__sigma_sd0
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.
Contains the driver state information.
uint8_t phasecal_config__timeout_macrop
#define VL53L1_RANGE_STATUS__RANGE_STATUS_MASK
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 result__interrupt_status
void VL53L1_encode_unsigned_integer(uint32_t ip_value, uint8_t no_of_bytes, uint8_t *pbuffer)
Encodes an unsigned integer into a uint8_t buffer MS byte first.
uint16_t result__mm_outer_actual_effective_spads_sd0
uint8_t range_config__vcsel_period_b
#define VL53L1_SYSTEM__INTERRUPT_CLEAR
unsigned short uint16_t
Typedef defining 16 bit unsigned short type. The developer should modify this to suit the platform be...
VL53L1_Error VL53L1_disable_firmware(VL53L1_DEV Dev)
Disables MCU firmware.
uint32_t VL53L1_decode_unsigned_integer(uint8_t *pbuffer, uint8_t no_of_bytes)
Decodes an unsigned integer from a uint8_t buffer 16-bit, 24-bit or 32-bit integers.
#define VL53L1_DEVICEMEASUREMENTMODE_MODE_MASK
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...
uint8_t VL53L1_is_aperture_location(uint8_t row, uint8_t col)
Returns > 0 if input (row,col) location is an apertured SPAD.
uint8_t global_config__spad_enables_rtn_15
uint32_t dss__total_rate_per_spad_mcps
uint16_t result__final_crosstalk_corrected_range_mm_sd1
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_MACRO_PERIOD_VCSEL_PERIODS
uint8_t is_low_power_auto_mode
VL53L1_static_nvm_managed_t stat_nvm
#define VL53L1_LL_API_IMPLEMENTATION_VER_REVISION
uint8_t global_config__spad_enables_rtn_10
uint8_t global_config__spad_enables_rtn_11
uint8_t mm_config__timeout_macrop_a_hi
uint8_t global_config__spad_enables_rtn_18
vl53l1x
Author(s):
autogenerated on Fri Aug 2 2024 08:35:54