vl53l1_silicon_core.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_platform.h"
72 #include "vl53l1_register_map.h"
73 #include "vl53l1_core.h"
74 #include "vl53l1_silicon_core.h"
75 
76 
77 #define LOG_FUNCTION_START(fmt, ...) \
78  _LOG_FUNCTION_START(VL53L1_TRACE_MODULE_CORE, fmt, ##__VA_ARGS__)
79 #define LOG_FUNCTION_END(status, ...) \
80  _LOG_FUNCTION_END(VL53L1_TRACE_MODULE_CORE, status, ##__VA_ARGS__)
81 #define LOG_FUNCTION_END_FMT(status, fmt, ...) \
82  _LOG_FUNCTION_END_FMT(VL53L1_TRACE_MODULE_CORE, status, fmt, ##__VA_ARGS__)
83 
84 
86  VL53L1_DEV Dev,
87  uint8_t *pready)
88 {
98 
99  uint8_t comms_buffer[5];
100 
101  LOG_FUNCTION_START("");
102 
103  /* read interrupt and power force reset status */
104 
105  status = VL53L1_ReadMulti(
106  Dev,
108  comms_buffer,
109  5);
110 
111  if (status == VL53L1_ERROR_NONE) {
112 
114  comms_buffer[0];
116  comms_buffer[1];
118  comms_buffer[2];
120  comms_buffer[3];
122  comms_buffer[4];
123 
124  if ((pdev->sys_ctrl.power_management__go1_power_force & 0x01) == 0x01) {
125 
126  if (((pdev->dbg_results.interrupt_manager__enables & 0x1F) == 0x1F) &&
127  ((pdev->dbg_results.interrupt_manager__clear & 0x1F) == 0x1F))
128  *pready = 0x01;
129  else
130  *pready = 0x00;
131 
132  } else {
133 
134  /* set ready flag if bit 0 is zero i.g G01 is in reset */
135  if ((pdev->dbg_results.power_management__go1_reset_status & 0x01) == 0x00)
136  *pready = 0x01;
137  else
138  *pready = 0x00;
139  }
140 
141  }
142 
143  LOG_FUNCTION_END(status);
144 
145  return status;
146 }
VL53L1_debug_results_t::interrupt_manager__enables
uint8_t interrupt_manager__enables
Definition: vl53l1_register_structs.h:2070
vl53l1_ll_def.h
Type definitions for VL53L1 LL Driver.
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_system_control_t::power_management__go1_power_force
uint8_t power_management__go1_power_force
Definition: vl53l1_register_structs.h:1291
VL53L1_INTERRUPT_MANAGER__ENABLES
#define VL53L1_INTERRUPT_MANAGER__ENABLES
Definition: vl53l1_register_map.h:3633
VL53L1_debug_results_t::interrupt_manager__status
uint8_t interrupt_manager__status
Definition: vl53l1_register_structs.h:2098
vl53l1_core.h
EwokPlus25 core function definitions.
VL53L1_Dev_t
Definition: vl53l1_platform_user_data.h:78
VL53L1_debug_results_t::mcu_to_host_bank__wr_access_en
uint8_t mcu_to_host_bank__wr_access_en
Definition: vl53l1_register_structs.h:2112
vl53l1_register_map.h
VL53L1 Register Map definitions.
vl53l1_silicon_core.h
EwokPlus25 low level silicon specific API function definitions.
VL53L1_LLDriverData_t::dbg_results
VL53L1_debug_results_t dbg_results
Definition: vl53l1_ll_def.h:888
VL53L1_ReadMulti
VL53L1_Error VL53L1_ReadMulti(VL53L1_DEV Dev, uint16_t index, uint8_t *pdata, uint32_t count)
Definition: vl53l1_platform.c:16
VL53L1_ERROR_NONE
#define VL53L1_ERROR_NONE
Definition: vl53l1_error_codes.h:91
VL53L1_debug_results_t::interrupt_manager__clear
uint8_t interrupt_manager__clear
Definition: vl53l1_register_structs.h:2084
VL53L1DevStructGetLLDriverHandle
#define VL53L1DevStructGetLLDriverHandle(Dev)
Definition: vl53l1_platform_user_data.h:94
VL53L1_LLDriverData_t::sys_ctrl
VL53L1_system_control_t sys_ctrl
Definition: vl53l1_ll_def.h:879
vl53l1_platform.h
VL53L1_LLDriverData_t
VL53L1 LL Driver ST private data structure .
Definition: vl53l1_ll_def.h:814
VL53L1_debug_results_t::power_management__go1_reset_status
uint8_t power_management__go1_reset_status
Definition: vl53l1_register_structs.h:2122
LOG_FUNCTION_START
#define LOG_FUNCTION_START(fmt,...)
Definition: vl53l1_silicon_core.c:77
VL53L1_Error
int8_t VL53L1_Error
Definition: vl53l1_error_codes.h:89
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
LOG_FUNCTION_END
#define LOG_FUNCTION_END(status,...)
Definition: vl53l1_silicon_core.c:79


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