vl53l1_api_calibration.c
Go to the documentation of this file.
1 /*
2 * Copyright (c) 2017, STMicroelectronics - All Rights Reserved
3 *
4 * This file is part of VL53L1 Core and is dual licensed,
5 * either 'STMicroelectronics
6 * Proprietary license'
7 * or 'BSD 3-clause "New" or "Revised" License' , at your option.
8 *
9 ********************************************************************************
10 *
11 * 'STMicroelectronics Proprietary license'
12 *
13 ********************************************************************************
14 *
15 * License terms: STMicroelectronics Proprietary in accordance with licensing
16 * terms at www.st.com/sla0081
17 *
18 * STMicroelectronics confidential
19 * Reproduction and Communication of this document is strictly prohibited unless
20 * specifically authorized in writing by STMicroelectronics.
21 *
22 *
23 ********************************************************************************
24 *
25 * Alternatively, VL53L1 Core may be distributed under the terms of
26 * 'BSD 3-clause "New" or "Revised" License', in which case the following
27 * provisions apply instead of the ones mentioned above :
28 *
29 ********************************************************************************
30 *
31 * License terms: BSD 3-clause "New" or "Revised" License.
32 *
33 * Redistribution and use in source and binary forms, with or without
34 * modification, are permitted provided that the following conditions are met:
35 *
36 * 1. Redistributions of source code must retain the above copyright notice, this
37 * list of conditions and the following disclaimer.
38 *
39 * 2. Redistributions in binary form must reproduce the above copyright notice,
40 * this list of conditions and the following disclaimer in the documentation
41 * and/or other materials provided with the distribution.
42 *
43 * 3. Neither the name of the copyright holder nor the names of its contributors
44 * may be used to endorse or promote products derived from this software
45 * without specific prior written permission.
46 *
47 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
48 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
49 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
50 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
51 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
52 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
53 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
54 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
55 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
56 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
57 *
58 *
59 ********************************************************************************
60 *
61 */
62 
70 #include "vl53l1_ll_def.h"
71 #include "vl53l1_ll_device.h"
72 #include "vl53l1_platform.h"
73 #include "vl53l1_register_map.h"
74 #include "vl53l1_register_funcs.h"
76 #include "vl53l1_core.h"
77 #include "vl53l1_wait.h"
79 #include "vl53l1_silicon_core.h"
80 #include "vl53l1_api_core.h"
81 #include "vl53l1_api_calibration.h"
82 
83 #ifdef VL53L1_LOG_ENABLE
84  #include "vl53l1_api_debug.h"
85 #endif
86 #ifdef VL53L1_LOGGING
87  #include "vl53l1_debug.h"
88 #endif
89 
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, \
96  fmt, ##__VA_ARGS__)
97 
98 #define trace_print(level, ...) \
99  _LOG_TRACE_PRINT(VL53L1_TRACE_MODULE_CORE, \
100  level, VL53L1_TRACE_FUNCTION_NONE, ##__VA_ARGS__)
101 
102 
103 #ifndef VL53L1_NOCALIB
105  VL53L1_DEV Dev,
106  VL53L1_Error *pcal_status)
107 {
108  /*
109  * Runs Reference SPAD Characterisation
110  */
111 
114 
115  uint8_t comms_buffer[6];
116 
117  VL53L1_refspadchar_config_t *prefspadchar = &(pdev->refspadchar);
118 
119  LOG_FUNCTION_START("");
120 
121  /*
122  * Ensure power force is enabled
123  */
124 
125  if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
126  status = VL53L1_enable_powerforce(Dev);
127 
128  /*
129  * Configure device
130  */
131 
132  if (status == VL53L1_ERROR_NONE)
133  status =
135  Dev,
136  prefspadchar->vcsel_period,
137  prefspadchar->timeout_us,
138  prefspadchar->target_count_rate_mcps,
139  prefspadchar->max_count_rate_limit_mcps,
140  prefspadchar->min_count_rate_limit_mcps,
142 
143  /*
144  * Run device test
145  */
146 
147  if (status == VL53L1_ERROR_NONE)
148  status = VL53L1_run_device_test(
149  Dev,
150  prefspadchar->device_test_mode);
151 
152  /*
153  * Read results
154  */
155 
156  if (status == VL53L1_ERROR_NONE)
157  status =
159  Dev,
161  comms_buffer,
162  2);
163 
164  if (status == VL53L1_ERROR_NONE) {
166  comms_buffer[0];
168  comms_buffer[1];
169  }
170 
171  /*
172  * copy results to customer nvm managed G02 registers
173  */
174 
175  if (status == VL53L1_ERROR_NONE)
176  status =
178  Dev,
180  comms_buffer,
181  2);
182 
183  if (status == VL53L1_ERROR_NONE) {
185  comms_buffer[0];
187  comms_buffer[1];
188  }
189 
190  /* After Ref Spad Char the final set of good SPAD enables
191  * are stored in the NCY results registers below
192  *
193  * - RESULT__SPARE_0_SD_1
194  * - RESULT__SPARE_1_SD_1
195  * - RESULT__SPARE_2_SD_1
196  */
197 
198  if (status == VL53L1_ERROR_NONE)
199  status =
201  Dev,
203  comms_buffer,
204  6);
205 
206  /*
207  * copy reference SPAD enables to customer nvm managed
208  * G02 registers
209  */
210 
211  if (status == VL53L1_ERROR_NONE)
212  status =
214  Dev,
216  comms_buffer,
217  6);
218 
219  if (status == VL53L1_ERROR_NONE) {
221  comms_buffer[0];
223  comms_buffer[1];
225  comms_buffer[2];
227  comms_buffer[3];
229  comms_buffer[4];
231  comms_buffer[5];
232  }
233 
234 #ifdef VL53L1_LOG_ENABLE
235  /* Print customer nvm managed data */
236  if (status == VL53L1_ERROR_NONE)
237  VL53L1_print_customer_nvm_managed(
238  &(pdev->customer),
239  "run_ref_spad_char():pdev->lldata.customer.",
240  VL53L1_TRACE_MODULE_REF_SPAD_CHAR);
241 #endif
242 
243  if (status == VL53L1_ERROR_NONE) {
244 
245  switch (pdev->sys_results.result__range_status) {
246 
249  break;
250 
253  break;
254 
257  break;
258  }
259  }
260 
261  /*
262  * Save unfiltered status
263  */
264 
265  *pcal_status = status;
266 
267  /* Status exception code */
268 
272  status);
273 
277  status);
278 
282  status);
283 
284 
285  LOG_FUNCTION_END(status);
286 
287  return status;
288 }
289 
291  VL53L1_DEV Dev,
292  int16_t cal_distance_mm,
293  VL53L1_Error *pcal_status)
294 {
295  /*
296  * Runs offset calibration
297  *
298  * Recommended tuning parm settings:
299  *
300  * - pre_num_of_samples = 32
301  * - mm1_num_of_samples = 100
302  * - mm2_num_of_samples = 64
303  * - target_distance_mm = 140mm
304  * - target reflectance = 5%
305  *
306  * Standard Ranging (sigma delta mode):
307  * - dss_config__target_total_rate_mcps = 20.0 -40.0 Mcps
308  * - phasecal_config_timeout_us = 1000
309  * - range_config_timeout_us = 13000
310  * - mm_config_timeout_us = 13000
311  *
312  *
313  * Note: function parms simplified as part of
314  * Patch_CalFunctionSimplification_11791
315  *
316  */
317 
319  VL53L1_LLDriverData_t *pdev =
321 
323 
324  VL53L1_range_results_t range_results;
325  VL53L1_range_results_t *prange_results = &range_results;
326  VL53L1_range_data_t *prange_data = NULL;
327  VL53L1_offset_range_data_t *poffset = NULL;
328 
329  uint8_t i = 0;
330  uint8_t m = 0;
331  uint8_t measurement_mode =
333  uint16_t manual_effective_spads =
335 
337 
338  LOG_FUNCTION_START("");
339 
340  /* select requested offset calibration mode */
341 
342  switch (pdev->offset_calibration_mode) {
343 
344  default:
345  device_preset_modes[0] =
347  device_preset_modes[1] =
349  device_preset_modes[2] =
351  break;
352  }
353 
354  /* initialise num_of_samples */
355  /* Start Patch_CalFunctionSimplification_11791 */
356  num_of_samples[0] = pdev->offsetcal_cfg.pre_num_of_samples;
357  num_of_samples[1] = pdev->offsetcal_cfg.mm1_num_of_samples;
358  num_of_samples[2] = pdev->offsetcal_cfg.mm2_num_of_samples;
359  /* End Patch_CalFunctionSimplification_11791 */
360 
361  /* force all offsets to zero */
362 
363  switch (pdev->offset_calibration_mode) {
364 
366  /* only run pre range */
367  pdev->offset_results.active_results = 1;
368 
369  break;
370 
371  default:
372 
377 
378  break;
379  }
380 
382 
383  /* initialise offset range results */
384 
386  pdev->offset_results.cal_distance_mm = cal_distance_mm;
387 
388  for (m = 0 ; m < VL53L1_MAX_OFFSET_RANGE_RESULTS; m++) {
389 
390  poffset = &(pdev->offset_results.data[m]);
391  poffset->preset_mode = 0;
392  poffset->no_of_samples = 0;
393  poffset->effective_spads = 0;
394  poffset->peak_rate_mcps = 0;
395  poffset->sigma_mm = 0;
396  poffset->median_range_mm = 0;
397  }
398 
399  for (m = 0 ; m < pdev->offset_results.active_results ; m++) {
400 
401  poffset = &(pdev->offset_results.data[m]);
402 
403  poffset->preset_mode = device_preset_modes[m];
404 
405  /* Apply preset mode */
406 
407  if (status == VL53L1_ERROR_NONE)
408  status =
410  Dev,
411  device_preset_modes[m],
412  /* Start Patch_CalFunctionSimplification_11791 */
417  /* End Patch_CalFunctionSimplification_11791 */
418  100);
419 
421  manual_effective_spads;
422 
423  /* Initialise device and start range */
424 
425  if (status == VL53L1_ERROR_NONE)
426  status =
428  Dev,
429  measurement_mode,
431 
432  for (i = 0 ; i <= (num_of_samples[m]+2) ; i++) {
433 
434  /* Wait for range completion */
435 
436  if (status == VL53L1_ERROR_NONE)
437  status =
439 
440  /*
441  * Get Device Results
442  * - Checks the stream count is the expected one
443  * - Read device system results
444  */
445 
446  if (status == VL53L1_ERROR_NONE)
447  status =
449  Dev,
451  prange_results);
452 
453  /*
454  * Ignore 1st two ranges to give the sigma delta initial
455  * phase time to settle
456  *
457  * accummulate range results if range is successful
458  */
459 
460  prange_data = &(prange_results->data[0]);
461 
462  if (prange_results->stream_count > 1) {
463 
464  if (prange_data->range_status ==
466 
467  poffset->no_of_samples++;
468  poffset->effective_spads +=
469  (uint32_t)prange_data->actual_effective_spads;
470  poffset->peak_rate_mcps +=
472  poffset->sigma_mm +=
473  (uint32_t)prange_data->sigma_mm;
474  poffset->median_range_mm +=
475  (int32_t)prange_data->median_range_mm;
476 
481  }
482  }
483 
484  /*
485  * Conditional wait for firmware ready. Only waits for timed
486  * and single shot modes. Mode check is performed inside the
487  * wait function
488  */
489 
490  if (status == VL53L1_ERROR_NONE)
491  status =
493 
494  /*
495  * Send ranging handshake
496  *
497  * - Update Zone management
498  * - Update GPH registers
499  * - Clear current interrupt
500  * - Initialise SYSTEM__MODE_START for next range (if there is one!)
501  */
502 
503  if (status == VL53L1_ERROR_NONE)
504  status =
506  Dev,
507  measurement_mode);
508  }
509 
510  /* Stop range */
511 
512  if (status == VL53L1_ERROR_NONE)
513  status = VL53L1_stop_range(Dev);
514 
515  /* Wait for Stop (abort) range to complete */
516 
517  if (status == VL53L1_ERROR_NONE)
518  status = VL53L1_WaitUs(Dev, 1000);
519 
520  /* generate average values */
521  if (poffset->no_of_samples > 0) {
522 
523  poffset->effective_spads += (poffset->no_of_samples/2);
524  poffset->effective_spads /= poffset->no_of_samples;
525 
526  poffset->peak_rate_mcps += (poffset->no_of_samples/2);
527  poffset->peak_rate_mcps /= poffset->no_of_samples;
528 
529  poffset->sigma_mm += (poffset->no_of_samples/2);
530  poffset->sigma_mm /= poffset->no_of_samples;
531 
532  poffset->median_range_mm += (poffset->no_of_samples/2);
533  poffset->median_range_mm /= poffset->no_of_samples;
534 
535  poffset->range_mm_offset = (int32_t)cal_distance_mm;
536  poffset->range_mm_offset -= poffset->median_range_mm;
537 
538  /* remember the number of SPADs for standard ranging */
539  if (poffset->preset_mode ==
541  manual_effective_spads =
542  (uint16_t)poffset->effective_spads;
543  }
544  }
545 
546  /* Calculate offsets */
547 
548  switch (pdev->offset_calibration_mode) {
549 
551 
552  /* copy offsets to customer data structure */
557  break;
558 
559  default:
560  /* copy offsets to customer data structure */
566 
567  /* copy average rate and effective SPAD count to
568  additional offset calibration data structure */
569 
574 
579 
580  break;
581  }
582 
583 
584  /* apply to device */
585 
586  if (status == VL53L1_ERROR_NONE)
587  status =
589  Dev,
590  &(pdev->customer));
591 
592  /*
593  * Check the peak rates, sigma, min spads for each stage
594  */
595 
596  for (m = 0 ; m < pdev->offset_results.active_results ; m++) {
597 
598  poffset = &(pdev->offset_results.data[m]);
599 
600  if (status == VL53L1_ERROR_NONE) {
601 
602  pdev->offset_results.cal_report = m;
603 
604  if (poffset->no_of_samples < num_of_samples[m])
606 
607  /* only check sigma for the pre-range as
608  * the it is not calculated by the device
609  * for the MM1 and MM2 stages
610  */
611  if (m == 0 && poffset->sigma_mm >
614 
615  if (poffset->peak_rate_mcps >
618 
622 
625 
626  if (poffset->no_of_samples == 0)
628  }
629  }
630 
631  /*
632  * Save unfiltered status
633  */
634 
635  pdev->offset_results.cal_status = status;
636  *pcal_status = pdev->offset_results.cal_status;
637 
638  /* Status exception codes */
639 
643  status);
644 
648  status);
649 
653  status);
654 
658  status);
659 
660 #ifdef VL53L1_LOG_ENABLE
661 
662  /* Prints out the offset calibration data for debug */
663 
664  VL53L1_print_customer_nvm_managed(
665  &(pdev->customer),
666  "run_offset_calibration():pdev->lldata.customer.",
667  VL53L1_TRACE_MODULE_OFFSET_DATA);
668 
669  VL53L1_print_additional_offset_cal_data(
670  &(pdev->add_off_cal_data),
671  "run_offset_calibration():pdev->lldata.add_off_cal_data.",
672  VL53L1_TRACE_MODULE_OFFSET_DATA);
673 
674  VL53L1_print_offset_range_results(
675  &(pdev->offset_results),
676  "run_offset_calibration():pdev->lldata.offset_results.",
677  VL53L1_TRACE_MODULE_OFFSET_DATA);
678 #endif
679 
680  LOG_FUNCTION_END(status);
681 
682  return status;
683 }
684 #endif
685 
686 #ifndef VL53L1_NOCALIB
688  VL53L1_DEV Dev,
689  VL53L1_DeviceTestMode device_test_mode,
690  VL53L1_DeviceSscArray array_select,
691  uint32_t ssc_config_timeout_us,
692  VL53L1_spad_rate_data_t *pspad_rate_data)
693 {
694 
700 
701  VL53L1_LLDriverData_t *pdev =
703 
704  LOG_FUNCTION_START("");
705 
706  /*
707  * Ensure power force is enabled
708  */
709  if (status == VL53L1_ERROR_NONE)
710  status = VL53L1_enable_powerforce(Dev);
711 
712  /*
713  * Configure the test
714  */
715 
716  if (status == VL53L1_ERROR_NONE) {
717  pdev->ssc_cfg.array_select = array_select;
718  pdev->ssc_cfg.timeout_us = ssc_config_timeout_us;
719  status =
721  Dev,
722  &(pdev->ssc_cfg),
724  }
725 
726  /*
727  * Run device test
728  */
729 
730  if (status == VL53L1_ERROR_NONE)
731  status =
733  Dev,
734  device_test_mode);
735 
736  /*
737  * Read Rate Data from Patch Ram
738  */
739 
740  if (status == VL53L1_ERROR_NONE)
741  status =
743  Dev,
744  pspad_rate_data);
745 
746  if (device_test_mode == VL53L1_DEVICETESTMODE_LCR_VCSEL_ON)
747  pspad_rate_data->fractional_bits = 7;
748  else
749  pspad_rate_data->fractional_bits = 15;
750 
751  /* Ensure power force is disabled */
752 
753  if (status == VL53L1_ERROR_NONE)
754  status = VL53L1_disable_powerforce(Dev);
755 
756 #ifdef VL53L1_LOG_ENABLE
757  /* Print return rate data and map */
758 
759  if (status == VL53L1_ERROR_NONE) {
760  VL53L1_print_spad_rate_data(
761  pspad_rate_data,
762  "run_spad_rate_map():",
763  VL53L1_TRACE_MODULE_SPAD_RATE_MAP);
764  VL53L1_print_spad_rate_map(
765  pspad_rate_data,
766  "run_spad_rate_map():",
767  VL53L1_TRACE_MODULE_SPAD_RATE_MAP);
768  }
769 #endif
770 
771  LOG_FUNCTION_END(status);
772 
773  return status;
774 }
775 #endif
776 
777 
778 #ifndef VL53L1_NOCALIB
780  VL53L1_DEV Dev,
781  VL53L1_DeviceTestMode device_test_mode)
782 {
783  /*
784  * Runs the selected Device Test Mode
785  */
786 
789 
790  uint8_t comms_buffer[2];
791  uint8_t gpio_hv_mux__ctrl = 0;
792 
793  LOG_FUNCTION_START("");
794 
795  /*
796  * Get current interrupt config
797  */
798 
799  if (status == VL53L1_ERROR_NONE) /*lint !e774 always true*/
800  status =
802  Dev,
804  &gpio_hv_mux__ctrl);
805 
806  if (status == VL53L1_ERROR_NONE)
807  pdev->stat_cfg.gpio_hv_mux__ctrl = gpio_hv_mux__ctrl;
808 
809  /*
810  * Trigger the test
811  */
812  if (status == VL53L1_ERROR_NONE)
813  status = VL53L1_start_test(
814  Dev,
815  device_test_mode);
816 
817  /*
818  * Wait for test completion
819  */
820  if (status == VL53L1_ERROR_NONE)
821  status = VL53L1_wait_for_test_completion(Dev);
822 
823  /*
824  * Read range and report status
825  */
826  if (status == VL53L1_ERROR_NONE)
827  status =
829  Dev,
831  comms_buffer,
832  2);
833 
834  if (status == VL53L1_ERROR_NONE) {
835  pdev->sys_results.result__range_status = comms_buffer[0];
836  pdev->sys_results.result__report_status = comms_buffer[1];
837  }
838 
839  /* mask range status bits */
840 
843 
844  if (status == VL53L1_ERROR_NONE) {
845  trace_print(
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",
852 
853  /*
854  * Clear interrupt
855  */
856  if (status == VL53L1_ERROR_NONE)
857  status = VL53L1_clear_interrupt(Dev);
858  }
859 
860  /*
861  * Clear test mode register
862  * - required so that next test command will trigger
863  * internal MCU interrupt
864  */
865 
866  if (status == VL53L1_ERROR_NONE)
867  status =
869  Dev,
870  0x00);
871 
872  LOG_FUNCTION_END(status);
873 
874  return status;
875 }
876 #endif
VL53L1_customer_nvm_managed_t::ref_spad_man__ref_location
uint8_t ref_spad_man__ref_location
Definition: vl53l1_register_structs.h:324
VL53L1_range_data_t::range_status
uint8_t range_status
Definition: vl53l1_ll_def.h:597
VL53L1_DEVICEERROR_REFSPADCHARLESSTHANTARGET
#define VL53L1_DEVICEERROR_REFSPADCHARLESSTHANTARGET
Definition: vl53l1_ll_device.h:273
vl53l1_ll_def.h
Type definitions for VL53L1 LL Driver.
VL53L1_offset_range_data_t::sigma_mm
uint32_t sigma_mm
Definition: vl53l1_ll_def.h:647
VL53L1_offsetcal_config_t::pre_num_of_samples
uint8_t pre_num_of_samples
Definition: vl53l1_ll_def.h:793
uint32_t
unsigned int uint32_t
Typedef defining 32 bit unsigned int type. The developer should modify this to suit the platform bein...
Definition: vl53l1_types.h:113
uint8_t
unsigned char uint8_t
Typedef defining 8 bit unsigned char type. The developer should modify this to suit the platform bein...
Definition: vl53l1_types.h:133
VL53L1_range_data_t::sigma_mm
uint16_t sigma_mm
Definition: vl53l1_ll_def.h:580
vl53l1_api_debug.h
EwokPlus25 low level API function definitions.
IGNORE_OFFSET_CAL_RATE_TOO_HIGH
#define IGNORE_OFFSET_CAL_RATE_TOO_HIGH
Definition: vl53l1_error_exceptions.h:86
IGNORE_OFFSET_CAL_SPAD_COUNT_TOO_LOW
#define IGNORE_OFFSET_CAL_SPAD_COUNT_TOO_LOW
Definition: vl53l1_error_exceptions.h:87
VL53L1_ssc_config_t::array_select
VL53L1_DeviceSscArray array_select
Definition: vl53l1_ll_def.h:189
VL53L1_offset_range_results_t::cal_report
uint8_t cal_report
Definition: vl53l1_ll_def.h:671
VL53L1_LLDriverData_t::add_off_cal_data
VL53L1_additional_offset_cal_data_t add_off_cal_data
Definition: vl53l1_ll_def.h:856
VL53L1_debug_results_t::ref_spad_char_result__num_actual_ref_spads
uint8_t ref_spad_char_result__num_actual_ref_spads
Definition: vl53l1_register_structs.h:1752
VL53L1_WARNING_REF_SPAD_CHAR_NOT_ENOUGH_SPADS
#define VL53L1_WARNING_REF_SPAD_CHAR_NOT_ENOUGH_SPADS
Definition: vl53l1_error_codes.h:171
VL53L1_DEVICEPRESETMODE_STANDARD_RANGING
#define VL53L1_DEVICEPRESETMODE_STANDARD_RANGING
Definition: vl53l1_ll_device.h:128
VL53L1_range_data_t
Internal data structure for storing post processed ranges.
Definition: vl53l1_ll_def.h:523
VL53L1_ssc_config_t::timeout_us
uint32_t timeout_us
Definition: vl53l1_ll_def.h:199
vl53l1_api_core.h
EwokPlus25 low level API function definitions.
VL53L1_additional_offset_cal_data_t::result__mm_inner_actual_effective_spads
uint16_t result__mm_inner_actual_effective_spads
Definition: vl53l1_ll_def.h:694
VL53L1_set_ssc_config
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.
Definition: vl53l1_core.c:1935
VL53L1_general_config_t::dss_config__manual_effective_spads_select
uint16_t dss_config__manual_effective_spads_select
Definition: vl53l1_register_structs.h:870
VL53L1_get_spad_rate_data
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.
Definition: vl53l1_core.c:2039
VL53L1_DEVICEERROR_RANGECOMPLETE
#define VL53L1_DEVICEERROR_RANGECOMPLETE
Definition: vl53l1_ll_device.h:266
VL53L1_LLDriverData_t::offset_results
VL53L1_offset_range_results_t offset_results
Definition: vl53l1_ll_def.h:884
VL53L1_wait_for_firmware_ready
VL53L1_Error VL53L1_wait_for_firmware_ready(VL53L1_DEV Dev)
Waits for initial firmware ready.
Definition: vl53l1_wait.c:136
LOG_FUNCTION_END
#define LOG_FUNCTION_END(status,...)
Definition: vl53l1_api_calibration.c:92
VL53L1_offsetcal_config_t::mm_config_timeout_us
uint32_t mm_config_timeout_us
Definition: vl53l1_ll_def.h:789
VL53L1_clear_interrupt
VL53L1_Error VL53L1_clear_interrupt(VL53L1_DEV Dev)
Clears Ranging Interrupt.
Definition: vl53l1_core.c:866
VL53L1_WARNING_OFFSET_CAL_RATE_TOO_HIGH
#define VL53L1_WARNING_OFFSET_CAL_RATE_TOO_HIGH
Definition: vl53l1_error_codes.h:190
VL53L1_stop_range
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.
Definition: vl53l1_api_core.c:2159
VL53L1_wait_for_range_completion
VL53L1_Error VL53L1_wait_for_range_completion(VL53L1_DEV Dev)
Waits for the next ranging interrupt.
Definition: vl53l1_wait.c:201
VL53L1_general_config_t::dss_config__roi_mode_control
uint8_t dss_config__roi_mode_control
Definition: vl53l1_register_structs.h:839
LOG_FUNCTION_START
#define LOG_FUNCTION_START(fmt,...)
Definition: vl53l1_api_calibration.c:90
VL53L1_DEVICERESULTSLEVEL_FULL
#define VL53L1_DEVICERESULTSLEVEL_FULL
Definition: vl53l1_ll_device.h:377
VL53L1_WARNING_OFFSET_CAL_MISSING_SAMPLES
#define VL53L1_WARNING_OFFSET_CAL_MISSING_SAMPLES
Definition: vl53l1_error_codes.h:183
vl53l1_wait.h
EwokPlus25 low level Driver wait function definitions.
vl53l1_register_settings.h
Device register setting defines.
vl53l1_api_preset_modes.h
EwokPlus25 API core function definition.
IGNORE_REF_SPAD_CHAR_RATE_TOO_LOW
#define IGNORE_REF_SPAD_CHAR_RATE_TOO_LOW
Definition: vl53l1_error_exceptions.h:82
VL53L1_set_customer_nvm_managed
VL53L1_Error VL53L1_set_customer_nvm_managed(VL53L1_DEV Dev, VL53L1_customer_nvm_managed_t *pdata)
Sets customer_nvm_managed register group.
Definition: vl53l1_register_funcs.c:366
VL53L1_spad_rate_data_t::fractional_bits
uint8_t fractional_bits
Definition: vl53l1_ll_def.h:1029
VL53L1_range_results_t::data
VL53L1_range_data_t data[2]
Definition: vl53l1_ll_def.h:620
VL53L1_spad_rate_data_t
SPAD Rate Data output by SSC.
Definition: vl53l1_ll_def.h:1019
VL53L1_offset_range_results_t::active_results
uint8_t active_results
Definition: vl53l1_ll_def.h:676
VL53L1_offsetcal_config_t::phasecal_config_timeout_us
uint32_t phasecal_config_timeout_us
Definition: vl53l1_ll_def.h:783
VL53L1_LLDriverData_t::offset_calibration_mode
VL53L1_OffsetCalibrationMode offset_calibration_mode
Definition: vl53l1_ll_def.h:822
VL53L1_OFFSET_CAL_MAX_PRE_PEAK_RATE_MCPS
#define VL53L1_OFFSET_CAL_MAX_PRE_PEAK_RATE_MCPS
Definition: vl53l1_platform_user_config.h:97
VL53L1_run_device_test
VL53L1_Error VL53L1_run_device_test(VL53L1_DEV Dev, VL53L1_DeviceTestMode device_test_mode)
Runs the input Device Test.
Definition: vl53l1_api_calibration.c:779
VL53L1_GPIO_HV_MUX__CTRL
#define VL53L1_GPIO_HV_MUX__CTRL
Definition: vl53l1_register_map.h:775
VL53L1_LLDriverData_t::ssc_cfg
VL53L1_ssc_config_t ssc_cfg
Definition: vl53l1_ll_def.h:869
vl53l1_core.h
EwokPlus25 core function definitions.
IGNORE_REF_SPAD_CHAR_NOT_ENOUGH_SPADS
#define IGNORE_REF_SPAD_CHAR_NOT_ENOUGH_SPADS
Definition: vl53l1_error_exceptions.h:80
VL53L1_additional_offset_cal_data_t::result__mm_inner_peak_signal_count_rtn_mcps
uint16_t result__mm_inner_peak_signal_count_rtn_mcps
Definition: vl53l1_ll_def.h:698
VL53L1_customer_nvm_managed_t::global_config__spad_enables_ref_0
uint8_t global_config__spad_enables_ref_0
Definition: vl53l1_register_structs.h:244
VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_HIGH
#define VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_HIGH
Definition: vl53l1_error_codes.h:173
VL53L1_range_data_t::peak_signal_count_rate_mcps
uint16_t peak_signal_count_rate_mcps
Definition: vl53l1_ll_def.h:567
VL53L1_offsetcal_config_t::mm1_num_of_samples
uint8_t mm1_num_of_samples
Definition: vl53l1_ll_def.h:796
VL53L1_refspadchar_config_t::target_count_rate_mcps
uint16_t target_count_rate_mcps
Definition: vl53l1_ll_def.h:173
VL53L1_static_nvm_managed_t::osc_measured__fast_osc__frequency
uint16_t osc_measured__fast_osc__frequency
Definition: vl53l1_register_structs.h:179
vl53l1_register_funcs.h
VL53L1 Register Function declarations.
VL53L1_Dev_t
Definition: vl53l1_platform_user_data.h:78
VL53L1_offset_range_data_t::range_mm_offset
int32_t range_mm_offset
Definition: vl53l1_ll_def.h:652
VL53L1_DevicePresetModes
uint8_t VL53L1_DevicePresetModes
Definition: vl53l1_ll_device.h:125
VL53L1_offset_range_data_t
Structure for storing the set of range results required for the mm1 and mm2 offset calibration functi...
Definition: vl53l1_ll_def.h:633
VL53L1_range_results_t
Structure for storing the set of range results.
Definition: vl53l1_ll_def.h:608
VL53L1_WaitUs
VL53L1_Error VL53L1_WaitUs(VL53L1_Dev_t *pdev, int32_t wait_us)
Definition: vl53l1_platform.c:77
VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_LOW
#define VL53L1_WARNING_REF_SPAD_CHAR_RATE_TOO_LOW
Definition: vl53l1_error_codes.h:177
VL53L1_offset_range_data_t::dss_config__manual_effective_spads_select
uint16_t dss_config__manual_effective_spads_select
Definition: vl53l1_ll_def.h:639
int16_t
short int16_t
Typedef defining 16 bit short type. The developer should modify this to suit the platform being deplo...
Definition: vl53l1_types.h:128
VL53L1_LLDriverData_t::gen_cfg
VL53L1_general_config_t gen_cfg
Definition: vl53l1_ll_def.h:876
VL53L1_MAX_OFFSET_RANGE_RESULTS
#define VL53L1_MAX_OFFSET_RANGE_RESULTS
Definition: vl53l1_ll_def.h:120
VL53L1_run_spad_rate_map
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.
Definition: vl53l1_api_calibration.c:687
VL53L1_customer_nvm_managed_t::global_config__spad_enables_ref_1
uint8_t global_config__spad_enables_ref_1
Definition: vl53l1_register_structs.h:254
VL53L1_wait_for_test_completion
VL53L1_Error VL53L1_wait_for_test_completion(VL53L1_DEV Dev)
Waits for a device test mode to complete.
Definition: vl53l1_wait.c:248
VL53L1_offset_range_results_t::cal_status
VL53L1_Error cal_status
Definition: vl53l1_ll_def.h:669
VL53L1_WARNING_OFFSET_CAL_SPAD_COUNT_TOO_LOW
#define VL53L1_WARNING_OFFSET_CAL_SPAD_COUNT_TOO_LOW
Definition: vl53l1_error_codes.h:194
VL53L1_init_and_start_range
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.
Definition: vl53l1_api_core.c:1889
IGNORE_REF_SPAD_CHAR_RATE_TOO_HIGH
#define IGNORE_REF_SPAD_CHAR_RATE_TOO_HIGH
Definition: vl53l1_error_exceptions.h:81
VL53L1_offset_range_data_t::dss_config__roi_mode_control
uint8_t dss_config__roi_mode_control
Definition: vl53l1_ll_def.h:637
VL53L1_additional_offset_cal_data_t::result__mm_outer_peak_signal_count_rtn_mcps
uint16_t result__mm_outer_peak_signal_count_rtn_mcps
Definition: vl53l1_ll_def.h:700
IGNORE_OFFSET_CAL_SIGMA_TOO_HIGH
#define IGNORE_OFFSET_CAL_SIGMA_TOO_HIGH
Definition: vl53l1_error_exceptions.h:85
vl53l1_register_map.h
VL53L1 Register Map definitions.
VL53L1_OFFSET_CAL_MIN_EFFECTIVE_SPADS
#define VL53L1_OFFSET_CAL_MIN_EFFECTIVE_SPADS
Definition: vl53l1_platform_user_config.h:93
VL53L1_LLDriverData_t::offsetcal_cfg
VL53L1_offsetcal_config_t offsetcal_cfg
Definition: vl53l1_ll_def.h:871
VL53L1_RESULT__SPARE_0_SD1
#define VL53L1_RESULT__SPARE_0_SD1
Definition: vl53l1_register_map.h:2581
vl53l1_silicon_core.h
EwokPlus25 low level silicon specific API function definitions.
VL53L1_start_test
VL53L1_Error VL53L1_start_test(VL53L1_DEV Dev, uint8_t test_mode__ctrl)
Triggers the start of the provided test_mode.
Definition: vl53l1_core.c:721
VL53L1_LLDriverData_t::dbg_results
VL53L1_debug_results_t dbg_results
Definition: vl53l1_ll_def.h:888
VL53L1_ERROR_OFFSET_CAL_NO_SAMPLE_FAIL
#define VL53L1_ERROR_OFFSET_CAL_NO_SAMPLE_FAIL
Definition: vl53l1_error_codes.h:153
VL53L1_offsetcal_config_t::range_config_timeout_us
uint32_t range_config_timeout_us
Definition: vl53l1_ll_def.h:786
VL53L1_ERROR_OFFSET_CAL_NO_SPADS_ENABLED_FAIL
#define VL53L1_ERROR_OFFSET_CAL_NO_SPADS_ENABLED_FAIL
Definition: vl53l1_error_codes.h:156
VL53L1_ReadMulti
VL53L1_Error VL53L1_ReadMulti(VL53L1_DEV Dev, uint16_t index, uint8_t *pdata, uint32_t count)
Definition: vl53l1_platform.c:16
VL53L1_WriteMulti
VL53L1_Error VL53L1_WriteMulti(VL53L1_DEV Dev, uint16_t index, uint8_t *pdata, uint32_t count)
Definition: vl53l1_platform.c:11
VL53L1_customer_nvm_managed_t::global_config__spad_enables_ref_5
uint8_t global_config__spad_enables_ref_5
Definition: vl53l1_register_structs.h:294
VL53L1_DEVICETESTMODE_LCR_VCSEL_ON
#define VL53L1_DEVICETESTMODE_LCR_VCSEL_ON
Definition: vl53l1_ll_device.h:412
VL53L1_customer_nvm_managed_t::global_config__spad_enables_ref_4
uint8_t global_config__spad_enables_ref_4
Definition: vl53l1_register_structs.h:284
VL53L1_offset_range_data_t::median_range_mm
int32_t median_range_mm
Definition: vl53l1_ll_def.h:649
VL53L1_ERROR_NONE
#define VL53L1_ERROR_NONE
Definition: vl53l1_error_codes.h:91
VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM1_CAL
#define VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM1_CAL
Definition: vl53l1_ll_device.h:131
VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM2_CAL
#define VL53L1_DEVICEPRESETMODE_STANDARD_RANGING_MM2_CAL
Definition: vl53l1_ll_device.h:132
VL53L1_get_device_results
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...
Definition: vl53l1_api_core.c:2298
VL53L1_LLDriverData_t::sys_results
VL53L1_system_results_t sys_results
Definition: vl53l1_ll_def.h:880
VL53L1_set_ref_spad_char_config
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.
Definition: vl53l1_core.c:1819
VL53L1_customer_nvm_managed_t::mm_config__outer_offset_mm
int16_t mm_config__outer_offset_mm
Definition: vl53l1_register_structs.h:394
VL53L1_customer_nvm_managed_t::ref_spad_man__num_requested_ref_spads
uint8_t ref_spad_man__num_requested_ref_spads
Definition: vl53l1_register_structs.h:314
VL53L1_set_preset_mode
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.
Definition: vl53l1_api_core.c:1230
VL53L1_offset_range_data_t::no_of_samples
uint8_t no_of_samples
Definition: vl53l1_ll_def.h:641
VL53L1_customer_nvm_managed_t::global_config__spad_enables_ref_2
uint8_t global_config__spad_enables_ref_2
Definition: vl53l1_register_structs.h:264
VL53L1_DeviceTestMode
uint8_t VL53L1_DeviceTestMode
Definition: vl53l1_ll_device.h:391
VL53L1_enable_powerforce
VL53L1_Error VL53L1_enable_powerforce(VL53L1_DEV Dev)
Enables power force.
Definition: vl53l1_core.c:828
VL53L1_range_data_t::actual_effective_spads
uint16_t actual_effective_spads
Definition: vl53l1_ll_def.h:541
VL53L1_DEVICEERROR_REFSPADCHARMORETHANTARGET
#define VL53L1_DEVICEERROR_REFSPADCHARMORETHANTARGET
Definition: vl53l1_ll_device.h:272
VL53L1_system_results_t::result__range_status
uint8_t result__range_status
Definition: vl53l1_register_structs.h:1372
int32_t
int int32_t
Typedef defining 32 bit int type. The developer should modify this to suit the platform being deploye...
Definition: vl53l1_types.h:118
VL53L1_REF_SPAD_CHAR_RESULT__NUM_ACTUAL_REF_SPADS
#define VL53L1_REF_SPAD_CHAR_RESULT__NUM_ACTUAL_REF_SPADS
Definition: vl53l1_register_map.h:3102
VL53L1_customer_nvm_managed_t::algo__part_to_part_range_offset_mm
int16_t algo__part_to_part_range_offset_mm
Definition: vl53l1_register_structs.h:374
VL53L1_LLDriverData_t::customer
VL53L1_customer_nvm_managed_t customer
Definition: vl53l1_ll_def.h:854
VL53L1_DEVICECONFIGLEVEL_CUSTOMER_ONWARDS
#define VL53L1_DEVICECONFIGLEVEL_CUSTOMER_ONWARDS
Definition: vl53l1_ll_device.h:352
VL53L1_DeviceSscArray
uint8_t VL53L1_DeviceSscArray
Definition: vl53l1_ll_device.h:434
VL53L1_disable_powerforce
VL53L1_Error VL53L1_disable_powerforce(VL53L1_DEV Dev)
Disables power force.
Definition: vl53l1_core.c:847
VL53L1_offset_range_results_t::data
VL53L1_offset_range_data_t data[VL53L1_MAX_OFFSET_RANGE_RESULTS]
Definition: vl53l1_ll_def.h:678
VL53L1_run_ref_spad_char
VL53L1_Error VL53L1_run_ref_spad_char(VL53L1_DEV Dev, VL53L1_Error *pcal_status)
Run Reference Array SPAD Characterisation.
Definition: vl53l1_api_calibration.c:104
VL53L1_customer_nvm_managed_t::global_config__spad_enables_ref_3
uint8_t global_config__spad_enables_ref_3
Definition: vl53l1_register_structs.h:274
VL53L1DevStructGetLLDriverHandle
#define VL53L1DevStructGetLLDriverHandle(Dev)
Definition: vl53l1_platform_user_data.h:94
VL53L1_refspadchar_config_t
Reference SPAD Characterization (RefSpadChar) Config.
Definition: vl53l1_ll_def.h:168
VL53L1_customer_nvm_managed_t::mm_config__inner_offset_mm
int16_t mm_config__inner_offset_mm
Definition: vl53l1_register_structs.h:384
VL53L1_system_results_t::result__report_status
uint8_t result__report_status
Definition: vl53l1_register_structs.h:1385
VL53L1_range_data_t::median_range_mm
int16_t median_range_mm
Definition: vl53l1_ll_def.h:590
VL53L1_offset_range_data_t::preset_mode
uint8_t preset_mode
Definition: vl53l1_ll_def.h:635
vl53l1_ll_device.h
LL Driver Device specific defines. To be adapted by implementer for the targeted device.
VL53L1_LLDriverData_t::stat_cfg
VL53L1_static_config_t stat_cfg
Definition: vl53l1_ll_def.h:875
VL53L1_additional_offset_cal_data_t::result__mm_outer_actual_effective_spads
uint16_t result__mm_outer_actual_effective_spads
Definition: vl53l1_ll_def.h:696
VL53L1_offset_range_results_t::cal_distance_mm
int16_t cal_distance_mm
Definition: vl53l1_ll_def.h:667
VL53L1_RdByte
VL53L1_Error VL53L1_RdByte(VL53L1_DEV Dev, uint16_t index, uint8_t *data)
Definition: vl53l1_platform.c:38
trace_print
#define trace_print(level,...)
Definition: vl53l1_api_calibration.c:98
VL53L1_offset_range_data_t::peak_rate_mcps
uint32_t peak_rate_mcps
Definition: vl53l1_ll_def.h:645
vl53l1_platform.h
VL53L1_refspadchar_config_t::vcsel_period
uint8_t vcsel_period
Definition: vl53l1_ll_def.h:171
VL53L1_offsetcal_config_t::mm2_num_of_samples
uint8_t mm2_num_of_samples
Definition: vl53l1_ll_def.h:799
VL53L1_offsetcal_config_t::dss_config__target_total_rate_mcps
uint16_t dss_config__target_total_rate_mcps
Definition: vl53l1_ll_def.h:780
VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK
#define VL53L1_DEVICEMEASUREMENTMODE_BACKTOBACK
Definition: vl53l1_ll_device.h:154
VL53L1_debug_results_t::ref_spad_char_result__ref_location
uint8_t ref_spad_char_result__ref_location
Definition: vl53l1_register_structs.h:1762
VL53L1_LLDriverData_t
VL53L1 LL Driver ST private data structure .
Definition: vl53l1_ll_def.h:814
IGNORE_STATUS
#define IGNORE_STATUS(__FUNCTION_ID__, __ERROR_STATUS_CHECK__, __STATUS__)
Definition: vl53l1_ll_def.h:1076
vl53l1_api_calibration.h
VL53L1_WARNING_OFFSET_CAL_SIGMA_TOO_HIGH
#define VL53L1_WARNING_OFFSET_CAL_SIGMA_TOO_HIGH
Definition: vl53l1_error_codes.h:186
VL53L1_Error
int8_t VL53L1_Error
Definition: vl53l1_error_codes.h:89
VL53L1_RANGE_STATUS__RANGE_STATUS_MASK
#define VL53L1_RANGE_STATUS__RANGE_STATUS_MASK
Definition: vl53l1_register_settings.h:199
VL53L1_OFFSET_CAL_MAX_SIGMA_MM
#define VL53L1_OFFSET_CAL_MAX_SIGMA_MM
Definition: vl53l1_platform_user_config.h:102
VL53L1_run_offset_calibration
VL53L1_Error VL53L1_run_offset_calibration(VL53L1_DEV Dev, int16_t cal_distance_mm, VL53L1_Error *pcal_status)
Run offset calibration.
Definition: vl53l1_api_calibration.c:290
VL53L1_refspadchar_config_t::device_test_mode
uint8_t device_test_mode
Definition: vl53l1_ll_def.h:170
uint16_t
unsigned short uint16_t
Typedef defining 16 bit unsigned short type. The developer should modify this to suit the platform be...
Definition: vl53l1_types.h:123
VL53L1_static_config_t::gpio_hv_mux__ctrl
uint8_t gpio_hv_mux__ctrl
Definition: vl53l1_register_structs.h:537
VL53L1_DEVICEERROR_REFSPADCHARNOTENOUGHDPADS
#define VL53L1_DEVICEERROR_REFSPADCHARNOTENOUGHDPADS
Definition: vl53l1_ll_device.h:271
VL53L1_offset_range_results_t::max_results
uint8_t max_results
Definition: vl53l1_ll_def.h:673
VL53L1_RESULT__RANGE_STATUS
#define VL53L1_RESULT__RANGE_STATUS
Definition: vl53l1_register_map.h:2069
VL53L1_refspadchar_config_t::max_count_rate_limit_mcps
uint16_t max_count_rate_limit_mcps
Definition: vl53l1_ll_def.h:177
VL53L1_clear_interrupt_and_enable_next_range
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.
Definition: vl53l1_api_core.c:2397
VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_REF_0
#define VL53L1_GLOBAL_CONFIG__SPAD_ENABLES_REF_0
Definition: vl53l1_register_map.h:248
VL53L1_refspadchar_config_t::timeout_us
uint32_t timeout_us
Definition: vl53l1_ll_def.h:172
VL53L1_LLDriverData_t::stat_nvm
VL53L1_static_nvm_managed_t stat_nvm
Definition: vl53l1_ll_def.h:874
IGNORE_OFFSET_CAL_MISSING_SAMPLES
#define IGNORE_OFFSET_CAL_MISSING_SAMPLES
Definition: vl53l1_error_exceptions.h:84
VL53L1_range_results_t::stream_count
uint8_t stream_count
Definition: vl53l1_ll_def.h:614
VL53L1_refspadchar_config_t::min_count_rate_limit_mcps
uint16_t min_count_rate_limit_mcps
Definition: vl53l1_ll_def.h:175
VL53L1_offset_range_data_t::effective_spads
uint32_t effective_spads
Definition: vl53l1_ll_def.h:643
VL53L1_OFFSETCALIBRATIONMODE__MM1_MM2__STANDARD_PRE_RANGE_ONLY
#define VL53L1_OFFSETCALIBRATIONMODE__MM1_MM2__STANDARD_PRE_RANGE_ONLY
Definition: vl53l1_ll_device.h:170
VL53L1_REF_SPAD_MAN__NUM_REQUESTED_REF_SPADS
#define VL53L1_REF_SPAD_MAN__NUM_REQUESTED_REF_SPADS
Definition: vl53l1_register_map.h:353
VL53L1_LLDriverData_t::refspadchar
VL53L1_refspadchar_config_t refspadchar
Definition: vl53l1_ll_def.h:868


vl53l1x
Author(s):
autogenerated on Fri Aug 2 2024 08:35:54