vl53l1_wait.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_core.h"
74 #include "vl53l1_silicon_core.h"
75 #include "vl53l1_wait.h"
77 
78 
79 #define LOG_FUNCTION_START(fmt, ...) \
80  _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_CORE, fmt, ##__VA_ARGS__)
81 #define LOG_FUNCTION_END(status, ...) \
82  _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_CORE, status, ##__VA_ARGS__)
83 #define LOG_FUNCTION_END_FMT(status, fmt, ...) \
84  _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_CORE, status, \
85  fmt, ##__VA_ARGS__)
86 
87 
89  VL53L1_DEV Dev)
90 {
91 
92  /* Waits for firmware boot to finish
93  */
94 
97 
98  uint8_t fw_ready = 0;
99 
100  LOG_FUNCTION_START("");
101 
103 
104  /* blocking version */
105 
106  status =
108  Dev,
110 
111  } else {
112 
113  /* implement non blocking version below */
114 
115  fw_ready = 0;
116  while (fw_ready == 0x00 && status == VL53L1_ERROR_NONE) {
117  status = VL53L1_is_boot_complete(
118  Dev,
119  &fw_ready);
120 
121  if (status == VL53L1_ERROR_NONE) {
122  status = VL53L1_WaitMs(
123  Dev,
125  }
126  }
127  }
128 
129  LOG_FUNCTION_END(status);
130 
131  return status;
132 
133 }
134 
135 
137  VL53L1_DEV Dev)
138 {
139 
140  /* If in timed mode or single shot then check firmware is ready
141  * before sending handshake
142  */
143 
146 
147  uint8_t fw_ready = 0;
148  uint8_t mode_start = 0;
149 
150  LOG_FUNCTION_START("");
151 
152  /* Filter out tje measure mode part of the mode
153  * start register
154  */
155  mode_start =
158 
159  /*
160  * conditional wait for firmware ready
161  * only waits for timed and single shot modes
162  */
163 
164  if ((mode_start == VL53L1_DEVICEMEASUREMENTMODE_TIMED) ||
165  (mode_start == VL53L1_DEVICEMEASUREMENTMODE_SINGLESHOT)) {
166 
168 
169  /* blocking version */
170 
171  status =
173  Dev,
175 
176  } else {
177 
178  /* implement non blocking version below */
179 
180  fw_ready = 0;
181  while (fw_ready == 0x00 && status == VL53L1_ERROR_NONE) {
182  status = VL53L1_is_firmware_ready(
183  Dev,
184  &fw_ready);
185 
186  if (status == VL53L1_ERROR_NONE) {
187  status = VL53L1_WaitMs(
188  Dev,
190  }
191  }
192  }
193  }
194 
195  LOG_FUNCTION_END(status);
196 
197  return status;
198 }
199 
200 
202  VL53L1_DEV Dev)
203 {
204 
205  /* Wrapper function for waiting for range completion
206  */
207 
210 
211  uint8_t data_ready = 0;
212 
213  LOG_FUNCTION_START("");
214 
216 
217  /* blocking version */
218 
219  status =
221  Dev,
223 
224  } else {
225 
226  /* implement non blocking version below */
227 
228  data_ready = 0;
229  while (data_ready == 0x00 && status == VL53L1_ERROR_NONE) {
230  status = VL53L1_is_new_data_ready(
231  Dev,
232  &data_ready);
233 
234  if (status == VL53L1_ERROR_NONE) {
235  status = VL53L1_WaitMs(
236  Dev,
238  }
239  }
240  }
241 
242  LOG_FUNCTION_END(status);
243 
244  return status;
245 }
246 
247 
249  VL53L1_DEV Dev)
250 {
251 
252  /* Wrapper function for waiting for test mode completion
253  */
254 
257 
258  uint8_t data_ready = 0;
259 
260  LOG_FUNCTION_START("");
261 
263 
264  /* blocking version */
265 
266  status =
268  Dev,
270 
271  } else {
272 
273  /* implement non blocking version below */
274 
275  data_ready = 0;
276  while (data_ready == 0x00 && status == VL53L1_ERROR_NONE) {
277  status = VL53L1_is_new_data_ready(
278  Dev,
279  &data_ready);
280 
281  if (status == VL53L1_ERROR_NONE) {
282  status = VL53L1_WaitMs(
283  Dev,
285  }
286  }
287  }
288 
289  LOG_FUNCTION_END(status);
290 
291  return status;
292 }
293 
294 
295 
296 
298  VL53L1_DEV Dev,
299  uint8_t *pready)
300 {
307  uint8_t firmware__system_status = 0;
308 
309  LOG_FUNCTION_START("");
310 
311  /* read current range interrupt state */
312 
313  status =
315  Dev,
317  &firmware__system_status);
318 
319  /* set *pready = 1 if new range data ready complete
320  * zero otherwise
321  */
322 
323  if ((firmware__system_status & 0x01) == 0x01) {
324  *pready = 0x01;
326  Dev,
328  } else {
329  *pready = 0x00;
331  Dev,
333  }
334 
335  LOG_FUNCTION_END(status);
336 
337  return status;
338 }
339 
340 
342  VL53L1_DEV Dev,
343  uint8_t *pready)
344 {
351 
352  LOG_FUNCTION_START("");
353 
355  Dev,
356  pready);
357 
358  pdev->fw_ready = *pready;
359 
360  LOG_FUNCTION_END(status);
361 
362  return status;
363 }
364 
365 
367  VL53L1_DEV Dev,
368  uint8_t *pready)
369 {
378 
379  uint8_t gpio__mux_active_high_hv = 0;
380  uint8_t gpio__tio_hv_status = 0;
381  uint8_t interrupt_ready = 0;
382 
383  LOG_FUNCTION_START("");
384 
385  gpio__mux_active_high_hv =
388 
389  if (gpio__mux_active_high_hv == VL53L1_DEVICEINTERRUPTLEVEL_ACTIVE_HIGH)
390  interrupt_ready = 0x01;
391  else
392  interrupt_ready = 0x00;
393 
394  /* read current range interrupt state */
395 
396  status = VL53L1_RdByte(
397  Dev,
399  &gpio__tio_hv_status);
400 
401  /* set *pready = 1 if new range data ready complete zero otherwise */
402 
403  if ((gpio__tio_hv_status & 0x01) == interrupt_ready)
404  *pready = 0x01;
405  else
406  *pready = 0x00;
407 
408  LOG_FUNCTION_END(status);
409 
410  return status;
411 }
412 
413 
414 
415 
417  VL53L1_DEV Dev,
418  uint32_t timeout_ms)
419 {
426 
427  LOG_FUNCTION_START("");
428 
429  /* after reset for the firmware blocks I2C access while
430  * it copies the NVM data into the G02 host register banks
431  * The host must wait the required time to allow the copy
432  * to complete before attempting to read the firmware status
433  */
434 
435  status = VL53L1_WaitUs(
436  Dev,
438 
439  if (status == VL53L1_ERROR_NONE)
440  status =
442  Dev,
443  timeout_ms,
445  0x01,
446  0x01,
448 
449  if (status == VL53L1_ERROR_NONE)
451 
452  LOG_FUNCTION_END(status);
453 
454  return status;
455 }
456 
457 
459  VL53L1_DEV Dev,
460  uint32_t timeout_ms)
461 {
469 
470  uint32_t start_time_ms = 0;
471  uint32_t current_time_ms = 0;
472  int32_t poll_delay_ms = VL53L1_POLLING_DELAY_MS;
473  uint8_t fw_ready = 0;
474 
475  /* calculate time limit in absolute time */
476 
477  VL53L1_GetTickCount(&start_time_ms); /*lint !e534 ignoring return*/
478  pdev->fw_ready_poll_duration_ms = 0;
479 
480  /* wait until firmware is ready, timeout reached on error occurred */
481 
482  while ((status == VL53L1_ERROR_NONE) &&
483  (pdev->fw_ready_poll_duration_ms < timeout_ms) &&
484  (fw_ready == 0)) {
485 
486  status = VL53L1_is_firmware_ready(
487  Dev,
488  &fw_ready);
489 
490  if (status == VL53L1_ERROR_NONE &&
491  fw_ready == 0 &&
492  poll_delay_ms > 0) {
493  status = VL53L1_WaitMs(
494  Dev,
495  poll_delay_ms);
496  }
497 
498  /*
499  * Update polling time (Compare difference rather than
500  * absolute to negate 32bit wrap around issue)
501  */
502  VL53L1_GetTickCount(&current_time_ms); /*lint !e534 ignoring return*/
504  current_time_ms - start_time_ms;
505  }
506 
507  if (fw_ready == 0 && status == VL53L1_ERROR_NONE)
508  status = VL53L1_ERROR_TIME_OUT;
509 
510  LOG_FUNCTION_END(status);
511 
512  return status;
513 }
514 
515 
517  VL53L1_DEV Dev,
518  uint32_t timeout_ms)
519 {
530 
531  uint8_t gpio__mux_active_high_hv = 0;
532  uint8_t interrupt_ready = 0;
533 
534  LOG_FUNCTION_START("");
535 
536  gpio__mux_active_high_hv =
539 
540  if (gpio__mux_active_high_hv == VL53L1_DEVICEINTERRUPTLEVEL_ACTIVE_HIGH)
541  interrupt_ready = 0x01;
542  else
543  interrupt_ready = 0x00;
544 
545  status =
547  Dev,
548  timeout_ms,
550  interrupt_ready,
551  0x01,
553 
554  LOG_FUNCTION_END(status);
555 
556  return status;
557 }
558 
VL53L1_init_ll_driver_state
void VL53L1_init_ll_driver_state(VL53L1_DEV Dev, VL53L1_DeviceState device_state)
Initialise LL Driver State.
Definition: vl53l1_core.c:114
vl53l1_ll_def.h
Type definitions for VL53L1 LL Driver.
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_poll_for_boot_completion
VL53L1_Error VL53L1_poll_for_boot_completion(VL53L1_DEV Dev, uint32_t timeout_ms)
Waits (polls) for initial firmware boot to finish.
Definition: vl53l1_wait.c:416
VL53L1_FIRMWARE_BOOT_TIME_US
#define VL53L1_FIRMWARE_BOOT_TIME_US
Definition: vl53l1_ll_device.h:483
VL53L1_system_control_t::system__mode_start
uint8_t system__mode_start
Definition: vl53l1_register_structs.h:1332
VL53L1_poll_for_firmware_ready
VL53L1_Error VL53L1_poll_for_firmware_ready(VL53L1_DEV Dev, uint32_t timeout_ms)
Waits (polls) for initial firmware ready.
Definition: vl53l1_wait.c:458
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
VL53L1_is_firmware_ready
VL53L1_Error VL53L1_is_firmware_ready(VL53L1_DEV Dev, uint8_t *pready)
Reads FIRMWARE__SYSTEM_STATUS register to detect if the firmware is ready for ranging.
Definition: vl53l1_wait.c:341
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_wait.h
EwokPlus25 low level Driver wait function definitions.
vl53l1_register_settings.h
Device register setting defines.
VL53L1_GPIO__TIO_HV_STATUS
#define VL53L1_GPIO__TIO_HV_STATUS
Definition: vl53l1_register_map.h:791
VL53L1_DEVICEINTERRUPTLEVEL_ACTIVE_HIGH
#define VL53L1_DEVICEINTERRUPTLEVEL_ACTIVE_HIGH
Definition: vl53l1_ll_device.h:465
LOG_FUNCTION_START
#define LOG_FUNCTION_START(fmt,...)
Definition: vl53l1_wait.c:79
vl53l1_core.h
EwokPlus25 core function definitions.
VL53L1_WaitValueMaskEx
VL53L1_Error VL53L1_WaitValueMaskEx(VL53L1_Dev_t *pdev, uint32_t timeout_ms, uint16_t index, uint8_t value, uint8_t mask, uint32_t poll_delay_ms)
Definition: vl53l1_platform.c:82
VL53L1_BOOT_COMPLETION_POLLING_TIMEOUT_MS
#define VL53L1_BOOT_COMPLETION_POLLING_TIMEOUT_MS
Definition: vl53l1_platform_user_config.h:77
VL53L1_TEST_COMPLETION_POLLING_TIMEOUT_MS
#define VL53L1_TEST_COMPLETION_POLLING_TIMEOUT_MS
Definition: vl53l1_platform_user_config.h:79
VL53L1_Dev_t
Definition: vl53l1_platform_user_data.h:78
VL53L1_WaitUs
VL53L1_Error VL53L1_WaitUs(VL53L1_Dev_t *pdev, int32_t wait_us)
Definition: vl53l1_platform.c:77
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_wait_for_boot_completion
VL53L1_Error VL53L1_wait_for_boot_completion(VL53L1_DEV Dev)
Wait for initial firmware boot to finish.
Definition: vl53l1_wait.c:88
LOG_FUNCTION_END
#define LOG_FUNCTION_END(status,...)
Definition: vl53l1_wait.c:81
VL53L1_is_boot_complete
VL53L1_Error VL53L1_is_boot_complete(VL53L1_DEV Dev, uint8_t *pready)
Reads FIRMWARE__SYSTEM_STATUS register to detect if the firmware was finished booting.
Definition: vl53l1_wait.c:297
VL53L1_LLDriverData_t::fw_ready_poll_duration_ms
uint32_t fw_ready_poll_duration_ms
Definition: vl53l1_ll_def.h:837
vl53l1_silicon_core.h
EwokPlus25 low level silicon specific API function definitions.
VL53L1_LLDriverData_t::wait_method
uint8_t wait_method
Definition: vl53l1_ll_def.h:816
VL53L1_RANGE_COMPLETION_POLLING_TIMEOUT_MS
#define VL53L1_RANGE_COMPLETION_POLLING_TIMEOUT_MS
Definition: vl53l1_platform_user_config.h:78
VL53L1_WAIT_METHOD_BLOCKING
#define VL53L1_WAIT_METHOD_BLOCKING
Definition: vl53l1_ll_device.h:91
VL53L1_WaitMs
VL53L1_Error VL53L1_WaitMs(VL53L1_Dev_t *pdev, int32_t wait_ms)
Definition: vl53l1_platform.c:72
VL53L1_ERROR_NONE
#define VL53L1_ERROR_NONE
Definition: vl53l1_error_codes.h:91
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_DEVICESTATE_FW_COLDBOOT
#define VL53L1_DEVICESTATE_FW_COLDBOOT
Definition: vl53l1_ll_device.h:105
VL53L1_DEVICEINTERRUPTLEVEL_ACTIVE_MASK
#define VL53L1_DEVICEINTERRUPTLEVEL_ACTIVE_MASK
Definition: vl53l1_ll_device.h:469
VL53L1_DEVICESTATE_SW_STANDBY
#define VL53L1_DEVICESTATE_SW_STANDBY
Definition: vl53l1_ll_device.h:106
VL53L1_LLDriverData_t::fw_ready
uint8_t fw_ready
Definition: vl53l1_ll_def.h:839
VL53L1DevStructGetLLDriverHandle
#define VL53L1DevStructGetLLDriverHandle(Dev)
Definition: vl53l1_platform_user_data.h:94
VL53L1_GetTickCount
VL53L1_Error VL53L1_GetTickCount(uint32_t *ptick_count_ms)
Definition: vl53l1_platform.c:51
VL53L1_ERROR_TIME_OUT
#define VL53L1_ERROR_TIME_OUT
Definition: vl53l1_error_codes.h:108
VL53L1_LLDriverData_t::sys_ctrl
VL53L1_system_control_t sys_ctrl
Definition: vl53l1_ll_def.h:879
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_RdByte
VL53L1_Error VL53L1_RdByte(VL53L1_DEV Dev, uint16_t index, uint8_t *data)
Definition: vl53l1_platform.c:38
vl53l1_platform.h
VL53L1_DEVICEMEASUREMENTMODE_SINGLESHOT
#define VL53L1_DEVICEMEASUREMENTMODE_SINGLESHOT
Definition: vl53l1_ll_device.h:153
VL53L1_LLDriverData_t
VL53L1 LL Driver ST private data structure .
Definition: vl53l1_ll_def.h:814
VL53L1_Error
int8_t VL53L1_Error
Definition: vl53l1_error_codes.h:89
VL53L1_DEVICEMEASUREMENTMODE_TIMED
#define VL53L1_DEVICEMEASUREMENTMODE_TIMED
Definition: vl53l1_ll_device.h:155
VL53L1_static_config_t::gpio_hv_mux__ctrl
uint8_t gpio_hv_mux__ctrl
Definition: vl53l1_register_structs.h:537
VL53L1_POLLING_DELAY_MS
#define VL53L1_POLLING_DELAY_MS
Definition: vl53l1_platform_user_config.h:81
VL53L1_DEVICEMEASUREMENTMODE_MODE_MASK
#define VL53L1_DEVICEMEASUREMENTMODE_MODE_MASK
Definition: vl53l1_register_settings.h:117
VL53L1_is_firmware_ready_silicon
VL53L1_Error VL53L1_is_firmware_ready_silicon(VL53L1_DEV Dev, uint8_t *pready)
Checks if the firmware is ready for ranging (Silicon variant)
Definition: vl53l1_silicon_core.c:85
VL53L1_poll_for_range_completion
VL53L1_Error VL53L1_poll_for_range_completion(VL53L1_DEV Dev, uint32_t timeout_ms)
Polls bit 0 of VL53L1_GPIO__TIO_HV_STATUS register to determine the state of the GPIO (Interrupt) pin...
Definition: vl53l1_wait.c:516
VL53L1_FIRMWARE__SYSTEM_STATUS
#define VL53L1_FIRMWARE__SYSTEM_STATUS
Definition: vl53l1_register_map.h:3287
VL53L1_is_new_data_ready
VL53L1_Error VL53L1_is_new_data_ready(VL53L1_DEV Dev, uint8_t *pready)
Reads bit 0 of VL53L1_GPIO__TIO_HV_STATUS register to determine if new range data is ready (available...
Definition: vl53l1_wait.c:366


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