83 #ifdef VL53L1_LOG_ENABLE 87 #include "vl53l1_debug.h" 90 #define LOG_FUNCTION_START(fmt, ...) \ 91 _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_CORE, fmt, ##__VA_ARGS__) 92 #define LOG_FUNCTION_END(status, ...) \ 93 _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_CORE, status, ##__VA_ARGS__) 94 #define LOG_FUNCTION_END_FMT(status, fmt, ...) \ 95 _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_CORE, status, \ 98 #define trace_print(level, ...) \ 99 _LOG_TRACE_PRINT(VL53L1_TRACE_MODULE_CORE, \ 100 level, VL53L1_TRACE_FUNCTION_NONE, ##__VA_ARGS__) 103 #ifndef VL53L1_NOCALIB 234 #ifdef VL53L1_LOG_ENABLE 237 VL53L1_print_customer_nvm_managed(
239 "run_ref_spad_char():pdev->lldata.customer.",
240 VL53L1_TRACE_MODULE_REF_SPAD_CHAR);
265 *pcal_status = status;
345 device_preset_modes[0] =
347 device_preset_modes[1] =
349 device_preset_modes[2] =
411 device_preset_modes[m],
421 manual_effective_spads;
432 for (i = 0 ; i <= (num_of_samples[m]+2) ; i++) {
460 prange_data = &(prange_results->
data[0]);
541 manual_effective_spads =
660 #ifdef VL53L1_LOG_ENABLE 664 VL53L1_print_customer_nvm_managed(
666 "run_offset_calibration():pdev->lldata.customer.",
667 VL53L1_TRACE_MODULE_OFFSET_DATA);
669 VL53L1_print_additional_offset_cal_data(
671 "run_offset_calibration():pdev->lldata.add_off_cal_data.",
672 VL53L1_TRACE_MODULE_OFFSET_DATA);
674 VL53L1_print_offset_range_results(
676 "run_offset_calibration():pdev->lldata.offset_results.",
677 VL53L1_TRACE_MODULE_OFFSET_DATA);
686 #ifndef VL53L1_NOCALIB 756 #ifdef VL53L1_LOG_ENABLE 760 VL53L1_print_spad_rate_data(
762 "run_spad_rate_map():",
763 VL53L1_TRACE_MODULE_SPAD_RATE_MAP);
764 VL53L1_print_spad_rate_map(
766 "run_spad_rate_map():",
767 VL53L1_TRACE_MODULE_SPAD_RATE_MAP);
778 #ifndef VL53L1_NOCALIB 846 VL53L1_TRACE_LEVEL_INFO,
847 " Device Test Complete:\n\t%-32s = %3u\n\t%-32s = %3u\n",
848 "result__range_status",
850 "result__report_status",
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_DeviceSscArray array_select
uint8_t global_config__spad_enables_ref_5
uint8_t global_config__spad_enables_ref_4
VL53L1 LL Driver ST private data structure .
uint16_t max_count_rate_limit_mcps
VL53L1_static_nvm_managed_t stat_nvm
Reference SPAD Characterization (RefSpadChar) Config.
#define VL53L1_DEVICEERROR_REFSPADCHARLESSTHANTARGET
uint8_t ref_spad_char_result__ref_location
VL53L1_Error VL53L1_run_device_test(VL53L1_DEV Dev, VL53L1_DeviceTestMode device_test_mode)
Runs the input Device Test.
#define IGNORE_OFFSET_CAL_SIGMA_TOO_HIGH
#define IGNORE_OFFSET_CAL_SPAD_COUNT_TOO_LOW
uint8_t global_config__spad_enables_ref_2
uint16_t min_count_rate_limit_mcps
Device register setting defines.
int16_t algo__part_to_part_range_offset_mm
#define IGNORE_REF_SPAD_CHAR_RATE_TOO_LOW
VL53L1_OffsetCalibrationMode offset_calibration_mode
int16_t mm_config__outer_offset_mm
uint8_t global_config__spad_enables_ref_3
VL53L1_additional_offset_cal_data_t add_off_cal_data
int16_t mm_config__inner_offset_mm
uint16_t result__mm_outer_actual_effective_spads
uint16_t dss_config__target_total_rate_mcps
VL53L1_refspadchar_config_t refspadchar
uint8_t ref_spad_man__num_requested_ref_spads
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...
short int16_t
Typedef defining 16 bit short type. The developer should modify this to suit the platform being deplo...
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.
#define VL53L1_RANGE_STATUS__RANGE_STATUS_MASK
SPAD Rate Data output by SSC.
#define VL53L1_DEVICEERROR_RANGECOMPLETE
VL53L1_Error VL53L1_clear_interrupt(VL53L1_DEV Dev)
Clears Ranging Interrupt.
uint8_t VL53L1_DeviceTestMode
#define VL53L1_GPIO_HV_MUX__CTRL
#define VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_HIGH
VL53L1_offset_range_results_t offset_results
VL53L1_Error VL53L1_wait_for_test_completion(VL53L1_DEV Dev)
Waits for a device test mode to complete.
VL53L1_general_config_t gen_cfg
#define VL53L1_RESULT__SPARE_0_SD1
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_DEVICETESTMODE_LCR_VCSEL_ON
VL53L1_range_data_t data[2]
#define IGNORE_REF_SPAD_CHAR_NOT_ENOUGH_SPADS
VL53L1_Error VL53L1_wait_for_firmware_ready(VL53L1_DEV Dev)
Waits for initial firmware ready.
uint8_t result__range_status
#define VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM1_CAL
#define IGNORE_STATUS(__FUNCTION_ID__, __ERROR_STATUS_CHECK__, __STATUS__)
VL53L1_Error VL53L1_wait_for_range_completion(VL53L1_DEV Dev)
Waits for the next ranging interrupt.
VL53L1_system_results_t sys_results
uint16_t peak_signal_count_rate_mcps
VL53L1_Error VL53L1_run_spad_rate_map(VL53L1_DEV Dev, VL53L1_DeviceTestMode device_test_mode, VL53L1_DeviceSscArray array_select, uint32_t ssc_config_timeout_us, VL53L1_spad_rate_data_t *pspad_rate_data)
Runs SPAD rate map.
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...
#define VL53L1_WARNING_OFFSET_CAL_MISSING_SAMPLES
#define VL53L1_WARNING_OFFSET_CAL_RATE_TOO_HIGH
VL53L1 Register Map definitions.
VL53L1_Error VL53L1_start_test(VL53L1_DEV Dev, uint8_t test_mode__ctrl)
Triggers the start of the provided test_mode.
LL Driver Device specific defines. To be adapted by implementer for the targeted device.
#define VL53L1_ERROR_NONE
EwokPlus25 low level API function definitions.
EwokPlus25 API core function definition.
#define VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_LOW
VL53L1_offset_range_data_t data[VL53L1_MAX_OFFSET_RANGE_RESULTS]
uint8_t ref_spad_man__ref_location
Type definitions for VL53L1 LL Driver.
uint16_t dss_config__manual_effective_spads_select
VL53L1_Error VL53L1_run_ref_spad_char(VL53L1_DEV Dev, VL53L1_Error *pcal_status)
Run Reference Array SPAD Characterisation.
uint8_t mm1_num_of_samples
#define VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK
#define VL53L1_RESULT__RANGE_STATUS
int int32_t
Typedef defining 32 bit int type. The developer should modify this to suit the platform being deploye...
uint16_t dss_config__manual_effective_spads_select
#define VL53L1_ERROR_OFFSET_CAL_NO_SPADS_ENABLED_FAIL
uint8_t gpio_hv_mux__ctrl
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 result__report_status
VL53L1_ssc_config_t ssc_cfg
VL53L1_Error VL53L1_disable_powerforce(VL53L1_DEV Dev)
Disables power force.
VL53L1_Error VL53L1_set_customer_nvm_managed(VL53L1_DEV Dev, VL53L1_customer_nvm_managed_t *pdata)
Sets customer_nvm_managed register group.
#define VL53L1_WARNING_OFFSET_CAL_SPAD_COUNT_TOO_LOW
EwokPlus25 low level silicon specific API function definitions.
EwokPlus25 low level Driver wait function definitions.
VL53L1_static_config_t stat_cfg
VL53L1_Error VL53L1_enable_powerforce(VL53L1_DEV Dev)
Enables power force.
VL53L1 Register Function declarations.
uint32_t range_config_timeout_us
#define VL53L1_WARNING_REF_SPAD_CHAR_NOT_ENOUGH_SPADS
VL53L1_debug_results_t dbg_results
EwokPlus25 core function definitions.
#define VL53L1_DEVICEERROR_REFSPADCHARMORETHANTARGET
#define VL53L1_OFFSETCALIBRATIONMODE__MM1_MM2__STANDARD_PRE_RANGE_ONLY
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...
uint16_t result__mm_inner_peak_signal_count_rtn_mcps
#define VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM2_CAL
uint8_t dss_config__roi_mode_control
uint8_t ref_spad_char_result__num_actual_ref_spads
#define VL53L1_ERROR_OFFSET_CAL_NO_SAMPLE_FAIL
VL53L1_offsetcal_config_t offsetcal_cfg
#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_REF_0
#define VL53L1_DEVICECONFIGLEVEL_CUSTOMER_ONWARDS
#define VL53L1_MAX_OFFSET_RANGE_RESULTS
Structure for storing the set of range results required for the mm1 and mm2 offset calibration functi...
uint32_t phasecal_config_timeout_us
uint16_t result__mm_outer_peak_signal_count_rtn_mcps
#define IGNORE_OFFSET_CAL_MISSING_SAMPLES
uint32_t mm_config_timeout_us
#define VL53L1_REF_SPAD_CHAR_RESULT__NUM_ACTUAL_REF_SPADS
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.
uint16_t actual_effective_spads
#define VL53L1_DEVICEERROR_REFSPADCHARNOTENOUGHDPADS
#define IGNORE_REF_SPAD_CHAR_RATE_TOO_HIGH
uint8_t VL53L1_DevicePresetModes
uint8_t VL53L1_DeviceSscArray
VL53L1_customer_nvm_managed_t customer
uint16_t osc_measured__fast_osc__frequency
#define VL53L1_REF_SPAD_MAN__NUM_REQUESTED_REF_SPADS
uint8_t global_config__spad_enables_ref_0
uint8_t global_config__spad_enables_ref_1
uint16_t result__mm_inner_actual_effective_spads
#define VL53L1_WARNING_OFFSET_CAL_SIGMA_TOO_HIGH
uint8_t dss_config__roi_mode_control
#define LOG_FUNCTION_END(status,...)
Structure for storing the set of range results.
#define LOG_FUNCTION_START(fmt,...)
uint16_t target_count_rate_mcps
VL53L1_Error VL53L1_run_offset_calibration(VL53L1_DEV Dev, int16_t cal_distance_mm, VL53L1_Error *pcal_status)
Run offset calibration.
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
uint8_t pre_num_of_samples
#define trace_print(level,...)
EwokPlus25 low level API function definitions.
#define VL53L1_DEVICEPRESETMODE_STANDARD_RANGING
uint8_t mm2_num_of_samples
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.
unsigned int uint32_t
Typedef defining 32 bit unsigned int type. The developer should modify this to suit the platform bein...
#define IGNORE_OFFSET_CAL_RATE_TOO_HIGH