Go to the documentation of this file.
69 #ifndef _VL53L1_CORE_H_
70 #define _VL53L1_CORE_H_
337 #ifndef VL53L1_NOCALIB
616 uint32_t phasecal_config_timeout_us,
796 uint16_t *pmm_inner_effective_spads,
797 uint16_t *pmm_outer_effective_spads);
831 uint8_t system__interrupt_config);
902 #ifndef VL53L1_NOCALIB
908 uint16_t max_count_rate_rtn_limit_mcps,
909 uint16_t min_count_rate_rtn_limit_mcps,
950 #ifndef VL53L1_NOCALIB
983 #ifndef VL53L1_NOCALIB
uint16_t VL53L1_encode_timeout(uint32_t timeout_mclks)
Encode timeout in (LSByte * 2^MSByte) + 1 register format.
Structure to hold state, tuning and output variables for the low power auto mode (Presence)
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.
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...
EwokPlus25 core function definitions.
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_Error VL53L1_disable_firmware(VL53L1_DEV Dev)
Disables MCU firmware.
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.
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...
uint32_t VL53L1_calc_macro_period_us(uint16_t fast_osc_frequency, uint8_t vcsel_period)
Forces shadow stream count to zero.
void VL53L1_init_ll_driver_state(VL53L1_DEV Dev, VL53L1_DeviceState ll_state)
Initialise LL Driver State.
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_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.
uint32_t VL53L1_decode_timeout(uint16_t encoded_timeout)
Decode 16-bit timeout register value.
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...
VL53L1_Error VL53L1_disable_powerforce(VL53L1_DEV Dev)
Disables power force.
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.
VL53L1_Error VL53L1_enable_firmware(VL53L1_DEV Dev)
Enables MCU firmware.
uint8_t VL53L1_DeviceState
int32_t VL53L1_i2c_decode_int32_t(uint16_t count, uint8_t *pbuffer)
Decodes a int32_t register value from an I2C read buffer.
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.
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.
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.
SPAD Rate Data output by SSC.
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.
uint8_t VL53L1_encode_GPIO_interrupt_config(VL53L1_GPIO_interrupt_config_t *pintconf)
Encodes VL53L1_GPIO_interrupt_config_t structure to FW register format.
SPAD Self Check (SSC) Config data structure.
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.
Structure to configure conditions when GPIO interrupt is trigerred.
VL53L1_Error VL53L1_low_power_auto_update_DSS(VL53L1_DEV Dev)
Do a DSS calculation and update manual config.
uint8_t VL53L1_is_aperture_location(uint8_t row, uint8_t col)
Returns > 0 if input (row,col) location is an apertured SPAD.
void V53L1_init_zone_dss_configs(VL53L1_DEV Dev)
Initialise zone dynamic config DSS control values.
VL53L1_Error VL53L1_low_power_auto_data_init(VL53L1_DEV Dev)
Initialize the Low Power Auto data structure.
short int16_t
Typedef defining 16 bit short type. The developer should modify this to suit the platform being deplo...
VL53L1_Error VL53L1_set_powerforce_register(VL53L1_DEV Dev, uint8_t value)
Set power force register.
VL53L1_Error VL53L1_set_firmware_enable_register(VL53L1_DEV Dev, uint8_t value)
Set firmware enable register.
int16_t VL53L1_i2c_decode_int16_t(uint16_t count, uint8_t *pbuffer)
Decodes a int16_t register value from an I2C read buffer.
uint16_t VL53L1_i2c_decode_uint16_t(uint16_t count, uint8_t *pbuffer)
Decodes a uint16_t register value from an I2C read buffer.
VL53L1_Error VL53L1_update_ll_driver_rd_state(VL53L1_DEV Dev)
Update LL Driver Read State.
VL53L1_Error VL53L1_set_GPIO_rate_threshold(VL53L1_DEV Dev, uint16_t threshold_high, uint16_t threshold_low)
SET GPIO rate threshold.
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.
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.
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.
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.
VL53L1_Error VL53L1_low_power_auto_data_stop_range(VL53L1_DEV Dev)
Reset internal state but leave low_power_auto mode intact.
VL53L1_Error VL53L1_set_GPIO_distance_threshold(VL53L1_DEV Dev, uint16_t threshold_high, uint16_t threshold_low)
SET GPIO distance threshold.
VL53L1_Error VL53L1_enable_powerforce(VL53L1_DEV Dev)
Enables power force.
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.
int int32_t
Typedef defining 32 bit int type. The developer should modify this to suit the platform being deploye...
void VL53L1_init_system_results(VL53L1_system_results_t *pdata)
Initialise system results structure to all ones.
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.
void VL53L1_init_version(VL53L1_DEV Dev)
Initialise version info in pdev.
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...
VL53L1_Error VL53L1_update_ll_driver_cfg_state(VL53L1_DEV Dev)
Update LL Driver Configuration State.
uint8_t VL53L1_encode_vcsel_period(uint8_t vcsel_period_pclks)
Encodes the real period in PLL clocks into the register value.
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...
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_encode_row_col(uint8_t row, uint8_t col, uint8_t *pspad_number)
Encodes a (col,row) coord value into ByteIndex.BitIndex format.
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 ...
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...
unsigned short uint16_t
Typedef defining 16 bit unsigned short type. The developer should modify this to suit the platform be...
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_Error VL53L1_start_test(VL53L1_DEV Dev, uint8_t test_mode__ctrl)
Triggers the start of the provided test_mode.
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...
uint32_t VL53L1_i2c_decode_uint32_t(uint16_t count, uint8_t *pbuffer)
Decodes a uint32_t register value from an I2C read buffer.
VL53L1_Error VL53L1_save_cfg_data(VL53L1_DEV Dev)
Function to save dynamic config data per zone at init and start range.
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_Error VL53L1_clear_interrupt(VL53L1_DEV Dev)
Clears Ranging Interrupt.
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.
vl53l1x
Author(s):
autogenerated on Fri Aug 2 2024 08:35:54