Go to the documentation of this file.
69 #ifndef _VL53L1_API_CORE_H_
70 #define _VL53L1_API_CORE_H_
231 uint32_t inter_measurement_period_ms);
248 uint32_t *pinter_measurement_period_ms);
268 uint32_t phasecal_config_timeout_us,
290 uint32_t *pphasecal_config_timeout_us,
292 uint32_t *prange_config_timeout_us);
316 uint16_t cal_config__repeat_period);
331 uint16_t *pcal_config__repeat_period);
407 #ifndef VL53L1_NOCALIB
423 #ifndef VL53L1_NOCALIB
443 uint8_t range_ignore_thresh_mult,
444 uint16_t range_ignore_threshold_mcps);
468 uint8_t *prange_ignore_thresh_mult,
469 uint16_t *prange_ignore_threshold_mcps_internal,
470 uint16_t *prange_ignore_threshold_mcps_current);
551 uint16_t dss_config__target_total_rate_mcps,
552 uint32_t phasecal_config_timeout_us,
555 uint32_t inter_measurement_period_ms);
577 uint16_t *pdss_config__target_total_rate_mcps,
578 uint32_t *pphasecal_config_timeout_us,
580 uint32_t *prange_config_timeout_us);
626 uint8_t *pcrosstalk_compensation_enable);
816 uint8_t intr_new_measure_ready,
VL53L1_Error VL53L1_get_offset_correction_mode(VL53L1_DEV Dev, VL53L1_OffsetCorrectionMode *poffset_cor_mode)
Get function for offset correction mode.
Defines User Zone(ROI) parameters.
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...
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...
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.
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.
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.
uint8_t VL53L1_DeviceConfigLevel
VL53L1_Error VL53L1_software_reset(VL53L1_DEV Dev)
Performs device software reset and then waits for the firmware to finish booting.
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...
VL53L1_Error VL53L1_get_device_results(VL53L1_DEV Dev, VL53L1_DeviceResultsLevel device_result_level, VL53L1_range_results_t *prange_results)
Get device system results, updates GPH registers and clears interrupt and configures SYSTEM__MODE_STA...
VL53L1_Error VL53L1_get_lite_xtalk_margin_kcps(VL53L1_DEV Dev, int16_t *pxtalk_margin)
Get function for Xtalk Margin setting Histogram Mode version.
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.
VL53L1_Error VL53L1_set_calibration_repeat_period(VL53L1_DEV Dev, uint16_t cal_config__repeat_period)
Sets the 12-bit calibration repeat period value.
Defines the parameters of the LL driver Get Version Functions.
Per Part calibration data.
VL53L1_Error VL53L1_get_part_to_part_data(VL53L1_DEV Dev, VL53L1_calibration_data_t *pcal_data)
Gets the customer part to part data.
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_set_offset_correction_mode(VL53L1_DEV Dev, VL53L1_OffsetCalibrationMode offset_cor_mode)
Set function for offset correction mode.
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.
VL53L1_Error VL53L1_get_sequence_config_bit(VL53L1_DEV Dev, VL53L1_DeviceSequenceConfig bit_id, uint8_t *pvalue)
Get system sequence config bit value.
VL53L1_Error VL53L1_get_interrupt_polarity(VL53L1_DEV Dev, VL53L1_DeviceInterruptPolarity *pinterrupt_polarity)
Get the interrupt polarity bit state.
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.
Structure to configure conditions when GPIO interrupt is trigerred.
VL53L1_Error VL53L1_set_tuning_parm(VL53L1_DEV Dev, VL53L1_TuningParms tuning_parm_key, int32_t tuning_parm_value)
Generic Tuning Parameter set function.
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_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.
uint8_t VL53L1_DevicePresetModes
Structure for storing the set of range results.
VL53L1_Error VL53L1_set_sequence_config_bit(VL53L1_DEV Dev, VL53L1_DeviceSequenceConfig bit_id, uint8_t value)
Set system sequence config bit value.
short int16_t
Typedef defining 16 bit short type. The developer should modify this to suit the platform being deplo...
VL53L1_Error VL53L1_set_offset_calibration_mode(VL53L1_DEV Dev, VL53L1_OffsetCalibrationMode offset_cal_mode)
Set function for offset calibration mode.
uint8_t VL53L1_GPIO_Interrupt_Mode
VL53L1_Error VL53L1_set_interrupt_polarity(VL53L1_DEV Dev, VL53L1_DeviceInterruptPolarity interrupt_polarity)
Set the interrupt polarity bit in.
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 ...
uint8_t VL53L1_OffsetCalibrationMode
VL53L1_Error VL53L1_enable_xtalk_compensation(VL53L1_DEV Dev)
Simple function to enable xtalk compensation.
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_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.
VL53L1_Error VL53L1_set_user_zone(VL53L1_DEV Dev, VL53L1_user_zone_t *puser_zone)
Sets the current user Zone (ROI) configuration structure data.
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_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 VL53L1_TuningParms
void VL53L1_get_xtalk_compensation_enable(VL53L1_DEV Dev, uint8_t *pcrosstalk_compensation_enable)
Simple function to retrieve xtalk compensation status.
VL53L1_Error VL53L1_get_offset_calibration_mode(VL53L1_DEV Dev, VL53L1_OffsetCalibrationMode *poffset_cal_mode)
Get function for offset calibration mode.
VL53L1_Error VL53L1_data_init(VL53L1_DEV Dev, uint8_t read_p2p_data)
Get LL Driver version information.
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 ...
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_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.
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.
int int32_t
Typedef defining 32 bit int type. The developer should modify this to suit the platform being deploye...
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_DeviceSequenceConfig
VL53L1_Error VL53L1_set_part_to_part_data(VL53L1_DEV Dev, VL53L1_calibration_data_t *pcal_data)
Sets the customer part to part data.
uint8_t VL53L1_DeviceInterruptPolarity
Reference SPAD Characterization (RefSpadChar) Config.
VL53L1_Error VL53L1_set_lite_xtalk_margin_kcps(VL53L1_DEV Dev, int16_t xtalk_margin)
Set function for Xtalk Margin setting Histogram Mode version.
uint8_t VL53L1_OffsetCorrectionMode
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_get_vhv_loopbound(VL53L1_DEV Dev, uint8_t *pvhv_loopbound)
Get function for VHV loopbound config.
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_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.
Tuning Parameters Debug data.
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_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.
uint8_t VL53L1_DeviceResultsLevel
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_xtalk_compensation(VL53L1_DEV Dev)
Simple function to disable xtalk compensation.
VL53L1_Error VL53L1_get_user_zone(VL53L1_DEV Dev, VL53L1_user_zone_t *puser_zone)
Gets the current user zone (ROI) configuration structure data.
VL53L1_Error VL53L1_get_measurement_results(VL53L1_DEV Dev, VL53L1_DeviceResultsLevel device_result_level)
Get range measurement result data.
VL53L1_Error VL53L1_set_vhv_loopbound(VL53L1_DEV Dev, uint8_t vhv_loopbound)
Set function for VHV loopbound config.
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.
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.
vl53l1x
Author(s):
autogenerated on Fri Aug 2 2024 08:35:54