EwokPlus25 low level Driver wait function definitions. More...
#include "vl53l1_platform.h"
Go to the source code of this file.
Functions | |
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. More... | |
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. More... | |
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). More... | |
VL53L1_Error | VL53L1_poll_for_boot_completion (VL53L1_DEV Dev, uint32_t timeout_ms) |
Waits (polls) for initial firmware boot to finish. More... | |
VL53L1_Error | VL53L1_poll_for_firmware_ready (VL53L1_DEV Dev, uint32_t timeout_ms) |
Waits (polls) for initial firmware ready. More... | |
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. More... | |
VL53L1_Error | VL53L1_wait_for_boot_completion (VL53L1_DEV Dev) |
Wait for initial firmware boot to finish. More... | |
VL53L1_Error | VL53L1_wait_for_firmware_ready (VL53L1_DEV Dev) |
Waits for initial firmware ready. More... | |
VL53L1_Error | VL53L1_wait_for_range_completion (VL53L1_DEV Dev) |
Waits for the next ranging interrupt. More... | |
VL53L1_Error | VL53L1_wait_for_test_completion (VL53L1_DEV Dev) |
Waits for a device test mode to complete. More... | |
EwokPlus25 low level Driver wait function definitions.
Definition in file vl53l1_wait.h.
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.
[in] | Dev | : Device handle |
[out] | pready | : pointer to data ready flag 0 = boot not complete 1 = boot complete |
Determines if the firmware finished booting by reading bit 0 of firmware__system_status register
Definition at line 297 of file vl53l1_wait.c.
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.
[in] | Dev | : Device handle |
[out] | pready | : pointer to data ready flag 0 = firmware not ready 1 = firmware ready |
Determines if the firmware is ready to range
Definition at line 341 of file vl53l1_wait.c.
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).
Interrupt may be either active high or active low. The behaviour of bit 0 of the VL53L1_GPIO__TIO_HV_STATUS register is the same as the interrupt signal generated on the GPIO pin.
pdev->stat_cfg.gpio_hv_mux_ctrl bit 4 is used to select required check level
[in] | Dev | : Device handle |
[out] | pready | : pointer to data ready flag 0 = data not ready 1 = new range data available |
Determines if new range data is ready by reading bit 0 of VL53L1_GPIO__TIO_HV_STATUS to determine the current state of output interrupt pin
Definition at line 366 of file vl53l1_wait.c.
VL53L1_Error VL53L1_poll_for_boot_completion | ( | VL53L1_DEV | Dev, |
uint32_t | timeout_ms | ||
) |
Waits (polls) for initial firmware boot to finish.
After power on or a device reset via XSHUTDOWN EwokPlus25 firmware takes about 2ms to boot. During this boot sequence elected NVM data is copied to the device's Host & MCU G02 registers
This function polls the FIRMWARE__SYSTEM_STATUS register to detect when firmware is ready.
Polling is implemented using VL53L1_WaitValueMaskEx()
[in] | Dev | : Device handle |
[in] | timeout_ms | : Wait timeout in [ms] |
Polls the bit 0 of the FIRMWARE__SYSTEM_STATUS register to see if the firmware is ready.
Definition at line 416 of file vl53l1_wait.c.
VL53L1_Error VL53L1_poll_for_firmware_ready | ( | VL53L1_DEV | Dev, |
uint32_t | timeout_ms | ||
) |
Waits (polls) for initial firmware ready.
Polling is implemented using VL53L1_WaitValueMaskEx()
[in] | Dev | : Device handle |
[in] | timeout_ms | : Wait timeout in [ms] |
Polls the bit 0 of the FIRMWARE__SYSTEM_STATUS register to see if the firmware is ready.
Definition at line 458 of file vl53l1_wait.c.
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.
Interrupt may be either active high or active low. The behaviour of bit 0 of the VL53L1_GPIO__TIO_HV_STATUS register is the same as the interrupt signal generated on the GPIO pin.
pdev->stat_cfg.gpio_hv_mux_ctrl bit 4 is used to select required check level
Polling is implemented using VL53L1_WaitValueMaskEx()
[in] | Dev | : Device handle |
[in] | timeout_ms | : Wait timeout in [ms] |
Polls bit 0 of VL53L1_GPIO__TIO_HV_STATUS to determine the state of output interrupt pin
Interrupt may be either active high or active low. Use active_high to select the required level check
Definition at line 516 of file vl53l1_wait.c.
VL53L1_Error VL53L1_wait_for_boot_completion | ( | VL53L1_DEV | Dev | ) |
Wait for initial firmware boot to finish.
Calls VL53L1_poll_for_boot_completion()
[in] | Dev | : Device handle |
Definition at line 88 of file vl53l1_wait.c.
VL53L1_Error VL53L1_wait_for_firmware_ready | ( | VL53L1_DEV | Dev | ) |
Waits for initial firmware ready.
Only waits to see if the firmware is ready in timed and single shot modes.
Calls VL53L1_poll_for_firmware_ready()
[in] | Dev | : Device handle |
Definition at line 136 of file vl53l1_wait.c.
VL53L1_Error VL53L1_wait_for_range_completion | ( | VL53L1_DEV | Dev | ) |
Waits for the next ranging interrupt.
Calls VL53L1_poll_for_range_completion()
[in] | Dev | : Device handle |
Definition at line 201 of file vl53l1_wait.c.
VL53L1_Error VL53L1_wait_for_test_completion | ( | VL53L1_DEV | Dev | ) |
Waits for a device test mode to complete.
Calls VL53L1_poll_for_test_completion()
[in] | Dev | : Device Handle |
Definition at line 248 of file vl53l1_wait.c.