Go to the documentation of this file.
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, \
307 uint8_t firmware__system_status = 0;
317 &firmware__system_status);
323 if ((firmware__system_status & 0x01) == 0x01) {
379 uint8_t gpio__mux_active_high_hv = 0;
380 uint8_t gpio__tio_hv_status = 0;
385 gpio__mux_active_high_hv =
390 interrupt_ready = 0x01;
392 interrupt_ready = 0x00;
399 &gpio__tio_hv_status);
403 if ((gpio__tio_hv_status & 0x01) == interrupt_ready)
504 current_time_ms - start_time_ms;
531 uint8_t gpio__mux_active_high_hv = 0;
536 gpio__mux_active_high_hv =
541 interrupt_ready = 0x01;
543 interrupt_ready = 0x00;
void VL53L1_init_ll_driver_state(VL53L1_DEV Dev, VL53L1_DeviceState device_state)
Initialise LL Driver State.
Type definitions for VL53L1 LL Driver.
unsigned int uint32_t
Typedef defining 32 bit unsigned int type. The developer should modify this to suit the platform bein...
unsigned char uint8_t
Typedef defining 8 bit unsigned char type. The developer should modify this to suit the platform bein...
VL53L1_Error VL53L1_poll_for_boot_completion(VL53L1_DEV Dev, uint32_t timeout_ms)
Waits (polls) for initial firmware boot to finish.
#define VL53L1_FIRMWARE_BOOT_TIME_US
uint8_t system__mode_start
VL53L1_Error VL53L1_poll_for_firmware_ready(VL53L1_DEV Dev, uint32_t timeout_ms)
Waits (polls) for initial firmware ready.
VL53L1_Error VL53L1_wait_for_firmware_ready(VL53L1_DEV Dev)
Waits for initial 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.
VL53L1_Error VL53L1_wait_for_range_completion(VL53L1_DEV Dev)
Waits for the next ranging interrupt.
EwokPlus25 low level Driver wait function definitions.
Device register setting defines.
#define VL53L1_GPIO__TIO_HV_STATUS
#define VL53L1_DEVICEINTERRUPTLEVEL_ACTIVE_HIGH
#define LOG_FUNCTION_START(fmt,...)
EwokPlus25 core function definitions.
VL53L1_Error VL53L1_wait_for_test_completion(VL53L1_DEV Dev)
Waits for a device test mode to complete.
VL53L1_Error VL53L1_wait_for_boot_completion(VL53L1_DEV Dev)
Wait for initial firmware boot to finish.
#define LOG_FUNCTION_END(status,...)
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.
uint32_t fw_ready_poll_duration_ms
EwokPlus25 low level silicon specific API function definitions.
#define VL53L1_WAIT_METHOD_BLOCKING
#define VL53L1_ERROR_NONE
int int32_t
Typedef defining 32 bit int type. The developer should modify this to suit the platform being deploye...
#define VL53L1_DEVICESTATE_FW_COLDBOOT
#define VL53L1_DEVICEINTERRUPTLEVEL_ACTIVE_MASK
#define VL53L1_DEVICESTATE_SW_STANDBY
#define VL53L1_ERROR_TIME_OUT
VL53L1_system_control_t sys_ctrl
LL Driver Device specific defines. To be adapted by implementer for the targeted device.
VL53L1_static_config_t stat_cfg
#define VL53L1_DEVICEMEASUREMENTMODE_SINGLESHOT
VL53L1 LL Driver ST private data structure .
#define VL53L1_DEVICEMEASUREMENTMODE_TIMED
uint8_t gpio_hv_mux__ctrl
#define VL53L1_DEVICEMEASUREMENTMODE_MODE_MASK
VL53L1_Error VL53L1_is_firmware_ready_silicon(VL53L1_DEV Dev, uint8_t *pready)
Checks if the firmware is ready for ranging (Silicon variant)
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...
#define VL53L1_FIRMWARE__SYSTEM_STATUS
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...
vl53l1x
Author(s):
autogenerated on Fri Aug 2 2024 08:35:54