EwokPlus25 low level API function definition. More...
#include "vl53l1_ll_def.h"
#include "vl53l1_ll_device.h"
#include "vl53l1_platform.h"
#include "vl53l1_register_map.h"
#include "vl53l1_register_settings.h"
#include "vl53l1_register_funcs.h"
#include "vl53l1_nvm_map.h"
#include "vl53l1_core.h"
#include "vl53l1_wait.h"
#include "vl53l1_api_preset_modes.h"
#include "vl53l1_silicon_core.h"
#include "vl53l1_api_core.h"
#include "vl53l1_tuning_parm_defaults.h"
Go to the source code of this file.
Macros | |
#define | LOG_FUNCTION_END(status, ...) _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_CORE, status, ##__VA_ARGS__) |
#define | LOG_FUNCTION_END_FMT(status, fmt, ...) |
#define | LOG_FUNCTION_START(fmt, ...) _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_CORE, fmt, ##__VA_ARGS__) |
#define | trace_print(level, ...) |
#define | VL53L1_MAX_I2C_XFER_SIZE 256 |
Functions | |
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. More... | |
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. More... | |
VL53L1_Error | VL53L1_data_init (VL53L1_DEV Dev, uint8_t read_p2p_data) |
Get LL Driver version information. More... | |
VL53L1_Error | VL53L1_disable_xtalk_compensation (VL53L1_DEV Dev) |
Simple function to disable xtalk compensation. More... | |
VL53L1_Error | VL53L1_enable_xtalk_compensation (VL53L1_DEV Dev) |
Simple function to enable xtalk compensation. More... | |
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. More... | |
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_START based on the input measurement mode. More... | |
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. More... | |
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. More... | |
VL53L1_Error | VL53L1_get_interrupt_polarity (VL53L1_DEV Dev, VL53L1_DeviceInterruptPolarity *pinterrupt_polarity) |
Get the interrupt polarity bit state. More... | |
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 signal rate. More... | |
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 estimated sigma level. More... | |
VL53L1_Error | VL53L1_get_lite_xtalk_margin_kcps (VL53L1_DEV Dev, int16_t *pxtalk_margin) |
Get function for Xtalk Margin setting Histogram Mode version. More... | |
VL53L1_Error | VL53L1_get_measurement_results (VL53L1_DEV Dev, VL53L1_DeviceResultsLevel device_results_level) |
Get range measurement result data. More... | |
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. More... | |
VL53L1_Error | VL53L1_get_offset_calibration_mode (VL53L1_DEV Dev, VL53L1_OffsetCalibrationMode *poffset_cal_mode) |
Get function for offset calibration mode. More... | |
VL53L1_Error | VL53L1_get_offset_correction_mode (VL53L1_DEV Dev, VL53L1_OffsetCorrectionMode *poffset_cor_mode) |
Get function for offset correction mode. More... | |
VL53L1_Error | VL53L1_get_part_to_part_data (VL53L1_DEV Dev, VL53L1_calibration_data_t *pcal_data) |
Gets the customer part to part data. More... | |
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. More... | |
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. More... | |
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. More... | |
VL53L1_Error | VL53L1_get_sequence_config_bit (VL53L1_DEV Dev, VL53L1_DeviceSequenceConfig bit_id, uint8_t *pvalue) |
Get system sequence config bit value. More... | |
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. More... | |
VL53L1_Error | VL53L1_get_tuning_parm (VL53L1_DEV Dev, VL53L1_TuningParms tuning_parm_key, int32_t *ptuning_parm_value) |
Generic Tuning Parameter extraction function. More... | |
VL53L1_Error | VL53L1_get_user_zone (VL53L1_DEV Dev, VL53L1_user_zone_t *puser_zone) |
Gets the current user zone (ROI) configuration structure data. More... | |
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. More... | |
VL53L1_Error | VL53L1_get_vhv_loopbound (VL53L1_DEV Dev, uint8_t *pvhv_loopbound) |
Get function for VHV loopbound config. More... | |
void | VL53L1_get_xtalk_compensation_enable (VL53L1_DEV Dev, uint8_t *pcrosstalk_compensation_enable) |
Simple function to retrieve xtalk compensation status. More... | |
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. More... | |
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. More... | |
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. More... | |
VL53L1_Error | VL53L1_set_calibration_repeat_period (VL53L1_DEV Dev, uint16_t cal_config__repeat_period) |
Sets the 12-bit calibration repeat period value. More... | |
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. More... | |
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. More... | |
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. More... | |
VL53L1_Error | VL53L1_set_interrupt_polarity (VL53L1_DEV Dev, VL53L1_DeviceInterruptPolarity interrupt_polarity) |
Set the interrupt polarity bit in. More... | |
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 signal rate. More... | |
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 estimated sigma level. More... | |
VL53L1_Error | VL53L1_set_lite_xtalk_margin_kcps (VL53L1_DEV Dev, int16_t xtalk_margin) |
Set function for Xtalk Margin setting Histogram Mode version. More... | |
VL53L1_Error | VL53L1_set_offset_calibration_mode (VL53L1_DEV Dev, VL53L1_OffsetCalibrationMode offset_cal_mode) |
Set function for offset calibration mode. More... | |
VL53L1_Error | VL53L1_set_offset_correction_mode (VL53L1_DEV Dev, VL53L1_OffsetCorrectionMode offset_cor_mode) |
Set function for offset correction mode. More... | |
VL53L1_Error | VL53L1_set_part_to_part_data (VL53L1_DEV Dev, VL53L1_calibration_data_t *pcal_data) |
Sets the customer part to part data. More... | |
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. More... | |
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. More... | |
VL53L1_Error | VL53L1_set_refspadchar_config_struct (VL53L1_DEV Dev, VL53L1_refspadchar_config_t *pdata) |
Extract the Ref spad char cfg struct from pdev. More... | |
VL53L1_Error | VL53L1_set_sequence_config_bit (VL53L1_DEV Dev, VL53L1_DeviceSequenceConfig bit_id, uint8_t value) |
Set system sequence config bit value. More... | |
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. More... | |
VL53L1_Error | VL53L1_set_tuning_parm (VL53L1_DEV Dev, VL53L1_TuningParms tuning_parm_key, int32_t tuning_parm_value) |
Generic Tuning Parameter set function. More... | |
VL53L1_Error | VL53L1_set_user_zone (VL53L1_DEV Dev, VL53L1_user_zone_t *puser_zone) |
Sets the current user Zone (ROI) configuration structure data. More... | |
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. More... | |
VL53L1_Error | VL53L1_set_vhv_loopbound (VL53L1_DEV Dev, uint8_t vhv_loopbound) |
Set function for VHV loopbound config. More... | |
VL53L1_Error | VL53L1_software_reset (VL53L1_DEV Dev) |
Performs device software reset and then waits for the firmware to finish booting. More... | |
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. More... | |
EwokPlus25 low level API function definition.
Definition in file vl53l1_api_core.c.
#define LOG_FUNCTION_END | ( | status, | |
... | |||
) | _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_CORE, status, ##__VA_ARGS__) |
Definition at line 90 of file vl53l1_api_core.c.
#define LOG_FUNCTION_END_FMT | ( | status, | |
fmt, | |||
... | |||
) |
Definition at line 92 of file vl53l1_api_core.c.
#define LOG_FUNCTION_START | ( | fmt, | |
... | |||
) | _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_CORE, fmt, ##__VA_ARGS__) |
Definition at line 88 of file vl53l1_api_core.c.
#define trace_print | ( | level, | |
... | |||
) |
Definition at line 96 of file vl53l1_api_core.c.
#define VL53L1_MAX_I2C_XFER_SIZE 256 |
Definition at line 100 of file vl53l1_api_core.c.
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.
updates GPH registers and clears interrupt and configures SYSTEM__MODE_START register based on the input measurement mode
Internally uses the following functions:
The system_control register group is always written as the last register of this group SYSTEM__MODE_START decides what happens next ...
[in] | Dev | : Device Handle |
[in] | measurement_mode | : Options: VL53L1_DEVICEMEASUREMENTMODE_STOP VL53L1_DEVICEMEASUREMENTMODE_SINGLESHOT VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK VL53L1_DEVICEMEASUREMENTMODE_TIMED |
Definition at line 2397 of file vl53l1_api_core.c.
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.
[in] | gain_factor | : gain correction factor 1.11 format |
[in] | psys | : pointer to VL53L1_system_results_t |
[in] | pcore | : pointer to VL53L1_core_results_t |
[out] | presults | : pointer to VL53L1_range_results_t |
Definition at line 2432 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_data_init | ( | VL53L1_DEV | Dev, |
uint8_t | read_p2p_data | ||
) |
Get LL Driver version information.
[in] | Dev | : Device handle |
[out] | pversion | : pointer to VL53L1_ll_version_t |
Initialises pdev structure and optionally read the part to part information form he device G02 registers
Important: VL53L1_platform_initialise() must called before calling this function
[in] | Dev | : Device handle |
[out] | read_p2p_data | : if > 0 then reads and caches P2P data |
Definition at line 152 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_disable_xtalk_compensation | ( | VL53L1_DEV | Dev | ) |
Simple function to disable xtalk compensation.
Disables xtalk compensation from hist post processing, and clears settings to device
[in] | Dev | : Device Handle |
Currently a very simple function to clear customer xtalk parms and apply to device
Definition at line 1611 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_enable_xtalk_compensation | ( | VL53L1_DEV | Dev | ) |
Simple function to enable xtalk compensation.
Applies xtalk compensation to hist post processing, and applies settings to device,
[in] | Dev | : Device Handle |
Currently a very simple function to copy private xtalk parms into customer section and apply to device
Definition at line 1452 of file vl53l1_api_core.c.
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.
[in] | Dev | : Device handle |
[out] | pcal_config__repeat_period | : current calibration config repeat period |
Convenience function for getting calibration repeat period
Definition at line 792 of file vl53l1_api_core.c.
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_START based on the input measurement mode.
Internally uses the following functions:
The system_control register group is always written as the last register of this group SYSTEM__MODE_START decides what happens next ...
[in] | Dev | : Device Handle |
[in] | device_result_level | : Options: VL53L1_DEVICERESULTSLEVEL_FULL VL53L1_DEVICERESULTSLEVEL_UPTO_CORE VL53L1_DEVICERESULTSLEVEL_SYSTEM_RESULTS |
[out] | prange_results | : pointer to VL53L1_range_results_t |
Definition at line 2298 of file vl53l1_api_core.c.
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.
[in] | Dev | : Device Handle |
[out] | pintconf | : output pointer to structure (note, pointer) |
Definition at line 2687 of file vl53l1_api_core.c.
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.
Uses the pdev->dbg_results.result__osc_calibrate_val value convert into [ms]
[in] | Dev | : Device handle |
[out] | pinter_measurement_period_ms | : current inter measurement period in [ms] |
Convenience function for getting the inter measurement period
Definition at line 629 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_get_interrupt_polarity | ( | VL53L1_DEV | Dev, |
VL53L1_DeviceInterruptPolarity * | pinterrupt_polarity | ||
) |
Get the interrupt polarity bit state.
[in] | Dev | : Device handle |
[out] | pinterrupt_polarity | : Interrupt Polarity Bit value |
Convenience function for getting interrupt polarity
Definition at line 1029 of file vl53l1_api_core.c.
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 signal rate.
Note: the min count rate value is overwritten when setting preset modes, and should only be altered after preset mode has been selected when running Lite Mode.
[in] | Dev | : Device Handle |
[out] | plite_mincountrate | : Output pointer for uint16_t min count rate\ in fixed point 9.7 Mcps |
Definition at line 1712 of file vl53l1_api_core.c.
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 estimated sigma level.
Note: the sigma thresh value is overwritten when setting preset modes, and should only be altered after preset mode has been selected when running Lite Mode.
[in] | Dev | : Device Handle |
[out] | plite_sigma | : Output pointer for uint16_t sigma thresh\ in fixed point 14.2 mm |
Definition at line 1661 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_get_lite_xtalk_margin_kcps | ( | VL53L1_DEV | Dev, |
int16_t * | pxtalk_margin | ||
) |
Get function for Xtalk Margin setting Histogram Mode version.
[in] | Dev | : Device Handle |
[out] | pxtalk_margin | : output pointer for int16_t xtalk_margin factor \ in fixed point 7.9 Kcps. |
Definition at line 1539 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_get_measurement_results | ( | VL53L1_DEV | Dev, |
VL53L1_DeviceResultsLevel | device_result_level | ||
) |
Get range measurement result data.
Reads the required number of registers as single multi byte read transaction and decodes the data into the data structures
range_result_level controls which result data is read back from the device
[in] | Dev | : Device Handle |
[in] | device_result_level | : Options: VL53L1_DEVICERESULTSLEVEL_FULL VL53L1_DEVICERESULTSLEVEL_UPTO_CORE VL53L1_DEVICERESULTSLEVEL_SYSTEM_RESULTS |
Definition at line 2199 of file vl53l1_api_core.c.
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.
[in] | Dev | : Device handle |
[out] | pmm_roi | : pointer to user zone (ROI) data structure |
Convenience function for getting the mode mitigation ROI
Definition at line 1115 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_get_offset_calibration_mode | ( | VL53L1_DEV | Dev, |
VL53L1_OffsetCalibrationMode * | poffset_cal_mode | ||
) |
Get function for offset calibration mode.
[in] | Dev | : Device Handle |
[out] | poffset_cal_mode | : output pointer for calibration mode |
Definition at line 2753 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_get_offset_correction_mode | ( | VL53L1_DEV | Dev, |
VL53L1_OffsetCorrectionMode * | poffset_cor_mode | ||
) |
Get function for offset correction mode.
[in] | Dev | : Device Handle |
[out] | poffset_cor_mode | : output pointer for correction mode |
Definition at line 2799 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_get_part_to_part_data | ( | VL53L1_DEV | Dev, |
VL53L1_calibration_data_t * | pcal_data | ||
) |
Gets the customer part to part data.
Just an internal memory copy
[in] | Dev | : Device handle |
[out] | pcal_data | : pointer to VL53L1_calibration_data_t |
Uses memcpy to copy pdev->customer to output data
Definition at line 533 of file vl53l1_api_core.c.
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.
Function Added as part of Patch_TuningParmPresetModeAddition_11839
[in] | Dev | : Device Handle |
[in] | device_preset_mode | : selected device preset mode |
[out] | pdss_config__target_total_rate_mcps | : dss rate output value |
[out] | pphasecal_config_timeout_us | : phasecal timeout output value |
[out] | pmm_config_timeout_us | : mm timeout output value |
[out] | prange_config_timeout_us | : range timeout output value |
Definition at line 1159 of file vl53l1_api_core.c.
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.
[in] | Dev | : Device handle |
[out] | prange_ignore_thresh_mult | : \ Range ignore threshold internal multiplier value in \ 3.5 fractional format. |
[out] | prange_ignore_threshold_mcps_internal | : \ Range Ignore Threshold Rate value generated from \ current xtalk parms |
[out] | prange_ignore_threshold_mcps_current | : \ Range Ignore Threshold Rate value generated from \ device static config struct |
Convenience function for retrieving Range Ignore Threshold
Values both in fixed point 3.13 Mcps per spad
Definition at line 995 of file vl53l1_api_core.c.
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.
[in] | Dev | : Device handle |
[in] | pdata | : Input pointer to VL53L1_refspadchar_config_t |
Definition at line 942 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_get_sequence_config_bit | ( | VL53L1_DEV | Dev, |
VL53L1_DeviceSequenceConfig | bit_id, | ||
uint8_t * | pvalue | ||
) |
Get system sequence config bit value.
[in] | Dev | : Device handle |
[in] | bit_id | : VL53L1_DeviceSequenceConfig bit id |
[out] | pvalue | : Output Bit value = 0 or 1 |
Convenience function for getting sequence config enable bits
Definition at line 850 of file vl53l1_api_core.c.
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.
Uses the pdev->stat_nvm.osc_measured__fast_osc__frequency convert into [us]
[in] | Dev | : Device handle |
[out] | pphasecal_config_timeout_us | : current Phase Cal Timeout in [us] |
[out] | pmm_config_timeout_us | : current MM Timeout in [us] |
[out] | prange_config_timeout_us | : current Ranging Timeout in [us] |
Convenience function for getting the MM and range timeouts
Definition at line 699 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_get_tuning_parm | ( | VL53L1_DEV | Dev, |
VL53L1_TuningParms | tuning_parm_key, | ||
int32_t * | ptuning_parm_value | ||
) |
Generic Tuning Parameter extraction function.
User passes a key input to retrieve a specific tuning parameter value, this will be cast to the int32_t type and output via the ptuning_parm_value pointer
If the key does not match any tuning parameter, status is returned with VL53L1_ERROR_INVALID_PARAMS
Patch_AddedTuningParms_11761
[in] | Dev | : Device Handle |
[in] | tuning_parm_key | : Key value to access specific tuning parm |
[out] | ptuning_parm_value | : Pointer to output int32_t type, retrieves \ requested tuning parm |
Definition at line 3004 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_get_user_zone | ( | VL53L1_DEV | Dev, |
VL53L1_user_zone_t * | puser_zone | ||
) |
Gets the current user zone (ROI) configuration structure data.
[in] | Dev | : Device handle |
[out] | puser_zone | : pointer to user zone (ROI) data structure |
Convenience function for getting the user ROI
Definition at line 1083 of file vl53l1_api_core.c.
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.
init_en - enables use of the init value instead of latest setting init_value - custom vhv setting or populated from nvm
[in] | Dev | : Device Handle |
[out] | pvhv_init_en | : Output pointer to uint8_t value |
[out] | pvhv_init_value | : Output pointer to uint8_t value |
< info:
fields:
Definition at line 1822 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_get_vhv_loopbound | ( | VL53L1_DEV | Dev, |
uint8_t * | pvhv_loopbound | ||
) |
Get function for VHV loopbound config.
Loopbound sets the number of +/- vhv settings to try around the vhv init value during vhv search i.e. if init_value = 10 and loopbound = 2 vhv search will run from 10-2 to 10+2 8 to 12.
[in] | Dev | : Device Handle |
[out] | pvhv_loopbound | : pointer to byte to extract loopbound |
Definition at line 1764 of file vl53l1_api_core.c.
void VL53L1_get_xtalk_compensation_enable | ( | VL53L1_DEV | Dev, |
uint8_t * | pcrosstalk_compensation_enable | ||
) |
Simple function to retrieve xtalk compensation status.
[in] | Dev | : Device Handle |
[out] | pcrosstalk_compensation_enable | : pointer to \ uint8 type, returns crosstalk compensation status \ where 0 means disabled and 1 means enabled. |
Currently a very simple function to return
#1 - Enabled #0 - Disabled
Definition at line 1512 of file vl53l1_api_core.c.
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.
The device_config_level input controls the level of initialization applied to the device
The system_control register group is always written as the last register of this group SYSTEM__MODE_START decides what happens next ...
[in] | Dev | : Device handle |
[in] | measurement_mode | : Options: VL53L1_DEVICEMEASUREMENTMODE_STOP VL53L1_DEVICEMEASUREMENTMODE_SINGLESHOT VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK VL53L1_DEVICEMEASUREMENTMODE_TIMED |
[in] | device_config_level | : Options: VL53L1_DEVICECONFIGLEVEL_SYSTEM_CONTROL VL53L1_DEVICECONFIGLEVEL_DYNAMIC_ONWARDS VL53L1_DEVICECONFIGLEVEL_TIMING_ONWARDS VL53L1_DEVICECONFIGLEVEL_STATIC_ONWARDS VL53L1_DEVICECONFIGLEVEL_CUSTOMER_ONWARDS VL53L1_DEVICECONFIGLEVEL_FULL |
The system_control register group is always written as the last register of this group SYSTEM__MODE_START decides what happens next ..
Definition at line 1889 of file vl53l1_api_core.c.
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.
Contains the key NVM data e.g identification info fast oscillator freq, max trim and laser safety info
Function all only be called after the device has finished booting
[in] | Dev | : Device handle |
Definition at line 313 of file vl53l1_api_core.c.
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.
This function does not recalculate all xtalk parms derived from the rates in question. In order to ensure correct ranging, a call to VL53L1_enable_xtalk_compensation should always be called prior to starting the ranging process.
[in] | Dev | : Device Handle |
Definition at line 1585 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_set_calibration_repeat_period | ( | VL53L1_DEV | Dev, |
uint16_t | cal_config__repeat_period | ||
) |
Sets the 12-bit calibration repeat period value.
Sets the repeat period for VHV and phasecal in ranges. Setting to zero to disables the repeat, but the VHV and PhaseCal is still run on the very first range in this case.
Only even values should be set
The max value is 4094 i.e. every
[in] | Dev | : Device handle |
[in] | cal_config__repeat_period | : current calibration config repeat period |
Convenience function for setting calibration repeat period
Definition at line 773 of file vl53l1_api_core.c.
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.
[in] | Dev | : Device Handle |
[in] | intr_mode_distance | : distance interrupt mode |
[in] | intr_mode_rate | : rate interrupt mode |
[in] | intr_new_measure_ready | : trigger when new interrupt ready |
[in] | intr_no_target | : trigger when no target found |
[in] | intr_combined_mode | : switch on combined mode |
[in] | thresh_distance_high | : High distance threshold in mm |
[in] | thresh_distance_low | : Low distance threshold in mm |
[in] | thresh_rate_high | : High rate threshold in 9.7 Mcps |
[in] | thresh_rate_low | : Low rate threshold in 9.7 Mcps |
Definition at line 2607 of file vl53l1_api_core.c.
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.
[in] | Dev | : Device Handle |
[in] | intconf | : input structure (note, not a pointer) |
Definition at line 2656 of file vl53l1_api_core.c.
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.
Just an internal copy
[in] | Dev | : Device handle |
[out] | ptun_data | : pointer to VL53L1_tuning_parameters_t |
Sets the inter measurement period in the VL53L1_timing_config_t structure
Uses the pdev->dbg_results.result__osc_calibrate_val value convert from [ms]
[in] | Dev | : Device handle |
[in] | inter_measurement_period_ms | : requested inter measurement period in [ms] |
Convenience function for setting the inter measurement period
Definition at line 600 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_set_interrupt_polarity | ( | VL53L1_DEV | Dev, |
VL53L1_DeviceInterruptPolarity | interrupt_polarity | ||
) |
Set the interrupt polarity bit in.
[in] | Dev | : Device handle |
[in] | interrupt_polarity | : Interrupt Polarity |
Convenience function for setting interrupt polarity
Definition at line 887 of file vl53l1_api_core.c.
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 signal rate.
Note: the min count rate value is overwritten when setting preset modes, and should only be altered after preset mode has been selected when running Lite Mode.
[in] | Dev | : Device Handle |
[in] | lite_mincountrate | : Input uint16_t min count rate in fixed point 9.7 Mcps |
Definition at line 1738 of file vl53l1_api_core.c.
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 estimated sigma level.
Note: the sigma thresh value is overwritten when setting preset modes, and should only be altered after preset mode has been selected when running Lite Mode.
[in] | Dev | : Device Handle |
[in] | lite_sigma | : Input uint16_t sigma thresh\ in fixed point 14.2 mm |
Definition at line 1687 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_set_lite_xtalk_margin_kcps | ( | VL53L1_DEV | Dev, |
int16_t | xtalk_margin | ||
) |
Set function for Xtalk Margin setting Histogram Mode version.
[in] | Dev | : Device Handle |
[in] | xtalk_margin | : Input int16_t xtalk_margin factor \ in fixed point 7.9 Kcps. |
Definition at line 1562 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_set_offset_calibration_mode | ( | VL53L1_DEV | Dev, |
VL53L1_OffsetCalibrationMode | offset_cal_mode | ||
) |
Set function for offset calibration mode.
[in] | Dev | : Device Handle |
[in] | offset_cal_mode | : input calibration mode |
Definition at line 2730 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_set_offset_correction_mode | ( | VL53L1_DEV | Dev, |
VL53L1_OffsetCalibrationMode | offset_cor_mode | ||
) |
Set function for offset correction mode.
[in] | Dev | : Device Handle |
[in] | offset_cor_mode | : input correction mode |
Definition at line 2776 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_set_part_to_part_data | ( | VL53L1_DEV | Dev, |
VL53L1_calibration_data_t * | pcal_data | ||
) |
Sets the customer part to part data.
Important: does not apply the settings to the device. Updates the following structures in the device structure
Just an internal memcpy to
[in] | Dev | : Device handle |
[in] | pcal_data | : pointer to VL53L1_calibration_data_t |
Uses memcpy to copy input data to pdev->customer
Definition at line 449 of file vl53l1_api_core.c.
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.
Important: does not apply the settings to the device. Updates the following structures in the device structure
Uses osc_measured__fast_osc__frequency in pdev->stat_nvm to convert the input timeouts in [us] to internal macro period timeout values.
Please call VL53L1_init_and_start_range() to update device and start a range
[in] | Dev | : Device handle |
[in] | device_preset_mode | : selected device preset mode |
[in] | dss_config__target_total_rate_mcps | : DSS target rate in 9.7 format e.g 0x0A00 -> 20.0 Mcps |
[in] | phasecal_config_timeout_us | : requested Phase Cal Timeout e.g. 1000us |
[in] | mm_config_timeout_us | : requested MM Timeout e.g. 2000us |
[in] | range_config_timeout_us | : requested Ranging Timeout e.g 10000us |
[in] | inter_measurement_period_ms | : requested timed mode repeat rate e.g 100ms |
Initializes static and dynamic data structures for the provided preset mode
Definition at line 1230 of file vl53l1_api_core.c.
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.
[in] | Dev | : Device handle |
[in] | range_ignore_thresh_mult | : Input RIT Mult value, in \ 3.5 fractional value |
[in] | range_ignore_threshold_mcps | : Range Ignore Threshold value |
Convenience function for setting Range Ignore Threshold
Definition at line 972 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_set_refspadchar_config_struct | ( | VL53L1_DEV | Dev, |
VL53L1_refspadchar_config_t * | pdata | ||
) |
Extract the Ref spad char cfg struct from pdev.
[in] | Dev | : Device handle |
[out] | pdata | : Output pointer to VL53L1_refspadchar_config_t |
Definition at line 911 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_set_sequence_config_bit | ( | VL53L1_DEV | Dev, |
VL53L1_DeviceSequenceConfig | bit_id, | ||
uint8_t | value | ||
) |
Set system sequence config bit value.
[in] | Dev | : Device handle |
[in] | bit_id | : VL53L1_DeviceSequenceConfig bit id |
[in] | value | : Input Bit value = 0 or 1 |
Convenience function for setting sequence config enable bits
Definition at line 811 of file vl53l1_api_core.c.
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.
Uses the pdev->stat_nvm.osc_measured__fast_osc__frequency value convert from [us]
[in] | Dev | : Device handle |
[in] | phasecal_config_timeout_us | : requested Phase Cal Timeout e.g. 1000us |
[in] | mm_config_timeout_us | : requested MM Timeout e.g. 2000us |
[in] | range_config_timeout_us | : requested Ranging Timeout e.g 13000us |
Convenience function for setting the MM and range timeouts
Definition at line 657 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_set_tuning_parm | ( | VL53L1_DEV | Dev, |
VL53L1_TuningParms | tuning_parm_key, | ||
int32_t | tuning_parm_value | ||
) |
Generic Tuning Parameter set function.
User passes a key input to set a specific tuning parameter value, this will be cast to the internal data type from the input int32_t data type.
If the key does not match any tuning parameter, status is returned with VL53L1_ERROR_INVALID_PARAMS
Patch_AddedTuningParms_11761
[in] | Dev | : Device Handle |
[in] | tuning_parm_key | : Key value to access specific tuning parm |
[in] | tuning_parm_value | : Input tuning parm value of int32_t type, \ sets requested tuning parm. |
Definition at line 3266 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_set_user_zone | ( | VL53L1_DEV | Dev, |
VL53L1_user_zone_t * | puser_zone | ||
) |
Sets the current user Zone (ROI) configuration structure data.
[in] | Dev | : Device handle |
[in] | puser_zone | : pointer to user Zone (ROI) data structure |
Convenience function for setting the user ROI
Definition at line 1050 of file vl53l1_api_core.c.
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.
init_en - enables use of the init value instead of latest setting init_value - custom vhv setting or populated from nvm
[in] | Dev | : Device Handle |
[in] | vhv_init_en | : input init_en setting |
[in] | vhv_init_value | : input vhv custom value |
Definition at line 1861 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_set_vhv_loopbound | ( | VL53L1_DEV | Dev, |
uint8_t | vhv_loopbound | ||
) |
Set function for VHV loopbound config.
Loopbound sets the number of +/- vhv settings to try around the vhv init value during vhv search i.e. if init_value = 10 and loopbound = 2 vhv search will run from 10-2 to 10+2 8 to 12.
[in] | Dev | : Device Handle |
[in] | vhv_loopbound | : input loopbound value |
Definition at line 1790 of file vl53l1_api_core.c.
VL53L1_Error VL53L1_software_reset | ( | VL53L1_DEV | Dev | ) |
Performs device software reset and then waits for the firmware to finish booting.
[in] | Dev | : Device handle |
Sets and clears the software reset register VL53L1_SOFT_RESET. and waits for the firmware to boot
Definition at line 406 of file vl53l1_api_core.c.
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.
[in] | Dev | : Device handle |
Definition at line 2159 of file vl53l1_api_core.c.