导航部分效果最好的版本,主分支
This commit is contained in:
143
App/VL53L0X_API/MIGRATION_NOTES.md
Normal file
143
App/VL53L0X_API/MIGRATION_NOTES.md
Normal file
@@ -0,0 +1,143 @@
|
||||
# VL53L0X_API Notes
|
||||
|
||||
本文档只说明 `VL53L0X_API` 目录里我们自己写的兼容层分别负责什么,方便后续在旧工程里继续集成。
|
||||
|
||||
## 目录分层
|
||||
|
||||
### `core/`
|
||||
|
||||
这是 ST 官方 API 核心层,主要负责:
|
||||
|
||||
- 设备初始化
|
||||
- 寄存器访问逻辑
|
||||
- 测距流程
|
||||
- 官方校准函数
|
||||
- `PerformRefSpadManagement`
|
||||
- `PerformRefCalibration`
|
||||
- `PerformOffsetCalibration`
|
||||
- `PerformXTalkCalibration`
|
||||
|
||||
这部分一般不要随便改,除非明确要修改 ST 官方行为。
|
||||
|
||||
### `platform/`
|
||||
|
||||
这是我们自己写的兼容层,负责把 ST API 接到 STM32 工程里。
|
||||
|
||||
## 我们自己写的兼容层文件说明
|
||||
|
||||
### `platform/vl53l0x_platform.h`
|
||||
|
||||
平台适配层头文件。
|
||||
|
||||
主要作用:
|
||||
|
||||
- 声明和 STM32 平台相关的接口
|
||||
- 给 ST API 提供底层读写函数声明
|
||||
- 提供总线、GPIO、延时、地址切换相关接口声明
|
||||
|
||||
### `platform/vl53l0x_platform.c`
|
||||
|
||||
平台适配层实现。
|
||||
|
||||
主要作用:
|
||||
|
||||
- 对接 STM32 的 `HAL I2C`
|
||||
- 实现 VL53L0X 所需的寄存器读写
|
||||
- 绑定每颗传感器的 I2C 句柄和地址
|
||||
- 控制 `XSHUT`
|
||||
- 支持运行时改 I2C 地址
|
||||
|
||||
简单说,这一层负责把 ST API 的“平台无关接口”落到我们实际板子上。
|
||||
|
||||
### `platform/vl53_board.h`
|
||||
|
||||
板级管理层头文件。
|
||||
|
||||
主要作用:
|
||||
|
||||
- 定义多颗 VL53 共用的管理结构体
|
||||
- 定义快照结构 `Vl53BoardSnapshot_t`
|
||||
- 定义硬件配置结构 `Vl53BoardHwCfg_t`
|
||||
- 对外暴露板级接口,例如:
|
||||
- `Vl53Board_Init`
|
||||
- `Vl53Board_StartContinuous`
|
||||
- `Vl53Board_StopContinuous`
|
||||
- `Vl53Board_ReadAll`
|
||||
- 当前版本还扩展了校准相关数据结构和接口
|
||||
|
||||
这一层是“上层任务代码直接调用的 API”。
|
||||
|
||||
### `platform/vl53_board.c`
|
||||
|
||||
板级管理层实现。
|
||||
|
||||
主要作用:
|
||||
|
||||
- 管理一组 VL53 传感器
|
||||
- 完成多颗设备的上电、拉低/拉高 `XSHUT`、分配运行地址
|
||||
- 调 ST 官方初始化流程
|
||||
- 启动/停止连续测量
|
||||
- 轮询读取测距结果
|
||||
- 组织成统一快照给上层使用
|
||||
- 对每颗测距值做简单卡尔曼滤波
|
||||
|
||||
如果说 `vl53l0x_platform.c` 是“底层总线适配”,那 `vl53_board.c` 就是“更贴近业务的板级封装”。
|
||||
|
||||
### `platform/vl53_calibration_config.h`
|
||||
|
||||
这是我们自己加的运行时校准配置头。
|
||||
|
||||
主要作用:
|
||||
|
||||
- 集中保存已经确认过的校准值
|
||||
- 让上层在启动后把这些值写回 VL53
|
||||
|
||||
当前主要用于保存:
|
||||
|
||||
- `offset_micro_meters`
|
||||
- `xtalk_compensation_rate_mcps`
|
||||
- 对应的 `*_calibrated` 标志
|
||||
|
||||
这不是 ST 官方自带文件,是我们为了工程集成方便单独加的配置层。
|
||||
|
||||
### `platform/vl53l0x_types.h`
|
||||
|
||||
类型辅助头文件。
|
||||
|
||||
主要作用:
|
||||
|
||||
- 补充平台侧需要的公共类型定义
|
||||
- 给 `platform` 层做类型适配
|
||||
|
||||
### `platform/vl53l0x_platform_log.h`
|
||||
|
||||
日志相关兼容头。
|
||||
|
||||
主要作用:
|
||||
|
||||
- 兼容 ST API 的日志宏
|
||||
- 当前工程里基本属于轻量占位层
|
||||
|
||||
## 推荐修改边界
|
||||
|
||||
如果后续要继续改 VL53 集成,优先修改:
|
||||
|
||||
- `platform/vl53_board.c/.h`
|
||||
- `platform/vl53_calibration_config.h`
|
||||
|
||||
如果只是换板子、换 I2C、换 XSHUT 引脚,优先修改:
|
||||
|
||||
- `platform/vl53l0x_platform.c/.h`
|
||||
|
||||
如果不是明确要动 ST 官方行为,尽量不要去改:
|
||||
|
||||
- `core/`
|
||||
|
||||
## 一句话总结
|
||||
|
||||
我们自己写的兼容层分两层:
|
||||
|
||||
- `vl53l0x_platform.*`:把 ST API 接到 STM32 HAL
|
||||
- `vl53_board.*`:把多颗 VL53 封装成上层任务可直接使用的板级接口
|
||||
|
||||
而 `vl53_calibration_config.h` 是我们额外加的“运行时固定标定值配置文件”。
|
||||
BIN
App/VL53L0X_API/VL53L0X.pdf
Normal file
BIN
App/VL53L0X_API/VL53L0X.pdf
Normal file
Binary file not shown.
1926
App/VL53L0X_API/core/inc/vl53l0x_api.h
Normal file
1926
App/VL53L0X_API/core/inc/vl53l0x_api.h
Normal file
File diff suppressed because it is too large
Load Diff
85
App/VL53L0X_API/core/inc/vl53l0x_api_calibration.h
Normal file
85
App/VL53L0X_API/core/inc/vl53l0x_api_calibration.h
Normal file
@@ -0,0 +1,85 @@
|
||||
/*******************************************************************************
|
||||
* Copyright © 2016, STMicroelectronics International N.V.
|
||||
All rights reserved.
|
||||
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
* Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
* Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in the
|
||||
documentation and/or other materials provided with the distribution.
|
||||
* Neither the name of STMicroelectronics nor the
|
||||
names of its contributors may be used to endorse or promote products
|
||||
derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
|
||||
NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
|
||||
IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
|
||||
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
|
||||
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*******************************************************************************/
|
||||
|
||||
#ifndef _VL53L0X_API_CALIBRATION_H_
|
||||
#define _VL53L0X_API_CALIBRATION_H_
|
||||
|
||||
#include "vl53l0x_def.h"
|
||||
#include "vl53l0x_platform.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
VL53L0X_Error VL53L0X_perform_xtalk_calibration(VL53L0X_DEV Dev,
|
||||
FixPoint1616_t XTalkCalDistance,
|
||||
FixPoint1616_t *pXTalkCompensationRateMegaCps);
|
||||
|
||||
VL53L0X_Error VL53L0X_perform_offset_calibration(VL53L0X_DEV Dev,
|
||||
FixPoint1616_t CalDistanceMilliMeter,
|
||||
int32_t *pOffsetMicroMeter);
|
||||
|
||||
VL53L0X_Error VL53L0X_set_offset_calibration_data_micro_meter(VL53L0X_DEV Dev,
|
||||
int32_t OffsetCalibrationDataMicroMeter);
|
||||
|
||||
VL53L0X_Error VL53L0X_get_offset_calibration_data_micro_meter(VL53L0X_DEV Dev,
|
||||
int32_t *pOffsetCalibrationDataMicroMeter);
|
||||
|
||||
VL53L0X_Error VL53L0X_apply_offset_adjustment(VL53L0X_DEV Dev);
|
||||
|
||||
VL53L0X_Error VL53L0X_perform_ref_spad_management(VL53L0X_DEV Dev,
|
||||
uint32_t *refSpadCount, uint8_t *isApertureSpads);
|
||||
|
||||
VL53L0X_Error VL53L0X_set_reference_spads(VL53L0X_DEV Dev,
|
||||
uint32_t count, uint8_t isApertureSpads);
|
||||
|
||||
VL53L0X_Error VL53L0X_get_reference_spads(VL53L0X_DEV Dev,
|
||||
uint32_t *pSpadCount, uint8_t *pIsApertureSpads);
|
||||
|
||||
VL53L0X_Error VL53L0X_perform_phase_calibration(VL53L0X_DEV Dev,
|
||||
uint8_t *pPhaseCal, const uint8_t get_data_enable,
|
||||
const uint8_t restore_config);
|
||||
|
||||
VL53L0X_Error VL53L0X_perform_ref_calibration(VL53L0X_DEV Dev,
|
||||
uint8_t *pVhvSettings, uint8_t *pPhaseCal, uint8_t get_data_enable);
|
||||
|
||||
VL53L0X_Error VL53L0X_set_ref_calibration(VL53L0X_DEV Dev,
|
||||
uint8_t VhvSettings, uint8_t PhaseCal);
|
||||
|
||||
VL53L0X_Error VL53L0X_get_ref_calibration(VL53L0X_DEV Dev,
|
||||
uint8_t *pVhvSettings, uint8_t *pPhaseCal);
|
||||
|
||||
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* _VL53L0X_API_CALIBRATION_H_ */
|
||||
113
App/VL53L0X_API/core/inc/vl53l0x_api_core.h
Normal file
113
App/VL53L0X_API/core/inc/vl53l0x_api_core.h
Normal file
@@ -0,0 +1,113 @@
|
||||
/*******************************************************************************
|
||||
* Copyright © 2016, STMicroelectronics International N.V.
|
||||
All rights reserved.
|
||||
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
* Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
* Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in the
|
||||
documentation and/or other materials provided with the distribution.
|
||||
* Neither the name of STMicroelectronics nor the
|
||||
names of its contributors may be used to endorse or promote products
|
||||
derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
|
||||
NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
|
||||
IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
|
||||
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
|
||||
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*******************************************************************************/
|
||||
|
||||
#ifndef _VL53L0X_API_CORE_H_
|
||||
#define _VL53L0X_API_CORE_H_
|
||||
|
||||
#include "vl53l0x_def.h"
|
||||
#include "vl53l0x_platform.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
|
||||
VL53L0X_Error VL53L0X_reverse_bytes(uint8_t *data, uint32_t size);
|
||||
|
||||
VL53L0X_Error VL53L0X_measurement_poll_for_completion(VL53L0X_DEV Dev);
|
||||
|
||||
uint8_t VL53L0X_encode_vcsel_period(uint8_t vcsel_period_pclks);
|
||||
|
||||
uint8_t VL53L0X_decode_vcsel_period(uint8_t vcsel_period_reg);
|
||||
|
||||
uint32_t VL53L0X_isqrt(uint32_t num);
|
||||
|
||||
uint32_t VL53L0X_quadrature_sum(uint32_t a, uint32_t b);
|
||||
|
||||
VL53L0X_Error VL53L0X_get_info_from_device(VL53L0X_DEV Dev, uint8_t option);
|
||||
|
||||
VL53L0X_Error VL53L0X_set_vcsel_pulse_period(VL53L0X_DEV Dev,
|
||||
VL53L0X_VcselPeriod VcselPeriodType, uint8_t VCSELPulsePeriodPCLK);
|
||||
|
||||
VL53L0X_Error VL53L0X_get_vcsel_pulse_period(VL53L0X_DEV Dev,
|
||||
VL53L0X_VcselPeriod VcselPeriodType, uint8_t *pVCSELPulsePeriodPCLK);
|
||||
|
||||
uint32_t VL53L0X_decode_timeout(uint16_t encoded_timeout);
|
||||
|
||||
VL53L0X_Error get_sequence_step_timeout(VL53L0X_DEV Dev,
|
||||
VL53L0X_SequenceStepId SequenceStepId,
|
||||
uint32_t *pTimeOutMicroSecs);
|
||||
|
||||
VL53L0X_Error set_sequence_step_timeout(VL53L0X_DEV Dev,
|
||||
VL53L0X_SequenceStepId SequenceStepId,
|
||||
uint32_t TimeOutMicroSecs);
|
||||
|
||||
VL53L0X_Error VL53L0X_set_measurement_timing_budget_micro_seconds(
|
||||
VL53L0X_DEV Dev,
|
||||
uint32_t MeasurementTimingBudgetMicroSeconds);
|
||||
|
||||
VL53L0X_Error VL53L0X_get_measurement_timing_budget_micro_seconds(
|
||||
VL53L0X_DEV Dev,
|
||||
uint32_t *pMeasurementTimingBudgetMicroSeconds);
|
||||
|
||||
VL53L0X_Error VL53L0X_load_tuning_settings(VL53L0X_DEV Dev,
|
||||
uint8_t *pTuningSettingBuffer);
|
||||
|
||||
VL53L0X_Error VL53L0X_calc_sigma_estimate(VL53L0X_DEV Dev,
|
||||
VL53L0X_RangingMeasurementData_t *pRangingMeasurementData,
|
||||
FixPoint1616_t *pSigmaEstimate);
|
||||
|
||||
VL53L0X_Error VL53L0X_calc_dmax(
|
||||
VL53L0X_DEV Dev, FixPoint1616_t ambRateMeas, uint32_t *pdmax_mm);
|
||||
|
||||
VL53L0X_Error VL53L0X_get_total_xtalk_rate(VL53L0X_DEV Dev,
|
||||
VL53L0X_RangingMeasurementData_t *pRangingMeasurementData,
|
||||
FixPoint1616_t *ptotal_xtalk_rate_mcps);
|
||||
|
||||
VL53L0X_Error VL53L0X_get_total_signal_rate(VL53L0X_DEV Dev,
|
||||
VL53L0X_RangingMeasurementData_t *pRangingMeasurementData,
|
||||
FixPoint1616_t *ptotal_signal_rate_mcps);
|
||||
|
||||
VL53L0X_Error VL53L0X_get_pal_range_status(VL53L0X_DEV Dev,
|
||||
uint8_t DeviceRangeStatus,
|
||||
FixPoint1616_t SignalRate,
|
||||
uint16_t EffectiveSpadRtnCount,
|
||||
VL53L0X_RangingMeasurementData_t *pRangingMeasurementData,
|
||||
uint8_t *pPalRangeStatus);
|
||||
|
||||
uint32_t VL53L0X_calc_timeout_mclks(VL53L0X_DEV Dev,
|
||||
uint32_t timeout_period_us, uint8_t vcsel_period_pclks);
|
||||
|
||||
uint16_t VL53L0X_encode_timeout(uint32_t timeout_macro_clks);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* _VL53L0X_API_CORE_H_ */
|
||||
47
App/VL53L0X_API/core/inc/vl53l0x_api_ranging.h
Normal file
47
App/VL53L0X_API/core/inc/vl53l0x_api_ranging.h
Normal file
@@ -0,0 +1,47 @@
|
||||
/*******************************************************************************
|
||||
* Copyright © 2016, STMicroelectronics International N.V.
|
||||
All rights reserved.
|
||||
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
* Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
* Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in the
|
||||
documentation and/or other materials provided with the distribution.
|
||||
* Neither the name of STMicroelectronics nor the
|
||||
names of its contributors may be used to endorse or promote products
|
||||
derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
|
||||
NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
|
||||
IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
|
||||
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
|
||||
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*******************************************************************************/
|
||||
|
||||
#ifndef _VL53L0X_API_RANGING_H_
|
||||
#define _VL53L0X_API_RANGING_H_
|
||||
|
||||
#include "vl53l0x_def.h"
|
||||
#include "vl53l0x_platform.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* _VL53L0X_API_RANGING_H_ */
|
||||
278
App/VL53L0X_API/core/inc/vl53l0x_api_strings.h
Normal file
278
App/VL53L0X_API/core/inc/vl53l0x_api_strings.h
Normal file
@@ -0,0 +1,278 @@
|
||||
/*******************************************************************************
|
||||
* Copyright © 2016, STMicroelectronics International N.V.
|
||||
All rights reserved.
|
||||
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
* Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
* Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in the
|
||||
documentation and/or other materials provided with the distribution.
|
||||
* Neither the name of STMicroelectronics nor the
|
||||
names of its contributors may be used to endorse or promote products
|
||||
derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
|
||||
NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
|
||||
IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
|
||||
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
|
||||
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*******************************************************************************/
|
||||
|
||||
#ifndef VL53L0X_API_STRINGS_H_
|
||||
#define VL53L0X_API_STRINGS_H_
|
||||
|
||||
#include "vl53l0x_def.h"
|
||||
#include "vl53l0x_platform.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
|
||||
VL53L0X_Error VL53L0X_get_device_info(VL53L0X_DEV Dev,
|
||||
VL53L0X_DeviceInfo_t *pVL53L0X_DeviceInfo);
|
||||
|
||||
VL53L0X_Error VL53L0X_get_device_error_string(VL53L0X_DeviceError ErrorCode,
|
||||
char *pDeviceErrorString);
|
||||
|
||||
VL53L0X_Error VL53L0X_get_range_status_string(uint8_t RangeStatus,
|
||||
char *pRangeStatusString);
|
||||
|
||||
VL53L0X_Error VL53L0X_get_pal_error_string(VL53L0X_Error PalErrorCode,
|
||||
char *pPalErrorString);
|
||||
|
||||
VL53L0X_Error VL53L0X_get_pal_state_string(VL53L0X_State PalStateCode,
|
||||
char *pPalStateString);
|
||||
|
||||
VL53L0X_Error VL53L0X_get_sequence_steps_info(
|
||||
VL53L0X_SequenceStepId SequenceStepId,
|
||||
char *pSequenceStepsString);
|
||||
|
||||
VL53L0X_Error VL53L0X_get_limit_check_info(VL53L0X_DEV Dev,
|
||||
uint16_t LimitCheckId,
|
||||
char *pLimitCheckString);
|
||||
|
||||
|
||||
#ifdef USE_EMPTY_STRING
|
||||
#define VL53L0X_STRING_DEVICE_INFO_NAME ""
|
||||
#define VL53L0X_STRING_DEVICE_INFO_NAME_TS0 ""
|
||||
#define VL53L0X_STRING_DEVICE_INFO_NAME_TS1 ""
|
||||
#define VL53L0X_STRING_DEVICE_INFO_NAME_TS2 ""
|
||||
#define VL53L0X_STRING_DEVICE_INFO_NAME_ES1 ""
|
||||
#define VL53L0X_STRING_DEVICE_INFO_TYPE ""
|
||||
|
||||
/* PAL ERROR strings */
|
||||
#define VL53L0X_STRING_ERROR_NONE ""
|
||||
#define VL53L0X_STRING_ERROR_CALIBRATION_WARNING ""
|
||||
#define VL53L0X_STRING_ERROR_MIN_CLIPPED ""
|
||||
#define VL53L0X_STRING_ERROR_UNDEFINED ""
|
||||
#define VL53L0X_STRING_ERROR_INVALID_PARAMS ""
|
||||
#define VL53L0X_STRING_ERROR_NOT_SUPPORTED ""
|
||||
#define VL53L0X_STRING_ERROR_RANGE_ERROR ""
|
||||
#define VL53L0X_STRING_ERROR_TIME_OUT ""
|
||||
#define VL53L0X_STRING_ERROR_MODE_NOT_SUPPORTED ""
|
||||
#define VL53L0X_STRING_ERROR_BUFFER_TOO_SMALL ""
|
||||
#define VL53L0X_STRING_ERROR_GPIO_NOT_EXISTING ""
|
||||
#define VL53L0X_STRING_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED ""
|
||||
#define VL53L0X_STRING_ERROR_CONTROL_INTERFACE ""
|
||||
#define VL53L0X_STRING_ERROR_INVALID_COMMAND ""
|
||||
#define VL53L0X_STRING_ERROR_DIVISION_BY_ZERO ""
|
||||
#define VL53L0X_STRING_ERROR_REF_SPAD_INIT ""
|
||||
#define VL53L0X_STRING_ERROR_NOT_IMPLEMENTED ""
|
||||
|
||||
#define VL53L0X_STRING_UNKNOW_ERROR_CODE ""
|
||||
|
||||
|
||||
|
||||
/* Range Status */
|
||||
#define VL53L0X_STRING_RANGESTATUS_NONE ""
|
||||
#define VL53L0X_STRING_RANGESTATUS_RANGEVALID ""
|
||||
#define VL53L0X_STRING_RANGESTATUS_SIGMA ""
|
||||
#define VL53L0X_STRING_RANGESTATUS_SIGNAL ""
|
||||
#define VL53L0X_STRING_RANGESTATUS_MINRANGE ""
|
||||
#define VL53L0X_STRING_RANGESTATUS_PHASE ""
|
||||
#define VL53L0X_STRING_RANGESTATUS_HW ""
|
||||
|
||||
|
||||
/* Range Status */
|
||||
#define VL53L0X_STRING_STATE_POWERDOWN ""
|
||||
#define VL53L0X_STRING_STATE_WAIT_STATICINIT ""
|
||||
#define VL53L0X_STRING_STATE_STANDBY ""
|
||||
#define VL53L0X_STRING_STATE_IDLE ""
|
||||
#define VL53L0X_STRING_STATE_RUNNING ""
|
||||
#define VL53L0X_STRING_STATE_UNKNOWN ""
|
||||
#define VL53L0X_STRING_STATE_ERROR ""
|
||||
|
||||
|
||||
/* Device Specific */
|
||||
#define VL53L0X_STRING_DEVICEERROR_NONE ""
|
||||
#define VL53L0X_STRING_DEVICEERROR_VCSELCONTINUITYTESTFAILURE ""
|
||||
#define VL53L0X_STRING_DEVICEERROR_VCSELWATCHDOGTESTFAILURE ""
|
||||
#define VL53L0X_STRING_DEVICEERROR_NOVHVVALUEFOUND ""
|
||||
#define VL53L0X_STRING_DEVICEERROR_MSRCNOTARGET ""
|
||||
#define VL53L0X_STRING_DEVICEERROR_SNRCHECK ""
|
||||
#define VL53L0X_STRING_DEVICEERROR_RANGEPHASECHECK ""
|
||||
#define VL53L0X_STRING_DEVICEERROR_SIGMATHRESHOLDCHECK ""
|
||||
#define VL53L0X_STRING_DEVICEERROR_TCC ""
|
||||
#define VL53L0X_STRING_DEVICEERROR_PHASECONSISTENCY ""
|
||||
#define VL53L0X_STRING_DEVICEERROR_MINCLIP ""
|
||||
#define VL53L0X_STRING_DEVICEERROR_RANGECOMPLETE ""
|
||||
#define VL53L0X_STRING_DEVICEERROR_ALGOUNDERFLOW ""
|
||||
#define VL53L0X_STRING_DEVICEERROR_ALGOOVERFLOW ""
|
||||
#define VL53L0X_STRING_DEVICEERROR_RANGEIGNORETHRESHOLD ""
|
||||
#define VL53L0X_STRING_DEVICEERROR_UNKNOWN ""
|
||||
|
||||
/* Check Enable */
|
||||
#define VL53L0X_STRING_CHECKENABLE_SIGMA_FINAL_RANGE ""
|
||||
#define VL53L0X_STRING_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE ""
|
||||
#define VL53L0X_STRING_CHECKENABLE_SIGNAL_REF_CLIP ""
|
||||
#define VL53L0X_STRING_CHECKENABLE_RANGE_IGNORE_THRESHOLD ""
|
||||
|
||||
/* Sequence Step */
|
||||
#define VL53L0X_STRING_SEQUENCESTEP_TCC ""
|
||||
#define VL53L0X_STRING_SEQUENCESTEP_DSS ""
|
||||
#define VL53L0X_STRING_SEQUENCESTEP_MSRC ""
|
||||
#define VL53L0X_STRING_SEQUENCESTEP_PRE_RANGE ""
|
||||
#define VL53L0X_STRING_SEQUENCESTEP_FINAL_RANGE ""
|
||||
#else
|
||||
#define VL53L0X_STRING_DEVICE_INFO_NAME "VL53L0X cut1.0"
|
||||
#define VL53L0X_STRING_DEVICE_INFO_NAME_TS0 "VL53L0X TS0"
|
||||
#define VL53L0X_STRING_DEVICE_INFO_NAME_TS1 "VL53L0X TS1"
|
||||
#define VL53L0X_STRING_DEVICE_INFO_NAME_TS2 "VL53L0X TS2"
|
||||
#define VL53L0X_STRING_DEVICE_INFO_NAME_ES1 "VL53L0X ES1 or later"
|
||||
#define VL53L0X_STRING_DEVICE_INFO_TYPE "VL53L0X"
|
||||
|
||||
/* PAL ERROR strings */
|
||||
#define VL53L0X_STRING_ERROR_NONE \
|
||||
"No Error"
|
||||
#define VL53L0X_STRING_ERROR_CALIBRATION_WARNING \
|
||||
"Calibration Warning Error"
|
||||
#define VL53L0X_STRING_ERROR_MIN_CLIPPED \
|
||||
"Min clipped error"
|
||||
#define VL53L0X_STRING_ERROR_UNDEFINED \
|
||||
"Undefined error"
|
||||
#define VL53L0X_STRING_ERROR_INVALID_PARAMS \
|
||||
"Invalid parameters error"
|
||||
#define VL53L0X_STRING_ERROR_NOT_SUPPORTED \
|
||||
"Not supported error"
|
||||
#define VL53L0X_STRING_ERROR_RANGE_ERROR \
|
||||
"Range error"
|
||||
#define VL53L0X_STRING_ERROR_TIME_OUT \
|
||||
"Time out error"
|
||||
#define VL53L0X_STRING_ERROR_MODE_NOT_SUPPORTED \
|
||||
"Mode not supported error"
|
||||
#define VL53L0X_STRING_ERROR_BUFFER_TOO_SMALL \
|
||||
"Buffer too small"
|
||||
#define VL53L0X_STRING_ERROR_GPIO_NOT_EXISTING \
|
||||
"GPIO not existing"
|
||||
#define VL53L0X_STRING_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED \
|
||||
"GPIO funct not supported"
|
||||
#define VL53L0X_STRING_ERROR_INTERRUPT_NOT_CLEARED \
|
||||
"Interrupt not Cleared"
|
||||
#define VL53L0X_STRING_ERROR_CONTROL_INTERFACE \
|
||||
"Control Interface Error"
|
||||
#define VL53L0X_STRING_ERROR_INVALID_COMMAND \
|
||||
"Invalid Command Error"
|
||||
#define VL53L0X_STRING_ERROR_DIVISION_BY_ZERO \
|
||||
"Division by zero Error"
|
||||
#define VL53L0X_STRING_ERROR_REF_SPAD_INIT \
|
||||
"Reference Spad Init Error"
|
||||
#define VL53L0X_STRING_ERROR_NOT_IMPLEMENTED \
|
||||
"Not implemented error"
|
||||
|
||||
#define VL53L0X_STRING_UNKNOW_ERROR_CODE \
|
||||
"Unknown Error Code"
|
||||
|
||||
|
||||
|
||||
/* Range Status */
|
||||
#define VL53L0X_STRING_RANGESTATUS_NONE "No Update"
|
||||
#define VL53L0X_STRING_RANGESTATUS_RANGEVALID "Range Valid"
|
||||
#define VL53L0X_STRING_RANGESTATUS_SIGMA "Sigma Fail"
|
||||
#define VL53L0X_STRING_RANGESTATUS_SIGNAL "Signal Fail"
|
||||
#define VL53L0X_STRING_RANGESTATUS_MINRANGE "Min Range Fail"
|
||||
#define VL53L0X_STRING_RANGESTATUS_PHASE "Phase Fail"
|
||||
#define VL53L0X_STRING_RANGESTATUS_HW "Hardware Fail"
|
||||
|
||||
|
||||
/* Range Status */
|
||||
#define VL53L0X_STRING_STATE_POWERDOWN "POWERDOWN State"
|
||||
#define VL53L0X_STRING_STATE_WAIT_STATICINIT \
|
||||
"Wait for staticinit State"
|
||||
#define VL53L0X_STRING_STATE_STANDBY "STANDBY State"
|
||||
#define VL53L0X_STRING_STATE_IDLE "IDLE State"
|
||||
#define VL53L0X_STRING_STATE_RUNNING "RUNNING State"
|
||||
#define VL53L0X_STRING_STATE_UNKNOWN "UNKNOWN State"
|
||||
#define VL53L0X_STRING_STATE_ERROR "ERROR State"
|
||||
|
||||
|
||||
/* Device Specific */
|
||||
#define VL53L0X_STRING_DEVICEERROR_NONE "No Update"
|
||||
#define VL53L0X_STRING_DEVICEERROR_VCSELCONTINUITYTESTFAILURE \
|
||||
"VCSEL Continuity Test Failure"
|
||||
#define VL53L0X_STRING_DEVICEERROR_VCSELWATCHDOGTESTFAILURE \
|
||||
"VCSEL Watchdog Test Failure"
|
||||
#define VL53L0X_STRING_DEVICEERROR_NOVHVVALUEFOUND \
|
||||
"No VHV Value found"
|
||||
#define VL53L0X_STRING_DEVICEERROR_MSRCNOTARGET \
|
||||
"MSRC No Target Error"
|
||||
#define VL53L0X_STRING_DEVICEERROR_SNRCHECK \
|
||||
"SNR Check Exit"
|
||||
#define VL53L0X_STRING_DEVICEERROR_RANGEPHASECHECK \
|
||||
"Range Phase Check Error"
|
||||
#define VL53L0X_STRING_DEVICEERROR_SIGMATHRESHOLDCHECK \
|
||||
"Sigma Threshold Check Error"
|
||||
#define VL53L0X_STRING_DEVICEERROR_TCC \
|
||||
"TCC Error"
|
||||
#define VL53L0X_STRING_DEVICEERROR_PHASECONSISTENCY \
|
||||
"Phase Consistency Error"
|
||||
#define VL53L0X_STRING_DEVICEERROR_MINCLIP \
|
||||
"Min Clip Error"
|
||||
#define VL53L0X_STRING_DEVICEERROR_RANGECOMPLETE \
|
||||
"Range Complete"
|
||||
#define VL53L0X_STRING_DEVICEERROR_ALGOUNDERFLOW \
|
||||
"Range Algo Underflow Error"
|
||||
#define VL53L0X_STRING_DEVICEERROR_ALGOOVERFLOW \
|
||||
"Range Algo Overlow Error"
|
||||
#define VL53L0X_STRING_DEVICEERROR_RANGEIGNORETHRESHOLD \
|
||||
"Range Ignore Threshold Error"
|
||||
#define VL53L0X_STRING_DEVICEERROR_UNKNOWN \
|
||||
"Unknown error code"
|
||||
|
||||
/* Check Enable */
|
||||
#define VL53L0X_STRING_CHECKENABLE_SIGMA_FINAL_RANGE \
|
||||
"SIGMA FINAL RANGE"
|
||||
#define VL53L0X_STRING_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE \
|
||||
"SIGNAL RATE FINAL RANGE"
|
||||
#define VL53L0X_STRING_CHECKENABLE_SIGNAL_REF_CLIP \
|
||||
"SIGNAL REF CLIP"
|
||||
#define VL53L0X_STRING_CHECKENABLE_RANGE_IGNORE_THRESHOLD \
|
||||
"RANGE IGNORE THRESHOLD"
|
||||
#define VL53L0X_STRING_CHECKENABLE_SIGNAL_RATE_MSRC \
|
||||
"SIGNAL RATE MSRC"
|
||||
#define VL53L0X_STRING_CHECKENABLE_SIGNAL_RATE_PRE_RANGE \
|
||||
"SIGNAL RATE PRE RANGE"
|
||||
|
||||
/* Sequence Step */
|
||||
#define VL53L0X_STRING_SEQUENCESTEP_TCC "TCC"
|
||||
#define VL53L0X_STRING_SEQUENCESTEP_DSS "DSS"
|
||||
#define VL53L0X_STRING_SEQUENCESTEP_MSRC "MSRC"
|
||||
#define VL53L0X_STRING_SEQUENCESTEP_PRE_RANGE "PRE RANGE"
|
||||
#define VL53L0X_STRING_SEQUENCESTEP_FINAL_RANGE "FINAL RANGE"
|
||||
#endif /* USE_EMPTY_STRING */
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
666
App/VL53L0X_API/core/inc/vl53l0x_def.h
Normal file
666
App/VL53L0X_API/core/inc/vl53l0x_def.h
Normal file
@@ -0,0 +1,666 @@
|
||||
/*******************************************************************************
|
||||
* Copyright <20> 2016, STMicroelectronics International N.V.
|
||||
All rights reserved.
|
||||
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
* Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
* Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in the
|
||||
documentation and/or other materials provided with the distribution.
|
||||
* Neither the name of STMicroelectronics nor the
|
||||
names of its contributors may be used to endorse or promote products
|
||||
derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
|
||||
NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
|
||||
IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
|
||||
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
|
||||
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*******************************************************************************/
|
||||
|
||||
/**
|
||||
* @file VL53L0X_def.h
|
||||
*
|
||||
* @brief Type definitions for VL53L0X API.
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#ifndef _VL53L0X_DEF_H_
|
||||
#define _VL53L0X_DEF_H_
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/** @defgroup VL53L0X_globaldefine_group VL53L0X Defines
|
||||
* @brief VL53L0X Defines
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/** PAL SPECIFICATION major version */
|
||||
#define VL53L0X10_SPECIFICATION_VER_MAJOR 1
|
||||
/** PAL SPECIFICATION minor version */
|
||||
#define VL53L0X10_SPECIFICATION_VER_MINOR 2
|
||||
/** PAL SPECIFICATION sub version */
|
||||
#define VL53L0X10_SPECIFICATION_VER_SUB 7
|
||||
/** PAL SPECIFICATION sub version */
|
||||
#define VL53L0X10_SPECIFICATION_VER_REVISION 1440
|
||||
|
||||
/** VL53L0X PAL IMPLEMENTATION major version */
|
||||
#define VL53L0X10_IMPLEMENTATION_VER_MAJOR 1
|
||||
/** VL53L0X PAL IMPLEMENTATION minor version */
|
||||
#define VL53L0X10_IMPLEMENTATION_VER_MINOR 0
|
||||
/** VL53L0X PAL IMPLEMENTATION sub version */
|
||||
#define VL53L0X10_IMPLEMENTATION_VER_SUB 9
|
||||
/** VL53L0X PAL IMPLEMENTATION sub version */
|
||||
#define VL53L0X10_IMPLEMENTATION_VER_REVISION 3673
|
||||
|
||||
/** PAL SPECIFICATION major version */
|
||||
#define VL53L0X_SPECIFICATION_VER_MAJOR 1
|
||||
/** PAL SPECIFICATION minor version */
|
||||
#define VL53L0X_SPECIFICATION_VER_MINOR 2
|
||||
/** PAL SPECIFICATION sub version */
|
||||
#define VL53L0X_SPECIFICATION_VER_SUB 7
|
||||
/** PAL SPECIFICATION sub version */
|
||||
#define VL53L0X_SPECIFICATION_VER_REVISION 1440
|
||||
|
||||
/** VL53L0X PAL IMPLEMENTATION major version */
|
||||
#define VL53L0X_IMPLEMENTATION_VER_MAJOR 1
|
||||
/** VL53L0X PAL IMPLEMENTATION minor version */
|
||||
#define VL53L0X_IMPLEMENTATION_VER_MINOR 0
|
||||
/** VL53L0X PAL IMPLEMENTATION sub version */
|
||||
#define VL53L0X_IMPLEMENTATION_VER_SUB 4
|
||||
/** VL53L0X PAL IMPLEMENTATION sub version */
|
||||
#define VL53L0X_IMPLEMENTATION_VER_REVISION 4960
|
||||
#define VL53L0X_DEFAULT_MAX_LOOP 2000
|
||||
#define VL53L0X_MAX_STRING_LENGTH 32
|
||||
|
||||
|
||||
#include "vl53l0x_device.h"
|
||||
#include "vl53l0x_types.h"
|
||||
|
||||
|
||||
/****************************************
|
||||
* PRIVATE define do not edit
|
||||
****************************************/
|
||||
|
||||
/** @brief Defines the parameters of the Get Version Functions
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t revision; /*!< revision number */
|
||||
uint8_t major; /*!< major number */
|
||||
uint8_t minor; /*!< minor number */
|
||||
uint8_t build; /*!< build number */
|
||||
} VL53L0X_Version_t;
|
||||
|
||||
|
||||
/** @brief Defines the parameters of the Get Device Info Functions
|
||||
*/
|
||||
typedef struct {
|
||||
char Name[VL53L0X_MAX_STRING_LENGTH];
|
||||
/*!< Name of the Device e.g. Left_Distance */
|
||||
char Type[VL53L0X_MAX_STRING_LENGTH];
|
||||
/*!< Type of the Device e.g VL53L0X */
|
||||
char ProductId[VL53L0X_MAX_STRING_LENGTH];
|
||||
/*!< Product Identifier String */
|
||||
uint8_t ProductType;
|
||||
/*!< Product Type, VL53L0X = 1, VL53L1 = 2 */
|
||||
uint8_t ProductRevisionMajor;
|
||||
/*!< Product revision major */
|
||||
uint8_t ProductRevisionMinor;
|
||||
/*!< Product revision minor */
|
||||
} VL53L0X_DeviceInfo_t;
|
||||
|
||||
|
||||
/** @defgroup VL53L0X_define_Error_group Error and Warning code returned by API
|
||||
* The following DEFINE are used to identify the PAL ERROR
|
||||
* @{
|
||||
*/
|
||||
|
||||
typedef int8_t VL53L0X_Error;
|
||||
|
||||
#define VL53L0X_ERROR_NONE ((VL53L0X_Error) 0)
|
||||
#define VL53L0X_ERROR_CALIBRATION_WARNING ((VL53L0X_Error) - 1)
|
||||
/*!< Warning invalid calibration data may be in used
|
||||
* \a VL53L0X_InitData()
|
||||
* \a VL53L0X_GetOffsetCalibrationData
|
||||
* \a VL53L0X_SetOffsetCalibrationData
|
||||
*/
|
||||
#define VL53L0X_ERROR_MIN_CLIPPED ((VL53L0X_Error) - 2)
|
||||
/*!< Warning parameter passed was clipped to min before to be applied */
|
||||
|
||||
#define VL53L0X_ERROR_UNDEFINED ((VL53L0X_Error) - 3)
|
||||
/*!< Unqualified error */
|
||||
#define VL53L0X_ERROR_INVALID_PARAMS ((VL53L0X_Error) - 4)
|
||||
/*!< Parameter passed is invalid or out of range */
|
||||
#define VL53L0X_ERROR_NOT_SUPPORTED ((VL53L0X_Error) - 5)
|
||||
/*!< Function is not supported in current mode or configuration */
|
||||
#define VL53L0X_ERROR_RANGE_ERROR ((VL53L0X_Error) - 6)
|
||||
/*!< Device report a ranging error interrupt status */
|
||||
#define VL53L0X_ERROR_TIME_OUT ((VL53L0X_Error) - 7)
|
||||
/*!< Aborted due to time out */
|
||||
#define VL53L0X_ERROR_MODE_NOT_SUPPORTED ((VL53L0X_Error) - 8)
|
||||
/*!< Asked mode is not supported by the device */
|
||||
#define VL53L0X_ERROR_BUFFER_TOO_SMALL ((VL53L0X_Error) - 9)
|
||||
/*!< ... */
|
||||
#define VL53L0X_ERROR_GPIO_NOT_EXISTING ((VL53L0X_Error) - 10)
|
||||
/*!< User tried to setup a non-existing GPIO pin */
|
||||
#define VL53L0X_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED ((VL53L0X_Error) - 11)
|
||||
/*!< unsupported GPIO functionality */
|
||||
#define VL53L0X_ERROR_INTERRUPT_NOT_CLEARED ((VL53L0X_Error) - 12)
|
||||
/*!< Error during interrupt clear */
|
||||
#define VL53L0X_ERROR_CONTROL_INTERFACE ((VL53L0X_Error) - 20)
|
||||
/*!< error reported from IO functions */
|
||||
#define VL53L0X_ERROR_INVALID_COMMAND ((VL53L0X_Error) - 30)
|
||||
/*!< The command is not allowed in the current device state
|
||||
* (power down)
|
||||
*/
|
||||
#define VL53L0X_ERROR_DIVISION_BY_ZERO ((VL53L0X_Error) - 40)
|
||||
/*!< In the function a division by zero occurs */
|
||||
#define VL53L0X_ERROR_REF_SPAD_INIT ((VL53L0X_Error) - 50)
|
||||
/*!< Error during reference SPAD initialization */
|
||||
#define VL53L0X_ERROR_NOT_IMPLEMENTED ((VL53L0X_Error) - 99)
|
||||
/*!< Tells requested functionality has not been implemented yet or
|
||||
* not compatible with the device
|
||||
*/
|
||||
/** @} VL53L0X_define_Error_group */
|
||||
|
||||
|
||||
/** @defgroup VL53L0X_define_DeviceModes_group Defines Device modes
|
||||
* Defines all possible modes for the device
|
||||
* @{
|
||||
*/
|
||||
typedef uint8_t VL53L0X_DeviceModes;
|
||||
|
||||
#define VL53L0X_DEVICEMODE_SINGLE_RANGING ((VL53L0X_DeviceModes) 0)
|
||||
#define VL53L0X_DEVICEMODE_CONTINUOUS_RANGING ((VL53L0X_DeviceModes) 1)
|
||||
#define VL53L0X_DEVICEMODE_SINGLE_HISTOGRAM ((VL53L0X_DeviceModes) 2)
|
||||
#define VL53L0X_DEVICEMODE_CONTINUOUS_TIMED_RANGING ((VL53L0X_DeviceModes) 3)
|
||||
#define VL53L0X_DEVICEMODE_SINGLE_ALS ((VL53L0X_DeviceModes) 10)
|
||||
#define VL53L0X_DEVICEMODE_GPIO_DRIVE ((VL53L0X_DeviceModes) 20)
|
||||
#define VL53L0X_DEVICEMODE_GPIO_OSC ((VL53L0X_DeviceModes) 21)
|
||||
/* ... Modes to be added depending on device */
|
||||
/** @} VL53L0X_define_DeviceModes_group */
|
||||
|
||||
|
||||
|
||||
/** @defgroup VL53L0X_define_HistogramModes_group Defines Histogram modes
|
||||
* Defines all possible Histogram modes for the device
|
||||
* @{
|
||||
*/
|
||||
typedef uint8_t VL53L0X_HistogramModes;
|
||||
|
||||
#define VL53L0X_HISTOGRAMMODE_DISABLED ((VL53L0X_HistogramModes) 0)
|
||||
/*!< Histogram Disabled */
|
||||
#define VL53L0X_HISTOGRAMMODE_REFERENCE_ONLY ((VL53L0X_HistogramModes) 1)
|
||||
/*!< Histogram Reference array only */
|
||||
#define VL53L0X_HISTOGRAMMODE_RETURN_ONLY ((VL53L0X_HistogramModes) 2)
|
||||
/*!< Histogram Return array only */
|
||||
#define VL53L0X_HISTOGRAMMODE_BOTH ((VL53L0X_HistogramModes) 3)
|
||||
/*!< Histogram both Reference and Return Arrays */
|
||||
/* ... Modes to be added depending on device */
|
||||
/** @} VL53L0X_define_HistogramModes_group */
|
||||
|
||||
|
||||
/** @defgroup VL53L0X_define_PowerModes_group List of available Power Modes
|
||||
* List of available Power Modes
|
||||
* @{
|
||||
*/
|
||||
|
||||
typedef uint8_t VL53L0X_PowerModes;
|
||||
|
||||
#define VL53L0X_POWERMODE_STANDBY_LEVEL1 ((VL53L0X_PowerModes) 0)
|
||||
/*!< Standby level 1 */
|
||||
#define VL53L0X_POWERMODE_STANDBY_LEVEL2 ((VL53L0X_PowerModes) 1)
|
||||
/*!< Standby level 2 */
|
||||
#define VL53L0X_POWERMODE_IDLE_LEVEL1 ((VL53L0X_PowerModes) 2)
|
||||
/*!< Idle level 1 */
|
||||
#define VL53L0X_POWERMODE_IDLE_LEVEL2 ((VL53L0X_PowerModes) 3)
|
||||
/*!< Idle level 2 */
|
||||
|
||||
/** @} VL53L0X_define_PowerModes_group */
|
||||
|
||||
|
||||
#define VL53L0X_DMAX_LUT_SIZE 7
|
||||
/*!< Defines the number of items in the DMAX lookup table */
|
||||
|
||||
/** @brief Structure defining data pair that makes up the DMAX Lookup table.
|
||||
*/
|
||||
typedef struct {
|
||||
FixPoint1616_t ambRate_mcps[VL53L0X_DMAX_LUT_SIZE];
|
||||
/*!< Ambient rate (mcps) */
|
||||
FixPoint1616_t dmax_mm[VL53L0X_DMAX_LUT_SIZE];
|
||||
/*!< DMAX Value (mm) */
|
||||
} VL53L0X_DMaxLUT_t;
|
||||
|
||||
/** @brief Defines all parameters for the device
|
||||
*/
|
||||
typedef struct {
|
||||
VL53L0X_DeviceModes DeviceMode;
|
||||
/*!< Defines type of measurement to be done for the next measure */
|
||||
VL53L0X_HistogramModes HistogramMode;
|
||||
/*!< Defines type of histogram measurement to be done for the next
|
||||
* measure
|
||||
*/
|
||||
uint32_t MeasurementTimingBudgetMicroSeconds;
|
||||
/*!< Defines the allowed total time for a single measurement */
|
||||
uint32_t InterMeasurementPeriodMilliSeconds;
|
||||
/*!< Defines time between two consecutive measurements (between two
|
||||
* measurement starts). If set to 0 means back-to-back mode
|
||||
*/
|
||||
uint8_t XTalkCompensationEnable;
|
||||
/*!< Tells if Crosstalk compensation shall be enable or not */
|
||||
uint16_t XTalkCompensationRangeMilliMeter;
|
||||
/*!< CrossTalk compensation range in millimeter */
|
||||
FixPoint1616_t XTalkCompensationRateMegaCps;
|
||||
/*!< CrossTalk compensation rate in Mega counts per seconds.
|
||||
* Expressed in 16.16 fixed point format.
|
||||
*/
|
||||
int32_t RangeOffsetMicroMeters;
|
||||
/*!< Range offset adjustment (mm). */
|
||||
|
||||
uint8_t LimitChecksEnable[VL53L0X_CHECKENABLE_NUMBER_OF_CHECKS];
|
||||
/*!< This Array store all the Limit Check enable for this device. */
|
||||
uint8_t LimitChecksStatus[VL53L0X_CHECKENABLE_NUMBER_OF_CHECKS];
|
||||
/*!< This Array store all the Status of the check linked to last
|
||||
* measurement.
|
||||
*/
|
||||
FixPoint1616_t LimitChecksValue[VL53L0X_CHECKENABLE_NUMBER_OF_CHECKS];
|
||||
/*!< This Array store all the Limit Check value for this device */
|
||||
|
||||
VL53L0X_DMaxLUT_t dmax_lut;
|
||||
/*!< Lookup table defining ambient rates and associated
|
||||
* dmax values.
|
||||
*/
|
||||
|
||||
uint8_t WrapAroundCheckEnable;
|
||||
/*!< Tells if Wrap Around Check shall be enable or not */
|
||||
} VL53L0X_DeviceParameters_t;
|
||||
|
||||
|
||||
/** @defgroup VL53L0X_define_State_group Defines the current status
|
||||
* of the device
|
||||
* Defines the current status of the device
|
||||
* @{
|
||||
*/
|
||||
|
||||
typedef uint8_t VL53L0X_State;
|
||||
|
||||
#define VL53L0X_STATE_POWERDOWN ((VL53L0X_State) 0)
|
||||
/*!< Device is in HW reset */
|
||||
#define VL53L0X_STATE_WAIT_STATICINIT ((VL53L0X_State) 1)
|
||||
/*!< Device is initialized and wait for static initialization */
|
||||
#define VL53L0X_STATE_STANDBY ((VL53L0X_State) 2)
|
||||
/*!< Device is in Low power Standby mode */
|
||||
#define VL53L0X_STATE_IDLE ((VL53L0X_State) 3)
|
||||
/*!< Device has been initialized and ready to do measurements */
|
||||
#define VL53L0X_STATE_RUNNING ((VL53L0X_State) 4)
|
||||
/*!< Device is performing measurement */
|
||||
#define VL53L0X_STATE_UNKNOWN ((VL53L0X_State) 98)
|
||||
/*!< Device is in unknown state and need to be rebooted */
|
||||
#define VL53L0X_STATE_ERROR ((VL53L0X_State) 99)
|
||||
/*!< Device is in error state and need to be rebooted */
|
||||
|
||||
/** @} VL53L0X_define_State_group */
|
||||
|
||||
|
||||
/**
|
||||
* @struct VL53L0X_RangeData_t
|
||||
* @brief Range measurement data.
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t TimeStamp; /*!< 32-bit time stamp. */
|
||||
uint32_t MeasurementTimeUsec;
|
||||
/*!< Give the Measurement time needed by the device to do the
|
||||
* measurement.
|
||||
*/
|
||||
|
||||
|
||||
uint16_t RangeMilliMeter; /*!< range distance in millimeter. */
|
||||
|
||||
uint16_t RangeDMaxMilliMeter;
|
||||
/*!< Tells what is the maximum detection distance of the device
|
||||
* in current setup and environment conditions (Filled when
|
||||
* applicable)
|
||||
*/
|
||||
|
||||
FixPoint1616_t SignalRateRtnMegaCps;
|
||||
/*!< Return signal rate (MCPS)\n these is a 16.16 fix point
|
||||
* value, which is effectively a measure of target
|
||||
* reflectance.
|
||||
*/
|
||||
FixPoint1616_t AmbientRateRtnMegaCps;
|
||||
/*!< Return ambient rate (MCPS)\n these is a 16.16 fix point
|
||||
* value, which is effectively a measure of the ambien
|
||||
* t light.
|
||||
*/
|
||||
|
||||
uint16_t EffectiveSpadRtnCount;
|
||||
/*!< Return the effective SPAD count for the return signal.
|
||||
* To obtain Real value it should be divided by 256
|
||||
*/
|
||||
|
||||
uint8_t ZoneId;
|
||||
/*!< Denotes which zone and range scheduler stage the range
|
||||
* data relates to.
|
||||
*/
|
||||
uint8_t RangeFractionalPart;
|
||||
/*!< Fractional part of range distance. Final value is a
|
||||
* FixPoint168 value.
|
||||
*/
|
||||
uint8_t RangeStatus;
|
||||
/*!< Range Status for the current measurement. This is device
|
||||
* dependent. Value = 0 means value is valid.
|
||||
* See \ref RangeStatusPage
|
||||
*/
|
||||
} VL53L0X_RangingMeasurementData_t;
|
||||
|
||||
|
||||
#define VL53L0X_HISTOGRAM_BUFFER_SIZE 24
|
||||
|
||||
/**
|
||||
* @struct VL53L0X_HistogramData_t
|
||||
* @brief Histogram measurement data.
|
||||
*/
|
||||
typedef struct {
|
||||
/* Histogram Measurement data */
|
||||
uint32_t HistogramData[VL53L0X_HISTOGRAM_BUFFER_SIZE];
|
||||
/*!< Histogram data */
|
||||
/*!< Indicate the types of histogram data :
|
||||
*Return only, Reference only, both Return and Reference
|
||||
*/
|
||||
uint8_t FirstBin; /*!< First Bin value */
|
||||
uint8_t BufferSize; /*!< Buffer Size - Set by the user.*/
|
||||
uint8_t NumberOfBins;
|
||||
/*!< Number of bins filled by the histogram measurement */
|
||||
|
||||
VL53L0X_DeviceError ErrorStatus;
|
||||
/*!< Error status of the current measurement. \n
|
||||
* see @a ::VL53L0X_DeviceError @a VL53L0X_GetStatusErrorString()
|
||||
*/
|
||||
} VL53L0X_HistogramMeasurementData_t;
|
||||
|
||||
#define VL53L0X_REF_SPAD_BUFFER_SIZE 6
|
||||
|
||||
/**
|
||||
* @struct VL53L0X_SpadData_t
|
||||
* @brief Spad Configuration Data.
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t RefSpadEnables[VL53L0X_REF_SPAD_BUFFER_SIZE];
|
||||
/*!< Reference Spad Enables */
|
||||
uint8_t RefGoodSpadMap[VL53L0X_REF_SPAD_BUFFER_SIZE];
|
||||
/*!< Reference Spad Good Spad Map */
|
||||
} VL53L0X_SpadData_t;
|
||||
|
||||
typedef struct {
|
||||
FixPoint1616_t OscFrequencyMHz; /* Frequency used */
|
||||
|
||||
uint16_t LastEncodedTimeout;
|
||||
/* last encoded Time out used for timing budget*/
|
||||
|
||||
VL53L0X_GpioFunctionality Pin0GpioFunctionality;
|
||||
/* store the functionality of the GPIO: pin0 */
|
||||
|
||||
uint32_t FinalRangeTimeoutMicroSecs;
|
||||
/*!< Execution time of the final range*/
|
||||
uint8_t FinalRangeVcselPulsePeriod;
|
||||
/*!< Vcsel pulse period (pll clocks) for the final range measurement*/
|
||||
uint32_t PreRangeTimeoutMicroSecs;
|
||||
/*!< Execution time of the final range*/
|
||||
uint8_t PreRangeVcselPulsePeriod;
|
||||
/*!< Vcsel pulse period (pll clocks) for the pre-range measurement*/
|
||||
|
||||
uint16_t SigmaEstRefArray;
|
||||
/*!< Reference array sigma value in 1/100th of [mm] e.g. 100 = 1mm */
|
||||
uint16_t SigmaEstEffPulseWidth;
|
||||
/*!< Effective Pulse width for sigma estimate in 1/100th
|
||||
* of ns e.g. 900 = 9.0ns
|
||||
*/
|
||||
uint16_t SigmaEstEffAmbWidth;
|
||||
/*!< Effective Ambient width for sigma estimate in 1/100th of ns
|
||||
* e.g. 500 = 5.0ns
|
||||
*/
|
||||
|
||||
|
||||
/* Indicate if read from device has been done (==1) or not (==0) */
|
||||
uint8_t ReadDataFromDeviceDone;
|
||||
uint8_t ModuleId; /* Module ID */
|
||||
uint8_t Revision; /* test Revision */
|
||||
char ProductId[VL53L0X_MAX_STRING_LENGTH];
|
||||
/* Product Identifier String */
|
||||
uint8_t ReferenceSpadCount; /* used for ref spad management */
|
||||
uint8_t ReferenceSpadType; /* used for ref spad management */
|
||||
uint8_t RefSpadsInitialised; /* reports if ref spads are initialised. */
|
||||
uint32_t PartUIDUpper; /*!< Unique Part ID Upper */
|
||||
uint32_t PartUIDLower; /*!< Unique Part ID Lower */
|
||||
/*!< Peek Signal rate at 400 mm*/
|
||||
FixPoint1616_t SignalRateMeasFixed400mm;
|
||||
|
||||
} VL53L0X_DeviceSpecificParameters_t;
|
||||
|
||||
/**
|
||||
* @struct VL53L0X_DevData_t
|
||||
*
|
||||
* @brief VL53L0X PAL device ST private data structure \n
|
||||
* End user should never access any of these field directly
|
||||
*
|
||||
* These must never access directly but only via macro
|
||||
*/
|
||||
typedef struct {
|
||||
int32_t Part2PartOffsetNVMMicroMeter;
|
||||
/*!< backed up NVM value */
|
||||
int32_t Part2PartOffsetAdjustmentNVMMicroMeter;
|
||||
/*!< backed up NVM value representing additional offset adjustment */
|
||||
VL53L0X_DeviceParameters_t CurrentParameters;
|
||||
/*!< Current Device Parameter */
|
||||
VL53L0X_RangingMeasurementData_t LastRangeMeasure;
|
||||
/*!< Ranging Data */
|
||||
VL53L0X_HistogramMeasurementData_t LastHistogramMeasure;
|
||||
/*!< Histogram Data */
|
||||
VL53L0X_DeviceSpecificParameters_t DeviceSpecificParameters;
|
||||
/*!< Parameters specific to the device */
|
||||
VL53L0X_SpadData_t SpadData;
|
||||
/*!< Spad Data */
|
||||
uint8_t SequenceConfig;
|
||||
/*!< Internal value for the sequence config */
|
||||
uint8_t RangeFractionalEnable;
|
||||
/*!< Enable/Disable fractional part of ranging data */
|
||||
VL53L0X_State PalState;
|
||||
/*!< Current state of the PAL for this device */
|
||||
VL53L0X_PowerModes PowerMode;
|
||||
/*!< Current Power Mode */
|
||||
uint16_t SigmaEstRefArray;
|
||||
/*!< Reference array sigma value in 1/100th of [mm] e.g. 100 = 1mm */
|
||||
uint16_t SigmaEstEffPulseWidth;
|
||||
/*!< Effective Pulse width for sigma estimate in 1/100th
|
||||
* of ns e.g. 900 = 9.0ns
|
||||
*/
|
||||
uint16_t SigmaEstEffAmbWidth;
|
||||
/*!< Effective Ambient width for sigma estimate in 1/100th of ns
|
||||
* e.g. 500 = 5.0ns
|
||||
*/
|
||||
uint8_t StopVariable;
|
||||
/*!< StopVariable used during the stop sequence */
|
||||
uint16_t targetRefRate;
|
||||
/*!< Target Ambient Rate for Ref spad management */
|
||||
FixPoint1616_t SigmaEstimate;
|
||||
/*!< Sigma Estimate - based on ambient & VCSEL rates and
|
||||
* signal_total_events
|
||||
*/
|
||||
FixPoint1616_t SignalEstimate;
|
||||
/*!< Signal Estimate - based on ambient & VCSEL rates and cross talk */
|
||||
FixPoint1616_t LastSignalRefMcps;
|
||||
/*!< Latest Signal ref in Mcps */
|
||||
uint8_t *pTuningSettingsPointer;
|
||||
/*!< Pointer for Tuning Settings table */
|
||||
uint8_t UseInternalTuningSettings;
|
||||
/*!< Indicate if we use Tuning Settings table */
|
||||
uint16_t LinearityCorrectiveGain;
|
||||
/*!< Linearity Corrective Gain value in x1000 */
|
||||
} VL53L0X_DevData_t;
|
||||
|
||||
|
||||
/** @defgroup VL53L0X_define_InterruptPolarity_group Defines the Polarity
|
||||
* of the Interrupt
|
||||
* Defines the Polarity of the Interrupt
|
||||
* @{
|
||||
*/
|
||||
typedef uint8_t VL53L0X_InterruptPolarity;
|
||||
|
||||
#define VL53L0X_INTERRUPTPOLARITY_LOW ((VL53L0X_InterruptPolarity) 0)
|
||||
/*!< Set active low polarity best setup for falling edge. */
|
||||
#define VL53L0X_INTERRUPTPOLARITY_HIGH ((VL53L0X_InterruptPolarity) 1)
|
||||
/*!< Set active high polarity best setup for rising edge. */
|
||||
|
||||
/** @} VL53L0X_define_InterruptPolarity_group */
|
||||
|
||||
|
||||
/** @defgroup VL53L0X_define_VcselPeriod_group Vcsel Period Defines
|
||||
* Defines the range measurement for which to access the vcsel period.
|
||||
* @{
|
||||
*/
|
||||
typedef uint8_t VL53L0X_VcselPeriod;
|
||||
|
||||
#define VL53L0X_VCSEL_PERIOD_PRE_RANGE ((VL53L0X_VcselPeriod) 0)
|
||||
/*!<Identifies the pre-range vcsel period. */
|
||||
#define VL53L0X_VCSEL_PERIOD_FINAL_RANGE ((VL53L0X_VcselPeriod) 1)
|
||||
/*!<Identifies the final range vcsel period. */
|
||||
|
||||
/** @} VL53L0X_define_VcselPeriod_group */
|
||||
|
||||
/** @defgroup VL53L0X_define_SchedulerSequence_group Defines the steps
|
||||
* carried out by the scheduler during a range measurement.
|
||||
* @{
|
||||
* Defines the states of all the steps in the scheduler
|
||||
* i.e. enabled/disabled.
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t TccOn; /*!<Reports if Target Centre Check On */
|
||||
uint8_t MsrcOn; /*!<Reports if MSRC On */
|
||||
uint8_t DssOn; /*!<Reports if DSS On */
|
||||
uint8_t PreRangeOn; /*!<Reports if Pre-Range On */
|
||||
uint8_t FinalRangeOn; /*!<Reports if Final-Range On */
|
||||
} VL53L0X_SchedulerSequenceSteps_t;
|
||||
|
||||
/** @} VL53L0X_define_SchedulerSequence_group */
|
||||
|
||||
/** @defgroup VL53L0X_define_SequenceStepId_group Defines the Polarity
|
||||
* of the Interrupt
|
||||
* Defines the the sequence steps performed during ranging..
|
||||
* @{
|
||||
*/
|
||||
typedef uint8_t VL53L0X_SequenceStepId;
|
||||
|
||||
#define VL53L0X_SEQUENCESTEP_TCC ((VL53L0X_VcselPeriod) 0)
|
||||
/*!<Target CentreCheck identifier. */
|
||||
#define VL53L0X_SEQUENCESTEP_DSS ((VL53L0X_VcselPeriod) 1)
|
||||
/*!<Dynamic Spad Selection function Identifier. */
|
||||
#define VL53L0X_SEQUENCESTEP_MSRC ((VL53L0X_VcselPeriod) 2)
|
||||
/*!<Minimum Signal Rate Check function Identifier. */
|
||||
#define VL53L0X_SEQUENCESTEP_PRE_RANGE ((VL53L0X_VcselPeriod) 3)
|
||||
/*!<Pre-Range check Identifier. */
|
||||
#define VL53L0X_SEQUENCESTEP_FINAL_RANGE ((VL53L0X_VcselPeriod) 4)
|
||||
/*!<Final Range Check Identifier. */
|
||||
|
||||
#define VL53L0X_SEQUENCESTEP_NUMBER_OF_CHECKS 5
|
||||
/*!<Number of Sequence Step Managed by the API. */
|
||||
|
||||
/** @} VL53L0X_define_SequenceStepId_group */
|
||||
|
||||
|
||||
/* MACRO Definitions */
|
||||
/** @defgroup VL53L0X_define_GeneralMacro_group General Macro Defines
|
||||
* General Macro Defines
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Defines */
|
||||
#define VL53L0X_SETPARAMETERFIELD(Dev, field, value) \
|
||||
PALDevDataSet(Dev, CurrentParameters.field, value)
|
||||
|
||||
#define VL53L0X_GETPARAMETERFIELD(Dev, field, variable) \
|
||||
(variable = ((PALDevDataGet(Dev, CurrentParameters)).field))
|
||||
|
||||
|
||||
#define VL53L0X_SETARRAYPARAMETERFIELD(Dev, field, index, value) \
|
||||
PALDevDataSet(Dev, CurrentParameters.field[index], value)
|
||||
|
||||
#define VL53L0X_GETARRAYPARAMETERFIELD(Dev, field, index, variable) \
|
||||
(variable = (PALDevDataGet(Dev, CurrentParameters)).field[index])
|
||||
|
||||
#define VL53L0X_SETDEVICESPECIFICPARAMETER(Dev, field, value) \
|
||||
PALDevDataSet(Dev, DeviceSpecificParameters.field, value)
|
||||
|
||||
#define VL53L0X_GETDEVICESPECIFICPARAMETER(Dev, field) \
|
||||
PALDevDataGet(Dev, DeviceSpecificParameters).field
|
||||
|
||||
|
||||
#define VL53L0X_FIXPOINT1616TOFIXPOINT97(Value) \
|
||||
(uint16_t)((Value>>9)&0xFFFF)
|
||||
#define VL53L0X_FIXPOINT97TOFIXPOINT1616(Value) \
|
||||
(FixPoint1616_t)(Value<<9)
|
||||
|
||||
#define VL53L0X_FIXPOINT1616TOFIXPOINT88(Value) \
|
||||
(uint16_t)((Value>>8)&0xFFFF)
|
||||
#define VL53L0X_FIXPOINT88TOFIXPOINT1616(Value) \
|
||||
(FixPoint1616_t)(Value<<8)
|
||||
|
||||
#define VL53L0X_FIXPOINT1616TOFIXPOINT412(Value) \
|
||||
(uint16_t)((Value>>4)&0xFFFF)
|
||||
#define VL53L0X_FIXPOINT412TOFIXPOINT1616(Value) \
|
||||
(FixPoint1616_t)(Value<<4)
|
||||
|
||||
#define VL53L0X_FIXPOINT1616TOFIXPOINT313(Value) \
|
||||
(uint16_t)((Value>>3)&0xFFFF)
|
||||
#define VL53L0X_FIXPOINT313TOFIXPOINT1616(Value) \
|
||||
(FixPoint1616_t)(Value<<3)
|
||||
|
||||
#define VL53L0X_FIXPOINT1616TOFIXPOINT08(Value) \
|
||||
(uint8_t)((Value>>8)&0x00FF)
|
||||
#define VL53L0X_FIXPOINT08TOFIXPOINT1616(Value) \
|
||||
(FixPoint1616_t)(Value<<8)
|
||||
|
||||
#define VL53L0X_FIXPOINT1616TOFIXPOINT53(Value) \
|
||||
(uint8_t)((Value>>13)&0x00FF)
|
||||
#define VL53L0X_FIXPOINT53TOFIXPOINT1616(Value) \
|
||||
(FixPoint1616_t)(Value<<13)
|
||||
|
||||
#define VL53L0X_FIXPOINT1616TOFIXPOINT102(Value) \
|
||||
(uint16_t)((Value>>14)&0x0FFF)
|
||||
#define VL53L0X_FIXPOINT102TOFIXPOINT1616(Value) \
|
||||
(FixPoint1616_t)(Value<<12)
|
||||
|
||||
#define VL53L0X_MAKEUINT16(lsb, msb) (uint16_t)((((uint16_t)msb)<<8) + \
|
||||
(uint16_t)lsb)
|
||||
|
||||
/** @} VL53L0X_define_GeneralMacro_group */
|
||||
|
||||
/** @} VL53L0X_globaldefine_group */
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#define TRACE_MODULE_API 0
|
||||
#define _LOG_FUNCTION_START(...) (void)0
|
||||
#define _LOG_FUNCTION_END(...) (void)0
|
||||
#define _LOG_FUNCTION_END_FMT(...) (void)0
|
||||
#endif /* _VL53L0X_DEF_H_ */
|
||||
262
App/VL53L0X_API/core/inc/vl53l0x_device.h
Normal file
262
App/VL53L0X_API/core/inc/vl53l0x_device.h
Normal file
@@ -0,0 +1,262 @@
|
||||
/*******************************************************************************
|
||||
* Copyright © 2016, STMicroelectronics International N.V.
|
||||
All rights reserved.
|
||||
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
* Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
* Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in the
|
||||
documentation and/or other materials provided with the distribution.
|
||||
* Neither the name of STMicroelectronics nor the
|
||||
names of its contributors may be used to endorse or promote products
|
||||
derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
|
||||
NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
|
||||
IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
|
||||
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
|
||||
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*******************************************************************************/
|
||||
|
||||
/**
|
||||
* Device specific defines. To be adapted by implementer for the targeted
|
||||
* device.
|
||||
*/
|
||||
|
||||
#ifndef _VL53L0X_DEVICE_H_
|
||||
#define _VL53L0X_DEVICE_H_
|
||||
|
||||
#include "vl53l0x_types.h"
|
||||
|
||||
|
||||
/** @defgroup VL53L0X_DevSpecDefines_group VL53L0X cut1.1 Device
|
||||
* Specific Defines
|
||||
* @brief VL53L0X cut1.1 Device Specific Defines
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup VL53L0X_DeviceError_group Device Error
|
||||
* @brief Device Error code
|
||||
*
|
||||
* This enum is Device specific it should be updated in the implementation
|
||||
* Use @a VL53L0X_GetStatusErrorString() to get the string.
|
||||
* It is related to Status Register of the Device.
|
||||
* @{
|
||||
*/
|
||||
typedef uint8_t VL53L0X_DeviceError;
|
||||
|
||||
#define VL53L0X_DEVICEERROR_NONE ((VL53L0X_DeviceError) 0)
|
||||
/*!< 0 NoError */
|
||||
#define VL53L0X_DEVICEERROR_VCSELCONTINUITYTESTFAILURE ((VL53L0X_DeviceError) 1)
|
||||
#define VL53L0X_DEVICEERROR_VCSELWATCHDOGTESTFAILURE ((VL53L0X_DeviceError) 2)
|
||||
#define VL53L0X_DEVICEERROR_NOVHVVALUEFOUND ((VL53L0X_DeviceError) 3)
|
||||
#define VL53L0X_DEVICEERROR_MSRCNOTARGET ((VL53L0X_DeviceError) 4)
|
||||
#define VL53L0X_DEVICEERROR_SNRCHECK ((VL53L0X_DeviceError) 5)
|
||||
#define VL53L0X_DEVICEERROR_RANGEPHASECHECK ((VL53L0X_DeviceError) 6)
|
||||
#define VL53L0X_DEVICEERROR_SIGMATHRESHOLDCHECK ((VL53L0X_DeviceError) 7)
|
||||
#define VL53L0X_DEVICEERROR_TCC ((VL53L0X_DeviceError) 8)
|
||||
#define VL53L0X_DEVICEERROR_PHASECONSISTENCY ((VL53L0X_DeviceError) 9)
|
||||
#define VL53L0X_DEVICEERROR_MINCLIP ((VL53L0X_DeviceError) 10)
|
||||
#define VL53L0X_DEVICEERROR_RANGECOMPLETE ((VL53L0X_DeviceError) 11)
|
||||
#define VL53L0X_DEVICEERROR_ALGOUNDERFLOW ((VL53L0X_DeviceError) 12)
|
||||
#define VL53L0X_DEVICEERROR_ALGOOVERFLOW ((VL53L0X_DeviceError) 13)
|
||||
#define VL53L0X_DEVICEERROR_RANGEIGNORETHRESHOLD ((VL53L0X_DeviceError) 14)
|
||||
|
||||
/** @} end of VL53L0X_DeviceError_group */
|
||||
|
||||
|
||||
/** @defgroup VL53L0X_CheckEnable_group Check Enable list
|
||||
* @brief Check Enable code
|
||||
*
|
||||
* Define used to specify the LimitCheckId.
|
||||
* Use @a VL53L0X_GetLimitCheckInfo() to get the string.
|
||||
* @{
|
||||
*/
|
||||
|
||||
#define VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE 0
|
||||
#define VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE 1
|
||||
#define VL53L0X_CHECKENABLE_SIGNAL_REF_CLIP 2
|
||||
#define VL53L0X_CHECKENABLE_RANGE_IGNORE_THRESHOLD 3
|
||||
#define VL53L0X_CHECKENABLE_SIGNAL_RATE_MSRC 4
|
||||
#define VL53L0X_CHECKENABLE_SIGNAL_RATE_PRE_RANGE 5
|
||||
|
||||
#define VL53L0X_CHECKENABLE_NUMBER_OF_CHECKS 6
|
||||
|
||||
/** @} end of VL53L0X_CheckEnable_group */
|
||||
|
||||
|
||||
/** @defgroup VL53L0X_GpioFunctionality_group Gpio Functionality
|
||||
* @brief Defines the different functionalities for the device GPIO(s)
|
||||
* @{
|
||||
*/
|
||||
typedef uint8_t VL53L0X_GpioFunctionality;
|
||||
|
||||
#define VL53L0X_GPIOFUNCTIONALITY_OFF \
|
||||
((VL53L0X_GpioFunctionality) 0) /*!< NO Interrupt */
|
||||
#define VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_LOW \
|
||||
((VL53L0X_GpioFunctionality) 1) /*!< Level Low (value < thresh_low) */
|
||||
#define VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_HIGH \
|
||||
((VL53L0X_GpioFunctionality) 2) /*!< Level High (value>thresh_high) */
|
||||
#define VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_OUT \
|
||||
((VL53L0X_GpioFunctionality) 3)
|
||||
/*!< Out Of Window (value < thresh_low OR value > thresh_high) */
|
||||
#define VL53L0X_GPIOFUNCTIONALITY_NEW_MEASURE_READY \
|
||||
((VL53L0X_GpioFunctionality) 4) /*!< New Sample Ready */
|
||||
|
||||
/** @} end of VL53L0X_GpioFunctionality_group */
|
||||
|
||||
|
||||
/* Device register map */
|
||||
|
||||
/** @defgroup VL53L0X_DefineRegisters_group Define Registers
|
||||
* @brief List of all the defined registers
|
||||
* @{
|
||||
*/
|
||||
#define VL53L0X_REG_SYSRANGE_START 0x000
|
||||
/** mask existing bit in #VL53L0X_REG_SYSRANGE_START*/
|
||||
#define VL53L0X_REG_SYSRANGE_MODE_MASK 0x0F
|
||||
/** bit 0 in #VL53L0X_REG_SYSRANGE_START write 1 toggle state in
|
||||
* continuous mode and arm next shot in single shot mode
|
||||
*/
|
||||
#define VL53L0X_REG_SYSRANGE_MODE_START_STOP 0x01
|
||||
/** bit 1 write 0 in #VL53L0X_REG_SYSRANGE_START set single shot mode */
|
||||
#define VL53L0X_REG_SYSRANGE_MODE_SINGLESHOT 0x00
|
||||
/** bit 1 write 1 in #VL53L0X_REG_SYSRANGE_START set back-to-back
|
||||
* operation mode
|
||||
*/
|
||||
#define VL53L0X_REG_SYSRANGE_MODE_BACKTOBACK 0x02
|
||||
/** bit 2 write 1 in #VL53L0X_REG_SYSRANGE_START set timed operation
|
||||
* mode
|
||||
*/
|
||||
#define VL53L0X_REG_SYSRANGE_MODE_TIMED 0x04
|
||||
/** bit 3 write 1 in #VL53L0X_REG_SYSRANGE_START set histogram operation
|
||||
* mode
|
||||
*/
|
||||
#define VL53L0X_REG_SYSRANGE_MODE_HISTOGRAM 0x08
|
||||
|
||||
|
||||
#define VL53L0X_REG_SYSTEM_THRESH_HIGH 0x000C
|
||||
#define VL53L0X_REG_SYSTEM_THRESH_LOW 0x000E
|
||||
|
||||
|
||||
#define VL53L0X_REG_SYSTEM_SEQUENCE_CONFIG 0x0001
|
||||
#define VL53L0X_REG_SYSTEM_RANGE_CONFIG 0x0009
|
||||
#define VL53L0X_REG_SYSTEM_INTERMEASUREMENT_PERIOD 0x0004
|
||||
|
||||
|
||||
#define VL53L0X_REG_SYSTEM_INTERRUPT_CONFIG_GPIO 0x000A
|
||||
#define VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_DISABLED 0x00
|
||||
#define VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_LEVEL_LOW 0x01
|
||||
#define VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_LEVEL_HIGH 0x02
|
||||
#define VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_OUT_OF_WINDOW 0x03
|
||||
#define VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_NEW_SAMPLE_READY 0x04
|
||||
|
||||
#define VL53L0X_REG_GPIO_HV_MUX_ACTIVE_HIGH 0x0084
|
||||
|
||||
|
||||
#define VL53L0X_REG_SYSTEM_INTERRUPT_CLEAR 0x000B
|
||||
|
||||
/* Result registers */
|
||||
#define VL53L0X_REG_RESULT_INTERRUPT_STATUS 0x0013
|
||||
#define VL53L0X_REG_RESULT_RANGE_STATUS 0x0014
|
||||
|
||||
#define VL53L0X_REG_RESULT_CORE_PAGE 1
|
||||
#define VL53L0X_REG_RESULT_CORE_AMBIENT_WINDOW_EVENTS_RTN 0x00BC
|
||||
#define VL53L0X_REG_RESULT_CORE_RANGING_TOTAL_EVENTS_RTN 0x00C0
|
||||
#define VL53L0X_REG_RESULT_CORE_AMBIENT_WINDOW_EVENTS_REF 0x00D0
|
||||
#define VL53L0X_REG_RESULT_CORE_RANGING_TOTAL_EVENTS_REF 0x00D4
|
||||
#define VL53L0X_REG_RESULT_PEAK_SIGNAL_RATE_REF 0x00B6
|
||||
|
||||
/* Algo register */
|
||||
|
||||
#define VL53L0X_REG_ALGO_PART_TO_PART_RANGE_OFFSET_MM 0x0028
|
||||
|
||||
#define VL53L0X_REG_I2C_SLAVE_DEVICE_ADDRESS 0x008a
|
||||
|
||||
/* Check Limit registers */
|
||||
#define VL53L0X_REG_MSRC_CONFIG_CONTROL 0x0060
|
||||
|
||||
#define VL53L0X_REG_PRE_RANGE_CONFIG_MIN_SNR 0X0027
|
||||
#define VL53L0X_REG_PRE_RANGE_CONFIG_VALID_PHASE_LOW 0x0056
|
||||
#define VL53L0X_REG_PRE_RANGE_CONFIG_VALID_PHASE_HIGH 0x0057
|
||||
#define VL53L0X_REG_PRE_RANGE_MIN_COUNT_RATE_RTN_LIMIT 0x0064
|
||||
|
||||
#define VL53L0X_REG_FINAL_RANGE_CONFIG_MIN_SNR 0X0067
|
||||
#define VL53L0X_REG_FINAL_RANGE_CONFIG_VALID_PHASE_LOW 0x0047
|
||||
#define VL53L0X_REG_FINAL_RANGE_CONFIG_VALID_PHASE_HIGH 0x0048
|
||||
#define VL53L0X_REG_FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT 0x0044
|
||||
|
||||
|
||||
#define VL53L0X_REG_PRE_RANGE_CONFIG_SIGMA_THRESH_HI 0X0061
|
||||
#define VL53L0X_REG_PRE_RANGE_CONFIG_SIGMA_THRESH_LO 0X0062
|
||||
|
||||
/* PRE RANGE registers */
|
||||
#define VL53L0X_REG_PRE_RANGE_CONFIG_VCSEL_PERIOD 0x0050
|
||||
#define VL53L0X_REG_PRE_RANGE_CONFIG_TIMEOUT_MACROP_HI 0x0051
|
||||
#define VL53L0X_REG_PRE_RANGE_CONFIG_TIMEOUT_MACROP_LO 0x0052
|
||||
|
||||
#define VL53L0X_REG_SYSTEM_HISTOGRAM_BIN 0x0081
|
||||
#define VL53L0X_REG_HISTOGRAM_CONFIG_INITIAL_PHASE_SELECT 0x0033
|
||||
#define VL53L0X_REG_HISTOGRAM_CONFIG_READOUT_CTRL 0x0055
|
||||
|
||||
#define VL53L0X_REG_FINAL_RANGE_CONFIG_VCSEL_PERIOD 0x0070
|
||||
#define VL53L0X_REG_FINAL_RANGE_CONFIG_TIMEOUT_MACROP_HI 0x0071
|
||||
#define VL53L0X_REG_FINAL_RANGE_CONFIG_TIMEOUT_MACROP_LO 0x0072
|
||||
#define VL53L0X_REG_CROSSTALK_COMPENSATION_PEAK_RATE_MCPS 0x0020
|
||||
|
||||
#define VL53L0X_REG_MSRC_CONFIG_TIMEOUT_MACROP 0x0046
|
||||
|
||||
|
||||
#define VL53L0X_REG_SOFT_RESET_GO2_SOFT_RESET_N 0x00bf
|
||||
#define VL53L0X_REG_IDENTIFICATION_MODEL_ID 0x00c0
|
||||
#define VL53L0X_REG_IDENTIFICATION_REVISION_ID 0x00c2
|
||||
|
||||
#define VL53L0X_REG_OSC_CALIBRATE_VAL 0x00f8
|
||||
|
||||
|
||||
#define VL53L0X_SIGMA_ESTIMATE_MAX_VALUE 65535
|
||||
/* equivalent to a range sigma of 655.35mm */
|
||||
|
||||
#define VL53L0X_REG_GLOBAL_CONFIG_VCSEL_WIDTH 0x032
|
||||
#define VL53L0X_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_0 0x0B0
|
||||
#define VL53L0X_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_1 0x0B1
|
||||
#define VL53L0X_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_2 0x0B2
|
||||
#define VL53L0X_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_3 0x0B3
|
||||
#define VL53L0X_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_4 0x0B4
|
||||
#define VL53L0X_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_5 0x0B5
|
||||
|
||||
#define VL53L0X_REG_GLOBAL_CONFIG_REF_EN_START_SELECT 0xB6
|
||||
#define VL53L0X_REG_DYNAMIC_SPAD_NUM_REQUESTED_REF_SPAD 0x4E /* 0x14E */
|
||||
#define VL53L0X_REG_DYNAMIC_SPAD_REF_EN_START_OFFSET 0x4F /* 0x14F */
|
||||
#define VL53L0X_REG_POWER_MANAGEMENT_GO1_POWER_FORCE 0x80
|
||||
|
||||
/*
|
||||
* Speed of light in um per 1E-10 Seconds
|
||||
*/
|
||||
|
||||
#define VL53L0X_SPEED_OF_LIGHT_IN_AIR 2997
|
||||
|
||||
#define VL53L0X_REG_VHV_CONFIG_PAD_SCL_SDA__EXTSUP_HV 0x0089
|
||||
|
||||
#define VL53L0X_REG_ALGO_PHASECAL_LIM 0x0030 /* 0x130 */
|
||||
#define VL53L0X_REG_ALGO_PHASECAL_CONFIG_TIMEOUT 0x0030
|
||||
|
||||
/** @} VL53L0X_DefineRegisters_group */
|
||||
|
||||
/** @} VL53L0X_DevSpecDefines_group */
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
/* _VL53L0X_DEVICE_H_ */
|
||||
|
||||
|
||||
194
App/VL53L0X_API/core/inc/vl53l0x_interrupt_threshold_settings.h
Normal file
194
App/VL53L0X_API/core/inc/vl53l0x_interrupt_threshold_settings.h
Normal file
@@ -0,0 +1,194 @@
|
||||
/*******************************************************************************
|
||||
* Copyright © 2016, STMicroelectronics International N.V.
|
||||
All rights reserved.
|
||||
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
* Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
* Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in the
|
||||
documentation and/or other materials provided with the distribution.
|
||||
* Neither the name of STMicroelectronics nor the
|
||||
names of its contributors may be used to endorse or promote products
|
||||
derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
|
||||
NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
|
||||
IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
|
||||
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
|
||||
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*******************************************************************************/
|
||||
|
||||
|
||||
#ifndef _VL53L0X_INTERRUPT_THRESHOLD_SETTINGS_H_
|
||||
#define _VL53L0X_INTERRUPT_THRESHOLD_SETTINGS_H_
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
|
||||
uint8_t InterruptThresholdSettings[] = {
|
||||
|
||||
/* Start of Interrupt Threshold Settings */
|
||||
0x1, 0xff, 0x00,
|
||||
0x1, 0x80, 0x01,
|
||||
0x1, 0xff, 0x01,
|
||||
0x1, 0x00, 0x00,
|
||||
0x1, 0xff, 0x01,
|
||||
0x1, 0x4f, 0x02,
|
||||
0x1, 0xFF, 0x0E,
|
||||
0x1, 0x00, 0x03,
|
||||
0x1, 0x01, 0x84,
|
||||
0x1, 0x02, 0x0A,
|
||||
0x1, 0x03, 0x03,
|
||||
0x1, 0x04, 0x08,
|
||||
0x1, 0x05, 0xC8,
|
||||
0x1, 0x06, 0x03,
|
||||
0x1, 0x07, 0x8D,
|
||||
0x1, 0x08, 0x08,
|
||||
0x1, 0x09, 0xC6,
|
||||
0x1, 0x0A, 0x01,
|
||||
0x1, 0x0B, 0x02,
|
||||
0x1, 0x0C, 0x00,
|
||||
0x1, 0x0D, 0xD5,
|
||||
0x1, 0x0E, 0x18,
|
||||
0x1, 0x0F, 0x12,
|
||||
0x1, 0x10, 0x01,
|
||||
0x1, 0x11, 0x82,
|
||||
0x1, 0x12, 0x00,
|
||||
0x1, 0x13, 0xD5,
|
||||
0x1, 0x14, 0x18,
|
||||
0x1, 0x15, 0x13,
|
||||
0x1, 0x16, 0x03,
|
||||
0x1, 0x17, 0x86,
|
||||
0x1, 0x18, 0x0A,
|
||||
0x1, 0x19, 0x09,
|
||||
0x1, 0x1A, 0x08,
|
||||
0x1, 0x1B, 0xC2,
|
||||
0x1, 0x1C, 0x03,
|
||||
0x1, 0x1D, 0x8F,
|
||||
0x1, 0x1E, 0x0A,
|
||||
0x1, 0x1F, 0x06,
|
||||
0x1, 0x20, 0x01,
|
||||
0x1, 0x21, 0x02,
|
||||
0x1, 0x22, 0x00,
|
||||
0x1, 0x23, 0xD5,
|
||||
0x1, 0x24, 0x18,
|
||||
0x1, 0x25, 0x22,
|
||||
0x1, 0x26, 0x01,
|
||||
0x1, 0x27, 0x82,
|
||||
0x1, 0x28, 0x00,
|
||||
0x1, 0x29, 0xD5,
|
||||
0x1, 0x2A, 0x18,
|
||||
0x1, 0x2B, 0x0B,
|
||||
0x1, 0x2C, 0x28,
|
||||
0x1, 0x2D, 0x78,
|
||||
0x1, 0x2E, 0x28,
|
||||
0x1, 0x2F, 0x91,
|
||||
0x1, 0x30, 0x00,
|
||||
0x1, 0x31, 0x0B,
|
||||
0x1, 0x32, 0x00,
|
||||
0x1, 0x33, 0x0B,
|
||||
0x1, 0x34, 0x00,
|
||||
0x1, 0x35, 0xA1,
|
||||
0x1, 0x36, 0x00,
|
||||
0x1, 0x37, 0xA0,
|
||||
0x1, 0x38, 0x00,
|
||||
0x1, 0x39, 0x04,
|
||||
0x1, 0x3A, 0x28,
|
||||
0x1, 0x3B, 0x30,
|
||||
0x1, 0x3C, 0x0C,
|
||||
0x1, 0x3D, 0x04,
|
||||
0x1, 0x3E, 0x0F,
|
||||
0x1, 0x3F, 0x79,
|
||||
0x1, 0x40, 0x28,
|
||||
0x1, 0x41, 0x1E,
|
||||
0x1, 0x42, 0x2F,
|
||||
0x1, 0x43, 0x87,
|
||||
0x1, 0x44, 0x00,
|
||||
0x1, 0x45, 0x0B,
|
||||
0x1, 0x46, 0x00,
|
||||
0x1, 0x47, 0x0B,
|
||||
0x1, 0x48, 0x00,
|
||||
0x1, 0x49, 0xA7,
|
||||
0x1, 0x4A, 0x00,
|
||||
0x1, 0x4B, 0xA6,
|
||||
0x1, 0x4C, 0x00,
|
||||
0x1, 0x4D, 0x04,
|
||||
0x1, 0x4E, 0x01,
|
||||
0x1, 0x4F, 0x00,
|
||||
0x1, 0x50, 0x00,
|
||||
0x1, 0x51, 0x80,
|
||||
0x1, 0x52, 0x09,
|
||||
0x1, 0x53, 0x08,
|
||||
0x1, 0x54, 0x01,
|
||||
0x1, 0x55, 0x00,
|
||||
0x1, 0x56, 0x0F,
|
||||
0x1, 0x57, 0x79,
|
||||
0x1, 0x58, 0x09,
|
||||
0x1, 0x59, 0x05,
|
||||
0x1, 0x5A, 0x00,
|
||||
0x1, 0x5B, 0x60,
|
||||
0x1, 0x5C, 0x05,
|
||||
0x1, 0x5D, 0xD1,
|
||||
0x1, 0x5E, 0x0C,
|
||||
0x1, 0x5F, 0x3C,
|
||||
0x1, 0x60, 0x00,
|
||||
0x1, 0x61, 0xD0,
|
||||
0x1, 0x62, 0x0B,
|
||||
0x1, 0x63, 0x03,
|
||||
0x1, 0x64, 0x28,
|
||||
0x1, 0x65, 0x10,
|
||||
0x1, 0x66, 0x2A,
|
||||
0x1, 0x67, 0x39,
|
||||
0x1, 0x68, 0x0B,
|
||||
0x1, 0x69, 0x02,
|
||||
0x1, 0x6A, 0x28,
|
||||
0x1, 0x6B, 0x10,
|
||||
0x1, 0x6C, 0x2A,
|
||||
0x1, 0x6D, 0x61,
|
||||
0x1, 0x6E, 0x0C,
|
||||
0x1, 0x6F, 0x00,
|
||||
0x1, 0x70, 0x0F,
|
||||
0x1, 0x71, 0x79,
|
||||
0x1, 0x72, 0x00,
|
||||
0x1, 0x73, 0x0B,
|
||||
0x1, 0x74, 0x00,
|
||||
0x1, 0x75, 0x0B,
|
||||
0x1, 0x76, 0x00,
|
||||
0x1, 0x77, 0xA1,
|
||||
0x1, 0x78, 0x00,
|
||||
0x1, 0x79, 0xA0,
|
||||
0x1, 0x7A, 0x00,
|
||||
0x1, 0x7B, 0x04,
|
||||
0x1, 0xFF, 0x04,
|
||||
0x1, 0x79, 0x1D,
|
||||
0x1, 0x7B, 0x27,
|
||||
0x1, 0x96, 0x0E,
|
||||
0x1, 0x97, 0xFE,
|
||||
0x1, 0x98, 0x03,
|
||||
0x1, 0x99, 0xEF,
|
||||
0x1, 0x9A, 0x02,
|
||||
0x1, 0x9B, 0x44,
|
||||
0x1, 0x73, 0x07,
|
||||
0x1, 0x70, 0x01,
|
||||
0x1, 0xff, 0x01,
|
||||
0x1, 0x00, 0x01,
|
||||
0x1, 0xff, 0x00,
|
||||
0x00, 0x00, 0x00
|
||||
};
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* _VL53L0X_INTERRUPT_THRESHOLD_SETTINGS_H_ */
|
||||
146
App/VL53L0X_API/core/inc/vl53l0x_tuning.h
Normal file
146
App/VL53L0X_API/core/inc/vl53l0x_tuning.h
Normal file
@@ -0,0 +1,146 @@
|
||||
/*******************************************************************************
|
||||
* Copyright © 2016, STMicroelectronics International N.V.
|
||||
All rights reserved.
|
||||
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
* Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
* Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in the
|
||||
documentation and/or other materials provided with the distribution.
|
||||
* Neither the name of STMicroelectronics nor the
|
||||
names of its contributors may be used to endorse or promote products
|
||||
derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
|
||||
NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
|
||||
IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
|
||||
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
|
||||
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*******************************************************************************/
|
||||
|
||||
|
||||
#ifndef _VL53L0X_TUNING_H_
|
||||
#define _VL53L0X_TUNING_H_
|
||||
|
||||
#include "vl53l0x_def.h"
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
|
||||
uint8_t DefaultTuningSettings[] = {
|
||||
|
||||
/* update 02/11/2015_v36 */
|
||||
0x01, 0xFF, 0x01,
|
||||
0x01, 0x00, 0x00,
|
||||
|
||||
0x01, 0xFF, 0x00,
|
||||
0x01, 0x09, 0x00,
|
||||
0x01, 0x10, 0x00,
|
||||
0x01, 0x11, 0x00,
|
||||
|
||||
0x01, 0x24, 0x01,
|
||||
0x01, 0x25, 0xff,
|
||||
0x01, 0x75, 0x00,
|
||||
|
||||
0x01, 0xFF, 0x01,
|
||||
0x01, 0x4e, 0x2c,
|
||||
0x01, 0x48, 0x00,
|
||||
0x01, 0x30, 0x20,
|
||||
|
||||
0x01, 0xFF, 0x00,
|
||||
0x01, 0x30, 0x09, /* mja changed from 0x64. */
|
||||
0x01, 0x54, 0x00,
|
||||
0x01, 0x31, 0x04,
|
||||
0x01, 0x32, 0x03,
|
||||
0x01, 0x40, 0x83,
|
||||
0x01, 0x46, 0x25,
|
||||
0x01, 0x60, 0x00,
|
||||
0x01, 0x27, 0x00,
|
||||
0x01, 0x50, 0x06,
|
||||
0x01, 0x51, 0x00,
|
||||
0x01, 0x52, 0x96,
|
||||
0x01, 0x56, 0x08,
|
||||
0x01, 0x57, 0x30,
|
||||
0x01, 0x61, 0x00,
|
||||
0x01, 0x62, 0x00,
|
||||
0x01, 0x64, 0x00,
|
||||
0x01, 0x65, 0x00,
|
||||
0x01, 0x66, 0xa0,
|
||||
|
||||
0x01, 0xFF, 0x01,
|
||||
0x01, 0x22, 0x32,
|
||||
0x01, 0x47, 0x14,
|
||||
0x01, 0x49, 0xff,
|
||||
0x01, 0x4a, 0x00,
|
||||
|
||||
0x01, 0xFF, 0x00,
|
||||
0x01, 0x7a, 0x0a,
|
||||
0x01, 0x7b, 0x00,
|
||||
0x01, 0x78, 0x21,
|
||||
|
||||
0x01, 0xFF, 0x01,
|
||||
0x01, 0x23, 0x34,
|
||||
0x01, 0x42, 0x00,
|
||||
0x01, 0x44, 0xff,
|
||||
0x01, 0x45, 0x26,
|
||||
0x01, 0x46, 0x05,
|
||||
0x01, 0x40, 0x40,
|
||||
0x01, 0x0E, 0x06,
|
||||
0x01, 0x20, 0x1a,
|
||||
0x01, 0x43, 0x40,
|
||||
|
||||
0x01, 0xFF, 0x00,
|
||||
0x01, 0x34, 0x03,
|
||||
0x01, 0x35, 0x44,
|
||||
|
||||
0x01, 0xFF, 0x01,
|
||||
0x01, 0x31, 0x04,
|
||||
0x01, 0x4b, 0x09,
|
||||
0x01, 0x4c, 0x05,
|
||||
0x01, 0x4d, 0x04,
|
||||
|
||||
|
||||
0x01, 0xFF, 0x00,
|
||||
0x01, 0x44, 0x00,
|
||||
0x01, 0x45, 0x20,
|
||||
0x01, 0x47, 0x08,
|
||||
0x01, 0x48, 0x28,
|
||||
0x01, 0x67, 0x00,
|
||||
0x01, 0x70, 0x04,
|
||||
0x01, 0x71, 0x01,
|
||||
0x01, 0x72, 0xfe,
|
||||
0x01, 0x76, 0x00,
|
||||
0x01, 0x77, 0x00,
|
||||
|
||||
0x01, 0xFF, 0x01,
|
||||
0x01, 0x0d, 0x01,
|
||||
|
||||
0x01, 0xFF, 0x00,
|
||||
0x01, 0x80, 0x01,
|
||||
0x01, 0x01, 0xF8,
|
||||
|
||||
0x01, 0xFF, 0x01,
|
||||
0x01, 0x8e, 0x01,
|
||||
0x01, 0x00, 0x01,
|
||||
0x01, 0xFF, 0x00,
|
||||
0x01, 0x80, 0x00,
|
||||
|
||||
0x00, 0x00, 0x00
|
||||
};
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* _VL53L0X_TUNING_H_ */
|
||||
3141
App/VL53L0X_API/core/src/vl53l0x_api.c
Normal file
3141
App/VL53L0X_API/core/src/vl53l0x_api.c
Normal file
File diff suppressed because it is too large
Load Diff
1288
App/VL53L0X_API/core/src/vl53l0x_api_calibration.c
Normal file
1288
App/VL53L0X_API/core/src/vl53l0x_api_calibration.c
Normal file
File diff suppressed because it is too large
Load Diff
2128
App/VL53L0X_API/core/src/vl53l0x_api_core.c
Normal file
2128
App/VL53L0X_API/core/src/vl53l0x_api_core.c
Normal file
File diff suppressed because it is too large
Load Diff
42
App/VL53L0X_API/core/src/vl53l0x_api_ranging.c
Normal file
42
App/VL53L0X_API/core/src/vl53l0x_api_ranging.c
Normal file
@@ -0,0 +1,42 @@
|
||||
/*******************************************************************************
|
||||
* Copyright © 2016, STMicroelectronics International N.V.
|
||||
All rights reserved.
|
||||
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
* Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
* Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in the
|
||||
documentation and/or other materials provided with the distribution.
|
||||
* Neither the name of STMicroelectronics nor the
|
||||
names of its contributors may be used to endorse or promote products
|
||||
derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
|
||||
NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
|
||||
IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
|
||||
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
|
||||
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
******************************************************************************/
|
||||
|
||||
#include "vl53l0x_api.h"
|
||||
#include "vl53l0x_api_core.h"
|
||||
|
||||
|
||||
#ifndef __KERNEL__
|
||||
#include <stdlib.h>
|
||||
#endif
|
||||
#define LOG_FUNCTION_START(fmt, ...) \
|
||||
_LOG_FUNCTION_START(TRACE_MODULE_API, fmt, ##__VA_ARGS__)
|
||||
#define LOG_FUNCTION_END(status, ...) \
|
||||
_LOG_FUNCTION_END(TRACE_MODULE_API, status, ##__VA_ARGS__)
|
||||
#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
|
||||
_LOG_FUNCTION_END_FMT(TRACE_MODULE_API, status, fmt, ##__VA_ARGS__)
|
||||
|
||||
466
App/VL53L0X_API/core/src/vl53l0x_api_strings.c
Normal file
466
App/VL53L0X_API/core/src/vl53l0x_api_strings.c
Normal file
@@ -0,0 +1,466 @@
|
||||
/*******************************************************************************
|
||||
* Copyright © 2016, STMicroelectronics International N.V.
|
||||
All rights reserved.
|
||||
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
* Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
* Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in the
|
||||
documentation and/or other materials provided with the distribution.
|
||||
* Neither the name of STMicroelectronics nor the
|
||||
names of its contributors may be used to endorse or promote products
|
||||
derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
|
||||
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
|
||||
NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
|
||||
IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. BE LIABLE FOR ANY
|
||||
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
|
||||
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
******************************************************************************/
|
||||
|
||||
#include "vl53l0x_api.h"
|
||||
#include "vl53l0x_api_core.h"
|
||||
#include "vl53l0x_api_strings.h"
|
||||
|
||||
#ifndef __KERNEL__
|
||||
#include <stdlib.h>
|
||||
#endif
|
||||
|
||||
#define LOG_FUNCTION_START(fmt, ...) \
|
||||
_LOG_FUNCTION_START(TRACE_MODULE_API, fmt, ##__VA_ARGS__)
|
||||
#define LOG_FUNCTION_END(status, ...) \
|
||||
_LOG_FUNCTION_END(TRACE_MODULE_API, status, ##__VA_ARGS__)
|
||||
#define LOG_FUNCTION_END_FMT(status, fmt, ...) \
|
||||
_LOG_FUNCTION_END_FMT(TRACE_MODULE_API, status, fmt, ##__VA_ARGS__)
|
||||
|
||||
|
||||
VL53L0X_Error VL53L0X_check_part_used(VL53L0X_DEV Dev,
|
||||
uint8_t *Revision,
|
||||
VL53L0X_DeviceInfo_t *pVL53L0X_DeviceInfo)
|
||||
{
|
||||
VL53L0X_Error Status = VL53L0X_ERROR_NONE;
|
||||
uint8_t ModuleIdInt;
|
||||
char *ProductId_tmp;
|
||||
|
||||
LOG_FUNCTION_START("");
|
||||
|
||||
Status = VL53L0X_get_info_from_device(Dev, 2);
|
||||
|
||||
if (Status == VL53L0X_ERROR_NONE) {
|
||||
ModuleIdInt = VL53L0X_GETDEVICESPECIFICPARAMETER(Dev, ModuleId);
|
||||
|
||||
if (ModuleIdInt == 0) {
|
||||
*Revision = 0;
|
||||
VL53L0X_COPYSTRING(pVL53L0X_DeviceInfo->ProductId, "");
|
||||
} else {
|
||||
*Revision = VL53L0X_GETDEVICESPECIFICPARAMETER(Dev, Revision);
|
||||
ProductId_tmp = VL53L0X_GETDEVICESPECIFICPARAMETER(Dev,
|
||||
ProductId);
|
||||
VL53L0X_COPYSTRING(pVL53L0X_DeviceInfo->ProductId,
|
||||
ProductId_tmp);
|
||||
}
|
||||
}
|
||||
|
||||
LOG_FUNCTION_END(Status);
|
||||
return Status;
|
||||
}
|
||||
|
||||
|
||||
VL53L0X_Error VL53L0X_get_device_info(VL53L0X_DEV Dev,
|
||||
VL53L0X_DeviceInfo_t *pVL53L0X_DeviceInfo)
|
||||
{
|
||||
VL53L0X_Error Status = VL53L0X_ERROR_NONE;
|
||||
uint8_t revision_id;
|
||||
uint8_t Revision;
|
||||
|
||||
Status = VL53L0X_check_part_used(Dev, &Revision, pVL53L0X_DeviceInfo);
|
||||
|
||||
if (Status == VL53L0X_ERROR_NONE) {
|
||||
if (Revision == 0) {
|
||||
VL53L0X_COPYSTRING(pVL53L0X_DeviceInfo->Name,
|
||||
VL53L0X_STRING_DEVICE_INFO_NAME_TS0);
|
||||
} else if ((Revision <= 34) && (Revision != 32)) {
|
||||
VL53L0X_COPYSTRING(pVL53L0X_DeviceInfo->Name,
|
||||
VL53L0X_STRING_DEVICE_INFO_NAME_TS1);
|
||||
} else if (Revision < 39) {
|
||||
VL53L0X_COPYSTRING(pVL53L0X_DeviceInfo->Name,
|
||||
VL53L0X_STRING_DEVICE_INFO_NAME_TS2);
|
||||
} else {
|
||||
VL53L0X_COPYSTRING(pVL53L0X_DeviceInfo->Name,
|
||||
VL53L0X_STRING_DEVICE_INFO_NAME_ES1);
|
||||
}
|
||||
|
||||
VL53L0X_COPYSTRING(pVL53L0X_DeviceInfo->Type,
|
||||
VL53L0X_STRING_DEVICE_INFO_TYPE);
|
||||
|
||||
}
|
||||
|
||||
if (Status == VL53L0X_ERROR_NONE) {
|
||||
Status = VL53L0X_RdByte(Dev,
|
||||
VL53L0X_REG_IDENTIFICATION_MODEL_ID,
|
||||
&pVL53L0X_DeviceInfo->ProductType);
|
||||
}
|
||||
|
||||
if (Status == VL53L0X_ERROR_NONE) {
|
||||
Status = VL53L0X_RdByte(Dev,
|
||||
VL53L0X_REG_IDENTIFICATION_REVISION_ID,
|
||||
&revision_id);
|
||||
pVL53L0X_DeviceInfo->ProductRevisionMajor = 1;
|
||||
pVL53L0X_DeviceInfo->ProductRevisionMinor =
|
||||
(revision_id & 0xF0) >> 4;
|
||||
}
|
||||
|
||||
return Status;
|
||||
}
|
||||
|
||||
|
||||
VL53L0X_Error VL53L0X_get_device_error_string(VL53L0X_DeviceError ErrorCode,
|
||||
char *pDeviceErrorString)
|
||||
{
|
||||
VL53L0X_Error Status = VL53L0X_ERROR_NONE;
|
||||
|
||||
LOG_FUNCTION_START("");
|
||||
|
||||
switch (ErrorCode) {
|
||||
case VL53L0X_DEVICEERROR_NONE:
|
||||
VL53L0X_COPYSTRING(pDeviceErrorString,
|
||||
VL53L0X_STRING_DEVICEERROR_NONE);
|
||||
break;
|
||||
case VL53L0X_DEVICEERROR_VCSELCONTINUITYTESTFAILURE:
|
||||
VL53L0X_COPYSTRING(pDeviceErrorString,
|
||||
VL53L0X_STRING_DEVICEERROR_VCSELCONTINUITYTESTFAILURE);
|
||||
break;
|
||||
case VL53L0X_DEVICEERROR_VCSELWATCHDOGTESTFAILURE:
|
||||
VL53L0X_COPYSTRING(pDeviceErrorString,
|
||||
VL53L0X_STRING_DEVICEERROR_VCSELWATCHDOGTESTFAILURE);
|
||||
break;
|
||||
case VL53L0X_DEVICEERROR_NOVHVVALUEFOUND:
|
||||
VL53L0X_COPYSTRING(pDeviceErrorString,
|
||||
VL53L0X_STRING_DEVICEERROR_NOVHVVALUEFOUND);
|
||||
break;
|
||||
case VL53L0X_DEVICEERROR_MSRCNOTARGET:
|
||||
VL53L0X_COPYSTRING(pDeviceErrorString,
|
||||
VL53L0X_STRING_DEVICEERROR_MSRCNOTARGET);
|
||||
break;
|
||||
case VL53L0X_DEVICEERROR_SNRCHECK:
|
||||
VL53L0X_COPYSTRING(pDeviceErrorString,
|
||||
VL53L0X_STRING_DEVICEERROR_SNRCHECK);
|
||||
break;
|
||||
case VL53L0X_DEVICEERROR_RANGEPHASECHECK:
|
||||
VL53L0X_COPYSTRING(pDeviceErrorString,
|
||||
VL53L0X_STRING_DEVICEERROR_RANGEPHASECHECK);
|
||||
break;
|
||||
case VL53L0X_DEVICEERROR_SIGMATHRESHOLDCHECK:
|
||||
VL53L0X_COPYSTRING(pDeviceErrorString,
|
||||
VL53L0X_STRING_DEVICEERROR_SIGMATHRESHOLDCHECK);
|
||||
break;
|
||||
case VL53L0X_DEVICEERROR_TCC:
|
||||
VL53L0X_COPYSTRING(pDeviceErrorString,
|
||||
VL53L0X_STRING_DEVICEERROR_TCC);
|
||||
break;
|
||||
case VL53L0X_DEVICEERROR_PHASECONSISTENCY:
|
||||
VL53L0X_COPYSTRING(pDeviceErrorString,
|
||||
VL53L0X_STRING_DEVICEERROR_PHASECONSISTENCY);
|
||||
break;
|
||||
case VL53L0X_DEVICEERROR_MINCLIP:
|
||||
VL53L0X_COPYSTRING(pDeviceErrorString,
|
||||
VL53L0X_STRING_DEVICEERROR_MINCLIP);
|
||||
break;
|
||||
case VL53L0X_DEVICEERROR_RANGECOMPLETE:
|
||||
VL53L0X_COPYSTRING(pDeviceErrorString,
|
||||
VL53L0X_STRING_DEVICEERROR_RANGECOMPLETE);
|
||||
break;
|
||||
case VL53L0X_DEVICEERROR_ALGOUNDERFLOW:
|
||||
VL53L0X_COPYSTRING(pDeviceErrorString,
|
||||
VL53L0X_STRING_DEVICEERROR_ALGOUNDERFLOW);
|
||||
break;
|
||||
case VL53L0X_DEVICEERROR_ALGOOVERFLOW:
|
||||
VL53L0X_COPYSTRING(pDeviceErrorString,
|
||||
VL53L0X_STRING_DEVICEERROR_ALGOOVERFLOW);
|
||||
break;
|
||||
case VL53L0X_DEVICEERROR_RANGEIGNORETHRESHOLD:
|
||||
VL53L0X_COPYSTRING(pDeviceErrorString,
|
||||
VL53L0X_STRING_DEVICEERROR_RANGEIGNORETHRESHOLD);
|
||||
break;
|
||||
|
||||
default:
|
||||
VL53L0X_COPYSTRING(pDeviceErrorString,
|
||||
VL53L0X_STRING_UNKNOW_ERROR_CODE);
|
||||
|
||||
}
|
||||
|
||||
LOG_FUNCTION_END(Status);
|
||||
return Status;
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_get_range_status_string(uint8_t RangeStatus,
|
||||
char *pRangeStatusString)
|
||||
{
|
||||
VL53L0X_Error Status = VL53L0X_ERROR_NONE;
|
||||
|
||||
LOG_FUNCTION_START("");
|
||||
|
||||
switch (RangeStatus) {
|
||||
case 0:
|
||||
VL53L0X_COPYSTRING(pRangeStatusString,
|
||||
VL53L0X_STRING_RANGESTATUS_RANGEVALID);
|
||||
break;
|
||||
case 1:
|
||||
VL53L0X_COPYSTRING(pRangeStatusString,
|
||||
VL53L0X_STRING_RANGESTATUS_SIGMA);
|
||||
break;
|
||||
case 2:
|
||||
VL53L0X_COPYSTRING(pRangeStatusString,
|
||||
VL53L0X_STRING_RANGESTATUS_SIGNAL);
|
||||
break;
|
||||
case 3:
|
||||
VL53L0X_COPYSTRING(pRangeStatusString,
|
||||
VL53L0X_STRING_RANGESTATUS_MINRANGE);
|
||||
break;
|
||||
case 4:
|
||||
VL53L0X_COPYSTRING(pRangeStatusString,
|
||||
VL53L0X_STRING_RANGESTATUS_PHASE);
|
||||
break;
|
||||
case 5:
|
||||
VL53L0X_COPYSTRING(pRangeStatusString,
|
||||
VL53L0X_STRING_RANGESTATUS_HW);
|
||||
break;
|
||||
|
||||
default: /**/
|
||||
VL53L0X_COPYSTRING(pRangeStatusString,
|
||||
VL53L0X_STRING_RANGESTATUS_NONE);
|
||||
}
|
||||
|
||||
LOG_FUNCTION_END(Status);
|
||||
return Status;
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_get_pal_error_string(VL53L0X_Error PalErrorCode,
|
||||
char *pPalErrorString)
|
||||
{
|
||||
VL53L0X_Error Status = VL53L0X_ERROR_NONE;
|
||||
|
||||
LOG_FUNCTION_START("");
|
||||
|
||||
switch (PalErrorCode) {
|
||||
case VL53L0X_ERROR_NONE:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_NONE);
|
||||
break;
|
||||
case VL53L0X_ERROR_CALIBRATION_WARNING:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_CALIBRATION_WARNING);
|
||||
break;
|
||||
case VL53L0X_ERROR_MIN_CLIPPED:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_MIN_CLIPPED);
|
||||
break;
|
||||
case VL53L0X_ERROR_UNDEFINED:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_UNDEFINED);
|
||||
break;
|
||||
case VL53L0X_ERROR_INVALID_PARAMS:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_INVALID_PARAMS);
|
||||
break;
|
||||
case VL53L0X_ERROR_NOT_SUPPORTED:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_NOT_SUPPORTED);
|
||||
break;
|
||||
case VL53L0X_ERROR_INTERRUPT_NOT_CLEARED:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_INTERRUPT_NOT_CLEARED);
|
||||
break;
|
||||
case VL53L0X_ERROR_RANGE_ERROR:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_RANGE_ERROR);
|
||||
break;
|
||||
case VL53L0X_ERROR_TIME_OUT:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_TIME_OUT);
|
||||
break;
|
||||
case VL53L0X_ERROR_MODE_NOT_SUPPORTED:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_MODE_NOT_SUPPORTED);
|
||||
break;
|
||||
case VL53L0X_ERROR_BUFFER_TOO_SMALL:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_BUFFER_TOO_SMALL);
|
||||
break;
|
||||
case VL53L0X_ERROR_GPIO_NOT_EXISTING:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_GPIO_NOT_EXISTING);
|
||||
break;
|
||||
case VL53L0X_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED);
|
||||
break;
|
||||
case VL53L0X_ERROR_CONTROL_INTERFACE:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_CONTROL_INTERFACE);
|
||||
break;
|
||||
case VL53L0X_ERROR_INVALID_COMMAND:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_INVALID_COMMAND);
|
||||
break;
|
||||
case VL53L0X_ERROR_DIVISION_BY_ZERO:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_DIVISION_BY_ZERO);
|
||||
break;
|
||||
case VL53L0X_ERROR_REF_SPAD_INIT:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_REF_SPAD_INIT);
|
||||
break;
|
||||
case VL53L0X_ERROR_NOT_IMPLEMENTED:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_ERROR_NOT_IMPLEMENTED);
|
||||
break;
|
||||
|
||||
default:
|
||||
VL53L0X_COPYSTRING(pPalErrorString,
|
||||
VL53L0X_STRING_UNKNOW_ERROR_CODE);
|
||||
}
|
||||
|
||||
LOG_FUNCTION_END(Status);
|
||||
return Status;
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_get_pal_state_string(VL53L0X_State PalStateCode,
|
||||
char *pPalStateString)
|
||||
{
|
||||
VL53L0X_Error Status = VL53L0X_ERROR_NONE;
|
||||
|
||||
LOG_FUNCTION_START("");
|
||||
|
||||
switch (PalStateCode) {
|
||||
case VL53L0X_STATE_POWERDOWN:
|
||||
VL53L0X_COPYSTRING(pPalStateString,
|
||||
VL53L0X_STRING_STATE_POWERDOWN);
|
||||
break;
|
||||
case VL53L0X_STATE_WAIT_STATICINIT:
|
||||
VL53L0X_COPYSTRING(pPalStateString,
|
||||
VL53L0X_STRING_STATE_WAIT_STATICINIT);
|
||||
break;
|
||||
case VL53L0X_STATE_STANDBY:
|
||||
VL53L0X_COPYSTRING(pPalStateString,
|
||||
VL53L0X_STRING_STATE_STANDBY);
|
||||
break;
|
||||
case VL53L0X_STATE_IDLE:
|
||||
VL53L0X_COPYSTRING(pPalStateString,
|
||||
VL53L0X_STRING_STATE_IDLE);
|
||||
break;
|
||||
case VL53L0X_STATE_RUNNING:
|
||||
VL53L0X_COPYSTRING(pPalStateString,
|
||||
VL53L0X_STRING_STATE_RUNNING);
|
||||
break;
|
||||
case VL53L0X_STATE_UNKNOWN:
|
||||
VL53L0X_COPYSTRING(pPalStateString,
|
||||
VL53L0X_STRING_STATE_UNKNOWN);
|
||||
break;
|
||||
case VL53L0X_STATE_ERROR:
|
||||
VL53L0X_COPYSTRING(pPalStateString,
|
||||
VL53L0X_STRING_STATE_ERROR);
|
||||
break;
|
||||
|
||||
default:
|
||||
VL53L0X_COPYSTRING(pPalStateString,
|
||||
VL53L0X_STRING_STATE_UNKNOWN);
|
||||
}
|
||||
|
||||
LOG_FUNCTION_END(Status);
|
||||
return Status;
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_get_sequence_steps_info(
|
||||
VL53L0X_SequenceStepId SequenceStepId,
|
||||
char *pSequenceStepsString)
|
||||
{
|
||||
VL53L0X_Error Status = VL53L0X_ERROR_NONE;
|
||||
|
||||
LOG_FUNCTION_START("");
|
||||
|
||||
switch (SequenceStepId) {
|
||||
case VL53L0X_SEQUENCESTEP_TCC:
|
||||
VL53L0X_COPYSTRING(pSequenceStepsString,
|
||||
VL53L0X_STRING_SEQUENCESTEP_TCC);
|
||||
break;
|
||||
case VL53L0X_SEQUENCESTEP_DSS:
|
||||
VL53L0X_COPYSTRING(pSequenceStepsString,
|
||||
VL53L0X_STRING_SEQUENCESTEP_DSS);
|
||||
break;
|
||||
case VL53L0X_SEQUENCESTEP_MSRC:
|
||||
VL53L0X_COPYSTRING(pSequenceStepsString,
|
||||
VL53L0X_STRING_SEQUENCESTEP_MSRC);
|
||||
break;
|
||||
case VL53L0X_SEQUENCESTEP_PRE_RANGE:
|
||||
VL53L0X_COPYSTRING(pSequenceStepsString,
|
||||
VL53L0X_STRING_SEQUENCESTEP_PRE_RANGE);
|
||||
break;
|
||||
case VL53L0X_SEQUENCESTEP_FINAL_RANGE:
|
||||
VL53L0X_COPYSTRING(pSequenceStepsString,
|
||||
VL53L0X_STRING_SEQUENCESTEP_FINAL_RANGE);
|
||||
break;
|
||||
|
||||
default:
|
||||
Status = VL53L0X_ERROR_INVALID_PARAMS;
|
||||
}
|
||||
|
||||
LOG_FUNCTION_END(Status);
|
||||
|
||||
return Status;
|
||||
}
|
||||
|
||||
|
||||
VL53L0X_Error VL53L0X_get_limit_check_info(VL53L0X_DEV Dev,
|
||||
uint16_t LimitCheckId,
|
||||
char *pLimitCheckString)
|
||||
{
|
||||
VL53L0X_Error Status = VL53L0X_ERROR_NONE;
|
||||
|
||||
LOG_FUNCTION_START("");
|
||||
|
||||
switch (LimitCheckId) {
|
||||
case VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE:
|
||||
VL53L0X_COPYSTRING(pLimitCheckString,
|
||||
VL53L0X_STRING_CHECKENABLE_SIGMA_FINAL_RANGE);
|
||||
break;
|
||||
case VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE:
|
||||
VL53L0X_COPYSTRING(pLimitCheckString,
|
||||
VL53L0X_STRING_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE);
|
||||
break;
|
||||
case VL53L0X_CHECKENABLE_SIGNAL_REF_CLIP:
|
||||
VL53L0X_COPYSTRING(pLimitCheckString,
|
||||
VL53L0X_STRING_CHECKENABLE_SIGNAL_REF_CLIP);
|
||||
break;
|
||||
case VL53L0X_CHECKENABLE_RANGE_IGNORE_THRESHOLD:
|
||||
VL53L0X_COPYSTRING(pLimitCheckString,
|
||||
VL53L0X_STRING_CHECKENABLE_RANGE_IGNORE_THRESHOLD);
|
||||
break;
|
||||
|
||||
case VL53L0X_CHECKENABLE_SIGNAL_RATE_MSRC:
|
||||
VL53L0X_COPYSTRING(pLimitCheckString,
|
||||
VL53L0X_STRING_CHECKENABLE_SIGNAL_RATE_MSRC);
|
||||
break;
|
||||
|
||||
case VL53L0X_CHECKENABLE_SIGNAL_RATE_PRE_RANGE:
|
||||
VL53L0X_COPYSTRING(pLimitCheckString,
|
||||
VL53L0X_STRING_CHECKENABLE_SIGNAL_RATE_PRE_RANGE);
|
||||
break;
|
||||
|
||||
default:
|
||||
VL53L0X_COPYSTRING(pLimitCheckString,
|
||||
VL53L0X_STRING_UNKNOW_ERROR_CODE);
|
||||
|
||||
}
|
||||
|
||||
LOG_FUNCTION_END(Status);
|
||||
return Status;
|
||||
}
|
||||
55
App/VL53L0X_API/platform/README.md
Normal file
55
App/VL53L0X_API/platform/README.md
Normal file
@@ -0,0 +1,55 @@
|
||||
# VL53L0X 多传感器模板(STM32H743 + FreeRTOS)
|
||||
|
||||
这组模板按固定顺序组织 4 颗 VL53L0X:
|
||||
|
||||
1. 左上
|
||||
2. 左下
|
||||
3. 右上
|
||||
4. 右下
|
||||
|
||||
## 文件说明
|
||||
|
||||
- `vl53l0x_platform.h/.c`
|
||||
- ST 官方 API 的平台适配层
|
||||
- 不再把 `hi2c1` 硬编码到驱动里
|
||||
- 读写失败时不会污染 `RdWord/RdDWord` 输出
|
||||
- `PollingDelay()` 在调度器已启动时使用 `vTaskDelay()`
|
||||
|
||||
- `vl53_board.h/.c`
|
||||
- 4 颗 VL53L0X 的板级管理层
|
||||
- 负责 `XSHUT` 拉低/逐个拉起/逐个改地址
|
||||
- 默认运行地址:0x54 / 0x56 / 0x58 / 0x5A(8-bit 写法)
|
||||
|
||||
- `vl53_task.h/.c`
|
||||
- FreeRTOS 任务骨架
|
||||
- 10ms 周期轮询一遍 4 颗传感器
|
||||
- 采集结果写成一个快照,避免上层散读散写
|
||||
|
||||
## 你需要改的地方
|
||||
|
||||
只要改 `vl53_board.c` 里的 `g_vl53_hw_cfg[]`:
|
||||
|
||||
- `hi2c`
|
||||
- `xshut_port`
|
||||
- `xshut_pin`
|
||||
- `gpio1_port` / `gpio1_pin`(如果暂时不用中断,可保持 `NULL/0`)
|
||||
|
||||
## 集成方式
|
||||
|
||||
1. 保留 ST 官方 API 的 `vl53l0x_api*.c`、`vl53l0x_def.h` 等核心文件不动。
|
||||
2. 用本模板替换你原来的 `vl53l0x_platform.h/.c`。
|
||||
3. 新增 `vl53_board.*` 和 `vl53_task.*` 到 `App/sensors/` 或你自己的目录。
|
||||
4. 在 CubeMX 里保留任务壳函数,在任务壳里调用 `AppVl53_TaskLoop()`。
|
||||
5. 不要把 VL53 逻辑塞进你 20ms 的 `canTxTask`。
|
||||
|
||||
## 建议任务频率
|
||||
|
||||
- `canTxTask`: 保持 20ms
|
||||
- `vl53Task`: 10ms 唤醒,内部读 ready 后取数
|
||||
- 估计/控制:50–100Hz
|
||||
|
||||
## 备注
|
||||
|
||||
- 地址写法用的是 **8-bit**,默认地址是 `0x52`。
|
||||
- 多颗同总线时,必须所有器件先 `XSHUT=RESET`,然后逐个拉起并改地址。
|
||||
- 这版模板默认走“单任务采集 + 快照共享”,适合你当前的 ASER 架构。
|
||||
217
App/VL53L0X_API/platform/vl53_board.c
Normal file
217
App/VL53L0X_API/platform/vl53_board.c
Normal file
@@ -0,0 +1,217 @@
|
||||
#include "robot_params.h"
|
||||
|
||||
#if !PARAM_VL53_USE_L1X
|
||||
|
||||
#include "vl53_board.h"
|
||||
#include "FreeRTOS.h"
|
||||
#include "task.h"
|
||||
#include "vl53_calibration_config.h"
|
||||
|
||||
/* ================= EMA滤波底层实现 ================= */
|
||||
static void vl53_ema_init(Vl53EMA_t *ema, float alpha) {
|
||||
ema->x = 0.0f;
|
||||
ema->alpha = alpha;
|
||||
ema->initialized = 0;
|
||||
}
|
||||
|
||||
static float vl53_ema_update(Vl53EMA_t *ema, float measurement) {
|
||||
if (ema->initialized == 0) {
|
||||
ema->x = measurement;
|
||||
ema->initialized = 1;
|
||||
return ema->x;
|
||||
}
|
||||
// EMA公式: x_new = alpha * measurement + (1 - alpha) * x_old
|
||||
ema->x = ema->alpha * measurement + (1.0f - ema->alpha) * ema->x;
|
||||
return ema->x;
|
||||
}
|
||||
|
||||
static const Vl53RuntimeCalibration_t *vl53_get_runtime_calibration(uint8_t id)
|
||||
{
|
||||
switch (id) {
|
||||
case 0: return &k_vl53_left_calibration[0];
|
||||
case 1: return &k_vl53_left_calibration[1];
|
||||
case 2: return &k_vl53_right_calibration[0];
|
||||
case 3: return &k_vl53_right_calibration[1];
|
||||
default: return NULL;
|
||||
}
|
||||
}
|
||||
|
||||
static VL53L0X_Error vl53_apply_runtime_calibration(VL53L0X_DEV dev, uint8_t id)
|
||||
{
|
||||
const Vl53RuntimeCalibration_t *cal = vl53_get_runtime_calibration(id);
|
||||
VL53L0X_Error status;
|
||||
|
||||
if (cal == NULL) return VL53L0X_ERROR_NONE;
|
||||
|
||||
if (cal->offset_calibrated != 0U) {
|
||||
status = VL53L0X_SetOffsetCalibrationDataMicroMeter(dev, cal->offset_micro_meters);
|
||||
if (status != VL53L0X_ERROR_NONE) return status;
|
||||
}
|
||||
|
||||
if (cal->xtalk_calibrated != 0U) {
|
||||
status = VL53L0X_SetXTalkCompensationRateMegaCps(dev, cal->xtalk_compensation_rate_mcps);
|
||||
if (status != VL53L0X_ERROR_NONE) return status;
|
||||
|
||||
status = VL53L0X_SetXTalkCompensationEnable(dev, 1u);
|
||||
if (status != VL53L0X_ERROR_NONE) return status;
|
||||
} else {
|
||||
status = VL53L0X_SetXTalkCompensationEnable(dev, 0u);
|
||||
if (status != VL53L0X_ERROR_NONE) return status;
|
||||
}
|
||||
|
||||
return VL53L0X_ERROR_NONE;
|
||||
}
|
||||
|
||||
/* ================= ST 官方配置序列 ================= */
|
||||
static VL53L0X_Error vl53_do_static_init(VL53L0X_DEV dev, uint32_t timing_budget_us)
|
||||
{
|
||||
VL53L0X_Error status;
|
||||
uint32_t ref_spad_count = 0u;
|
||||
uint8_t is_aperture_spads = 0u;
|
||||
uint8_t vhv_settings = 0u;
|
||||
uint8_t phase_cal = 0u;
|
||||
|
||||
status = VL53L0X_StaticInit(dev);
|
||||
if (status != VL53L0X_ERROR_NONE) return status;
|
||||
|
||||
status = VL53L0X_PerformRefSpadManagement(dev, &ref_spad_count, &is_aperture_spads);
|
||||
if (status != VL53L0X_ERROR_NONE) return status;
|
||||
|
||||
status = VL53L0X_PerformRefCalibration(dev, &vhv_settings, &phase_cal);
|
||||
if (status != VL53L0X_ERROR_NONE) return status;
|
||||
|
||||
status = VL53L0X_SetDeviceMode(dev, VL53L0X_DEVICEMODE_CONTINUOUS_RANGING);
|
||||
if (status != VL53L0X_ERROR_NONE) return status;
|
||||
|
||||
status = VL53L0X_SetMeasurementTimingBudgetMicroSeconds(dev, timing_budget_us);
|
||||
if (status != VL53L0X_ERROR_NONE) return status;
|
||||
|
||||
/* 连续测量采用 back-to-back 模式,让下一次测量在上一帧完成后立即开始。
|
||||
* 这样任务轮询周期变快时,能尽可能拿到最新帧,而不是被固定间隔再次拖慢。 */
|
||||
status = VL53L0X_SetInterMeasurementPeriodMilliSeconds(dev, 0u);
|
||||
if (status != VL53L0X_ERROR_NONE) return status;
|
||||
|
||||
status = VL53L0X_SetLimitCheckEnable(dev, VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE, 1u);
|
||||
if (status != VL53L0X_ERROR_NONE) return status;
|
||||
|
||||
status = VL53L0X_SetLimitCheckEnable(dev, VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE, 1u);
|
||||
if (status != VL53L0X_ERROR_NONE) return status;
|
||||
|
||||
return VL53L0X_ERROR_NONE;
|
||||
}
|
||||
|
||||
/* ================= 核心管理器 API ================= */
|
||||
VL53L0X_Error Vl53Board_Init(Vl53Board_t *board, const Vl53BoardHwCfg_t *hw_cfgs, uint8_t count, uint32_t timing_budget_us)
|
||||
{
|
||||
if ((board == NULL) || (hw_cfgs == NULL) || (count == 0) || (count > VL53_MAX_DEVS_PER_BOARD)) {
|
||||
return VL53L0X_ERROR_INVALID_PARAMS;
|
||||
}
|
||||
|
||||
memset(board, 0, sizeof(Vl53Board_t));
|
||||
board->dev_count = count;
|
||||
board->timing_budget_us = (timing_budget_us == 0u) ? 33000u : timing_budget_us;
|
||||
|
||||
for (uint8_t i = 0; i < count; i++) {
|
||||
board->dev[i].name = hw_cfgs[i].name;
|
||||
board->dev[i].id = hw_cfgs[i].id;
|
||||
board->dev[i].comms_type = 1u;
|
||||
board->dev[i].comms_speed_khz = 400u;
|
||||
board->dev[i].is_present = 0u;
|
||||
|
||||
VL53L0X_PlatformAttachBus(&board->dev[i], hw_cfgs[i].hi2c, VL53L0X_DEFAULT_ADDR_8BIT, 100u, NULL);
|
||||
VL53L0X_PlatformAttachPins(&board->dev[i], hw_cfgs[i].xshut_port, hw_cfgs[i].xshut_pin, NULL, 0);
|
||||
|
||||
VL53L0X_PlatformSetXShut(&board->dev[i], GPIO_PIN_RESET);
|
||||
|
||||
/* 初始化EMA滤波器:alpha 从 robot_params.h 读取 */
|
||||
vl53_ema_init(&board->ema[i], PARAM_VL53_EMA_ALPHA);
|
||||
}
|
||||
|
||||
vTaskDelay(pdMS_TO_TICKS(10));
|
||||
|
||||
for (uint8_t i = 0; i < count; i++) {
|
||||
if (VL53L0X_PlatformSetXShut(&board->dev[i], GPIO_PIN_SET) != VL53L0X_ERROR_NONE) continue;
|
||||
vTaskDelay(pdMS_TO_TICKS(20));
|
||||
|
||||
board->dev[i].I2cDevAddr = VL53L0X_DEFAULT_ADDR_8BIT;
|
||||
if (VL53L0X_PlatformChangeAddress(&board->dev[i], hw_cfgs[i].runtime_addr_8bit) != VL53L0X_ERROR_NONE) continue;
|
||||
if (VL53L0X_DataInit(&board->dev[i]) != VL53L0X_ERROR_NONE) continue;
|
||||
if (vl53_do_static_init(&board->dev[i], board->timing_budget_us) != VL53L0X_ERROR_NONE) continue;
|
||||
if (vl53_apply_runtime_calibration(&board->dev[i], hw_cfgs[i].id) != VL53L0X_ERROR_NONE) continue;
|
||||
|
||||
board->init_mask |= (uint8_t)(1u << i);
|
||||
board->dev[i].is_present = 1u;
|
||||
}
|
||||
|
||||
return VL53L0X_ERROR_NONE;
|
||||
}
|
||||
|
||||
VL53L0X_Error Vl53Board_StartContinuous(Vl53Board_t *board)
|
||||
{
|
||||
if (board == NULL) return VL53L0X_ERROR_INVALID_PARAMS;
|
||||
for (uint8_t i = 0; i < board->dev_count; i++) {
|
||||
if (board->init_mask & (1u << i)) VL53L0X_StartMeasurement(&board->dev[i]);
|
||||
}
|
||||
return VL53L0X_ERROR_NONE;
|
||||
}
|
||||
|
||||
VL53L0X_Error Vl53Board_StopContinuous(Vl53Board_t *board)
|
||||
{
|
||||
if (board == NULL) return VL53L0X_ERROR_INVALID_PARAMS;
|
||||
for (uint8_t i = 0; i < board->dev_count; i++) {
|
||||
if (board->init_mask & (1u << i)) VL53L0X_StopMeasurement(&board->dev[i]);
|
||||
}
|
||||
return VL53L0X_ERROR_NONE;
|
||||
}
|
||||
|
||||
VL53L0X_Error Vl53Board_ReadAll(Vl53Board_t *board, Vl53BoardSnapshot_t *snapshot)
|
||||
{
|
||||
if (board == NULL || snapshot == NULL) return VL53L0X_ERROR_INVALID_PARAMS;
|
||||
|
||||
memset(snapshot, 0, sizeof(Vl53BoardSnapshot_t));
|
||||
snapshot->tick_ms = xTaskGetTickCount() * portTICK_PERIOD_MS;
|
||||
|
||||
for (uint8_t i = 0; i < board->dev_count; i++) {
|
||||
if ((board->init_mask & (1u << i)) == 0u) {
|
||||
snapshot->range_status[i] = 255u;
|
||||
continue;
|
||||
}
|
||||
|
||||
uint8_t ready = 0u;
|
||||
if (VL53L0X_GetMeasurementDataReady(&board->dev[i], &ready) != VL53L0X_ERROR_NONE) continue;
|
||||
|
||||
if (ready) {
|
||||
VL53L0X_RangingMeasurementData_t data;
|
||||
memset(&data, 0, sizeof(data));
|
||||
|
||||
if (VL53L0X_GetRangingMeasurementData(&board->dev[i], &data) == VL53L0X_ERROR_NONE) {
|
||||
/* 1. 写入原始数据 */
|
||||
snapshot->range_mm[i] = data.RangeMilliMeter;
|
||||
snapshot->range_status[i] = data.RangeStatus;
|
||||
|
||||
if (data.RangeStatus == 0u) {
|
||||
/* 2. 标记有效并按开关决定是否应用EMA滤波 */
|
||||
snapshot->valid_mask |= (1u << i);
|
||||
#if PARAM_VL53_USE_EMA_FILTER
|
||||
snapshot->range_mm_filtered[i] = vl53_ema_update(&board->ema[i], (float)data.RangeMilliMeter);
|
||||
#else
|
||||
snapshot->range_mm_filtered[i] = (float)data.RangeMilliMeter;
|
||||
board->ema[i].x = (float)data.RangeMilliMeter;
|
||||
board->ema[i].initialized = 1u;
|
||||
#endif
|
||||
} else {
|
||||
/* 测距失败时,滤波值维持上一次的历史最佳估计不变 */
|
||||
snapshot->range_mm_filtered[i] = board->ema[i].x;
|
||||
}
|
||||
|
||||
VL53L0X_ClearInterruptMask(&board->dev[i], 0u);
|
||||
}
|
||||
} else {
|
||||
/* 如果没准备好,把上一帧的历史值顺延下来,防止读到 0 */
|
||||
snapshot->range_mm_filtered[i] = board->ema[i].x;
|
||||
}
|
||||
}
|
||||
return VL53L0X_ERROR_NONE;
|
||||
}
|
||||
|
||||
#endif
|
||||
57
App/VL53L0X_API/platform/vl53_board.h
Normal file
57
App/VL53L0X_API/platform/vl53_board.h
Normal file
@@ -0,0 +1,57 @@
|
||||
#ifndef VL53_BOARD_H
|
||||
#define VL53_BOARD_H
|
||||
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include "vl53l0x_api.h"
|
||||
#include "vl53l0x_platform.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#define VL53_MAX_DEVS_PER_BOARD 4
|
||||
|
||||
typedef struct {
|
||||
I2C_HandleTypeDef *hi2c;
|
||||
GPIO_TypeDef *xshut_port;
|
||||
uint16_t xshut_pin;
|
||||
uint8_t runtime_addr_8bit;
|
||||
const char *name;
|
||||
uint8_t id;
|
||||
} Vl53BoardHwCfg_t;
|
||||
|
||||
/* ================= 内部EMA滤波器结构 ================= */
|
||||
typedef struct {
|
||||
float x; // 当前滤波值 (滤波后的距离)
|
||||
float alpha; // 平滑系数 (0.0~1.0, 越大响应越快)
|
||||
uint8_t initialized; // 防止第一次开机从0缓慢爬升
|
||||
} Vl53EMA_t;
|
||||
|
||||
/* ================= 快照数据结构 (对外接口) ================= */
|
||||
typedef struct {
|
||||
uint32_t tick_ms;
|
||||
uint16_t range_mm[VL53_MAX_DEVS_PER_BOARD]; /* 接口1:原始硬件数据 */
|
||||
float range_mm_filtered[VL53_MAX_DEVS_PER_BOARD]; /* 接口2:EMA平滑数据 */
|
||||
uint8_t range_status[VL53_MAX_DEVS_PER_BOARD];
|
||||
uint8_t valid_mask;
|
||||
} Vl53BoardSnapshot_t;
|
||||
|
||||
typedef struct {
|
||||
VL53L0X_Dev_t dev[VL53_MAX_DEVS_PER_BOARD];
|
||||
Vl53EMA_t ema[VL53_MAX_DEVS_PER_BOARD]; /* 每个传感器配备一个专属EMA滤波器 */
|
||||
uint8_t init_mask;
|
||||
uint8_t dev_count;
|
||||
uint32_t timing_budget_us;
|
||||
} Vl53Board_t;
|
||||
|
||||
VL53L0X_Error Vl53Board_Init(Vl53Board_t *board, const Vl53BoardHwCfg_t *hw_cfgs, uint8_t count, uint32_t timing_budget_us);
|
||||
VL53L0X_Error Vl53Board_StartContinuous(Vl53Board_t *board);
|
||||
VL53L0X_Error Vl53Board_StopContinuous(Vl53Board_t *board);
|
||||
VL53L0X_Error Vl53Board_ReadAll(Vl53Board_t *board, Vl53BoardSnapshot_t *snapshot);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* VL53_BOARD_H */
|
||||
53
App/VL53L0X_API/platform/vl53_calibration_config.h
Normal file
53
App/VL53L0X_API/platform/vl53_calibration_config.h
Normal file
@@ -0,0 +1,53 @@
|
||||
#ifndef VL53_CALIBRATION_CONFIG_H
|
||||
#define VL53_CALIBRATION_CONFIG_H
|
||||
|
||||
#include <stdint.h>
|
||||
#include "vl53l0x_def.h"
|
||||
|
||||
typedef struct {
|
||||
int32_t offset_micro_meters;
|
||||
uint8_t offset_calibrated;
|
||||
FixPoint1616_t xtalk_compensation_rate_mcps;
|
||||
uint8_t xtalk_calibrated;
|
||||
} Vl53RuntimeCalibration_t;
|
||||
|
||||
/*
|
||||
* 运行时直接加载的 VL53 校准值。
|
||||
*
|
||||
* 当前已确认:
|
||||
* - 左前 offset = 12000 um
|
||||
* - 左后 offset = 11000 um
|
||||
*
|
||||
* 右侧和 XTalk 目前未写入有效标定值,因此 calibrated 标志保持 0。
|
||||
*/
|
||||
static const Vl53RuntimeCalibration_t k_vl53_left_calibration[2] = {
|
||||
{
|
||||
.offset_micro_meters = 8000,
|
||||
.xtalk_compensation_rate_mcps = 0,
|
||||
.offset_calibrated = 0,
|
||||
.xtalk_calibrated = 0,
|
||||
},
|
||||
{
|
||||
.offset_micro_meters = 8000,
|
||||
.xtalk_compensation_rate_mcps = 0,
|
||||
.offset_calibrated = 0,
|
||||
.xtalk_calibrated = 0,
|
||||
},
|
||||
};
|
||||
|
||||
static const Vl53RuntimeCalibration_t k_vl53_right_calibration[2] = {
|
||||
{
|
||||
.offset_micro_meters = 2000,
|
||||
.xtalk_compensation_rate_mcps = 0,
|
||||
.offset_calibrated = 0,
|
||||
.xtalk_calibrated = 0,
|
||||
},
|
||||
{
|
||||
.offset_micro_meters = 9000,
|
||||
.xtalk_compensation_rate_mcps = 0,
|
||||
.offset_calibrated = 0,
|
||||
.xtalk_calibrated = 0,
|
||||
},
|
||||
};
|
||||
|
||||
#endif /* VL53_CALIBRATION_CONFIG_H */
|
||||
315
App/VL53L0X_API/platform/vl53l0x_platform.c
Normal file
315
App/VL53L0X_API/platform/vl53l0x_platform.c
Normal file
@@ -0,0 +1,315 @@
|
||||
#include "vl53l0x_platform.h"
|
||||
#include "vl53l0x_api.h"
|
||||
|
||||
#if VL53_USE_FREERTOS_DELAY
|
||||
#include "FreeRTOS.h"
|
||||
#include "task.h"
|
||||
#endif
|
||||
|
||||
#if defined(configSUPPORT_STATIC_ALLOCATION) || defined(configUSE_MUTEXES)
|
||||
#include "semphr.h"
|
||||
#define VL53_USE_FREERTOS_MUTEX 1
|
||||
#else
|
||||
#define VL53_USE_FREERTOS_MUTEX 0
|
||||
#endif
|
||||
|
||||
static VL53L0X_Error vl53_hal_to_pal(HAL_StatusTypeDef hal_status)
|
||||
{
|
||||
switch (hal_status) {
|
||||
case HAL_OK:
|
||||
return VL53L0X_ERROR_NONE;
|
||||
case HAL_TIMEOUT:
|
||||
return VL53L0X_ERROR_TIME_OUT;
|
||||
default:
|
||||
return VL53L0X_ERROR_CONTROL_INTERFACE;
|
||||
}
|
||||
}
|
||||
|
||||
static VL53L0X_Error vl53_validate_dev(VL53L0X_DEV Dev)
|
||||
{
|
||||
if ((Dev == NULL) || (Dev->hi2c == NULL)) {
|
||||
return VL53L0X_ERROR_CONTROL_INTERFACE;
|
||||
}
|
||||
return VL53L0X_ERROR_NONE;
|
||||
}
|
||||
|
||||
static VL53L0X_Error vl53_bus_lock(VL53L0X_DEV Dev)
|
||||
{
|
||||
#if VL53_USE_FREERTOS_MUTEX
|
||||
if ((Dev != NULL) && (Dev->bus_lock != NULL)) {
|
||||
if (xTaskGetSchedulerState() != taskSCHEDULER_NOT_STARTED) {
|
||||
const TickType_t wait_ticks = pdMS_TO_TICKS((Dev->io_timeout_ms == 0u) ? 10u : Dev->io_timeout_ms);
|
||||
if (xSemaphoreTake((SemaphoreHandle_t)Dev->bus_lock, wait_ticks) != pdTRUE) {
|
||||
return VL53L0X_ERROR_TIME_OUT;
|
||||
}
|
||||
}
|
||||
}
|
||||
#else
|
||||
(void)Dev;
|
||||
#endif
|
||||
return VL53L0X_ERROR_NONE;
|
||||
}
|
||||
|
||||
static void vl53_bus_unlock(VL53L0X_DEV Dev)
|
||||
{
|
||||
#if VL53_USE_FREERTOS_MUTEX
|
||||
if ((Dev != NULL) && (Dev->bus_lock != NULL)) {
|
||||
if (xTaskGetSchedulerState() != taskSCHEDULER_NOT_STARTED) {
|
||||
(void)xSemaphoreGive((SemaphoreHandle_t)Dev->bus_lock);
|
||||
}
|
||||
}
|
||||
#else
|
||||
(void)Dev;
|
||||
#endif
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_LockSequenceAccess(VL53L0X_DEV Dev)
|
||||
{
|
||||
(void)Dev;
|
||||
/* Shared I2C bus is already serialized per I/O transaction below. */
|
||||
return VL53L0X_ERROR_NONE;
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_UnlockSequenceAccess(VL53L0X_DEV Dev)
|
||||
{
|
||||
(void)Dev;
|
||||
return VL53L0X_ERROR_NONE;
|
||||
}
|
||||
|
||||
void VL53L0X_PlatformAttachBus(VL53L0X_DEV Dev,
|
||||
I2C_HandleTypeDef *hi2c,
|
||||
uint8_t i2c_addr_8bit,
|
||||
uint16_t io_timeout_ms,
|
||||
void *bus_lock)
|
||||
{
|
||||
if (Dev == NULL) {
|
||||
return;
|
||||
}
|
||||
Dev->hi2c = hi2c;
|
||||
Dev->I2cDevAddr = i2c_addr_8bit;
|
||||
Dev->io_timeout_ms = (io_timeout_ms == 0u) ? 100u : io_timeout_ms;
|
||||
Dev->bus_lock = bus_lock;
|
||||
}
|
||||
|
||||
void VL53L0X_PlatformAttachPins(VL53L0X_DEV Dev,
|
||||
GPIO_TypeDef *xshut_port,
|
||||
uint16_t xshut_pin,
|
||||
GPIO_TypeDef *gpio1_port,
|
||||
uint16_t gpio1_pin)
|
||||
{
|
||||
if (Dev == NULL) {
|
||||
return;
|
||||
}
|
||||
Dev->xshut_port = xshut_port;
|
||||
Dev->xshut_pin = xshut_pin;
|
||||
Dev->gpio1_port = gpio1_port;
|
||||
Dev->gpio1_pin = gpio1_pin;
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_PlatformSetXShut(VL53L0X_DEV Dev, GPIO_PinState state)
|
||||
{
|
||||
if ((Dev == NULL) || (Dev->xshut_port == NULL)) {
|
||||
return VL53L0X_ERROR_INVALID_PARAMS;
|
||||
}
|
||||
HAL_GPIO_WritePin(Dev->xshut_port, Dev->xshut_pin, state);
|
||||
return VL53L0X_ERROR_NONE;
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_PlatformBootDevice(VL53L0X_DEV Dev, uint32_t reset_low_ms, uint32_t boot_wait_ms)
|
||||
{
|
||||
VL53L0X_Error status = VL53L0X_PlatformSetXShut(Dev, GPIO_PIN_RESET);
|
||||
if (status != VL53L0X_ERROR_NONE) {
|
||||
return status;
|
||||
}
|
||||
|
||||
if (xTaskGetSchedulerState() != taskSCHEDULER_NOT_STARTED) {
|
||||
vTaskDelay(pdMS_TO_TICKS(reset_low_ms));
|
||||
} else {
|
||||
HAL_Delay(reset_low_ms);
|
||||
}
|
||||
|
||||
status = VL53L0X_PlatformSetXShut(Dev, GPIO_PIN_SET);
|
||||
if (status != VL53L0X_ERROR_NONE) {
|
||||
return status;
|
||||
}
|
||||
|
||||
if (xTaskGetSchedulerState() != taskSCHEDULER_NOT_STARTED) {
|
||||
vTaskDelay(pdMS_TO_TICKS(boot_wait_ms));
|
||||
} else {
|
||||
HAL_Delay(boot_wait_ms);
|
||||
}
|
||||
|
||||
return VL53L0X_ERROR_NONE;
|
||||
}
|
||||
|
||||
uint32_t VL53L0X_PlatformGetTick(void)
|
||||
{
|
||||
return HAL_GetTick();
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_WriteMulti(VL53L0X_DEV Dev, uint8_t index, uint8_t *pdata, uint32_t count)
|
||||
{
|
||||
HAL_StatusTypeDef hal_status;
|
||||
VL53L0X_Error status;
|
||||
|
||||
if ((pdata == NULL) || (count == 0u) || (count > 255u)) {
|
||||
return VL53L0X_ERROR_INVALID_PARAMS;
|
||||
}
|
||||
status = vl53_validate_dev(Dev);
|
||||
if (status != VL53L0X_ERROR_NONE) {
|
||||
return status;
|
||||
}
|
||||
status = vl53_bus_lock(Dev);
|
||||
if (status != VL53L0X_ERROR_NONE) {
|
||||
return status;
|
||||
}
|
||||
|
||||
hal_status = HAL_I2C_Mem_Write(Dev->hi2c,
|
||||
Dev->I2cDevAddr,
|
||||
index,
|
||||
I2C_MEMADD_SIZE_8BIT,
|
||||
pdata,
|
||||
(uint16_t)count,
|
||||
Dev->io_timeout_ms);
|
||||
vl53_bus_unlock(Dev);
|
||||
return vl53_hal_to_pal(hal_status);
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_ReadMulti(VL53L0X_DEV Dev, uint8_t index, uint8_t *pdata, uint32_t count)
|
||||
{
|
||||
HAL_StatusTypeDef hal_status;
|
||||
VL53L0X_Error status;
|
||||
|
||||
if ((pdata == NULL) || (count == 0u) || (count > 255u)) {
|
||||
return VL53L0X_ERROR_INVALID_PARAMS;
|
||||
}
|
||||
status = vl53_validate_dev(Dev);
|
||||
if (status != VL53L0X_ERROR_NONE) {
|
||||
return status;
|
||||
}
|
||||
status = vl53_bus_lock(Dev);
|
||||
if (status != VL53L0X_ERROR_NONE) {
|
||||
return status;
|
||||
}
|
||||
|
||||
hal_status = HAL_I2C_Mem_Read(Dev->hi2c,
|
||||
Dev->I2cDevAddr,
|
||||
index,
|
||||
I2C_MEMADD_SIZE_8BIT,
|
||||
pdata,
|
||||
(uint16_t)count,
|
||||
Dev->io_timeout_ms);
|
||||
vl53_bus_unlock(Dev);
|
||||
return vl53_hal_to_pal(hal_status);
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_WrByte(VL53L0X_DEV Dev, uint8_t index, uint8_t data)
|
||||
{
|
||||
return VL53L0X_WriteMulti(Dev, index, &data, 1u);
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_WrWord(VL53L0X_DEV Dev, uint8_t index, uint16_t data)
|
||||
{
|
||||
uint8_t buffer[2];
|
||||
buffer[0] = (uint8_t)(data >> 8);
|
||||
buffer[1] = (uint8_t)(data & 0xFFu);
|
||||
return VL53L0X_WriteMulti(Dev, index, buffer, 2u);
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_WrDWord(VL53L0X_DEV Dev, uint8_t index, uint32_t data)
|
||||
{
|
||||
uint8_t buffer[4];
|
||||
buffer[0] = (uint8_t)(data >> 24);
|
||||
buffer[1] = (uint8_t)(data >> 16);
|
||||
buffer[2] = (uint8_t)(data >> 8);
|
||||
buffer[3] = (uint8_t)(data & 0xFFu);
|
||||
return VL53L0X_WriteMulti(Dev, index, buffer, 4u);
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_RdByte(VL53L0X_DEV Dev, uint8_t index, uint8_t *data)
|
||||
{
|
||||
if (data == NULL) {
|
||||
return VL53L0X_ERROR_INVALID_PARAMS;
|
||||
}
|
||||
return VL53L0X_ReadMulti(Dev, index, data, 1u);
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_RdWord(VL53L0X_DEV Dev, uint8_t index, uint16_t *data)
|
||||
{
|
||||
uint8_t buffer[2] = {0u, 0u};
|
||||
VL53L0X_Error status;
|
||||
|
||||
if (data == NULL) {
|
||||
return VL53L0X_ERROR_INVALID_PARAMS;
|
||||
}
|
||||
status = VL53L0X_ReadMulti(Dev, index, buffer, 2u);
|
||||
if (status == VL53L0X_ERROR_NONE) {
|
||||
*data = (((uint16_t)buffer[0]) << 8) | buffer[1];
|
||||
}
|
||||
return status;
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_RdDWord(VL53L0X_DEV Dev, uint8_t index, uint32_t *data)
|
||||
{
|
||||
uint8_t buffer[4] = {0u, 0u, 0u, 0u};
|
||||
VL53L0X_Error status;
|
||||
|
||||
if (data == NULL) {
|
||||
return VL53L0X_ERROR_INVALID_PARAMS;
|
||||
}
|
||||
status = VL53L0X_ReadMulti(Dev, index, buffer, 4u);
|
||||
if (status == VL53L0X_ERROR_NONE) {
|
||||
*data = (((uint32_t)buffer[0]) << 24)
|
||||
| (((uint32_t)buffer[1]) << 16)
|
||||
| (((uint32_t)buffer[2]) << 8)
|
||||
| ((uint32_t)buffer[3]);
|
||||
}
|
||||
return status;
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_UpdateByte(VL53L0X_DEV Dev, uint8_t index, uint8_t AndData, uint8_t OrData)
|
||||
{
|
||||
VL53L0X_Error status;
|
||||
uint8_t data = 0u;
|
||||
|
||||
status = VL53L0X_RdByte(Dev, index, &data);
|
||||
if (status != VL53L0X_ERROR_NONE) {
|
||||
return status;
|
||||
}
|
||||
data = (uint8_t)((data & AndData) | OrData);
|
||||
return VL53L0X_WrByte(Dev, index, data);
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_PollingDelay(VL53L0X_DEV Dev)
|
||||
{
|
||||
(void)Dev;
|
||||
#if VL53_USE_FREERTOS_DELAY
|
||||
if (xTaskGetSchedulerState() != taskSCHEDULER_NOT_STARTED) {
|
||||
vTaskDelay(pdMS_TO_TICKS(2u));
|
||||
} else {
|
||||
HAL_Delay(2u);
|
||||
}
|
||||
#else
|
||||
HAL_Delay(2u);
|
||||
#endif
|
||||
return VL53L0X_ERROR_NONE;
|
||||
}
|
||||
|
||||
VL53L0X_Error VL53L0X_PlatformChangeAddress(VL53L0X_DEV Dev, uint8_t new_addr_8bit)
|
||||
{
|
||||
VL53L0X_Error status;
|
||||
|
||||
if (new_addr_8bit == 0u) {
|
||||
return VL53L0X_ERROR_INVALID_PARAMS;
|
||||
}
|
||||
status = VL53L0X_SetDeviceAddress(Dev, new_addr_8bit);
|
||||
if (status == VL53L0X_ERROR_NONE) {
|
||||
Dev->I2cDevAddr = new_addr_8bit;
|
||||
if (xTaskGetSchedulerState() != taskSCHEDULER_NOT_STARTED) {
|
||||
vTaskDelay(pdMS_TO_TICKS(2u));
|
||||
} else {
|
||||
HAL_Delay(2u);
|
||||
}
|
||||
}
|
||||
return status;
|
||||
}
|
||||
89
App/VL53L0X_API/platform/vl53l0x_platform.h
Normal file
89
App/VL53L0X_API/platform/vl53l0x_platform.h
Normal file
@@ -0,0 +1,89 @@
|
||||
#ifndef VL53L0X_PLATFORM_H
|
||||
#define VL53L0X_PLATFORM_H
|
||||
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include "main.h"
|
||||
|
||||
#ifndef VL53L0X_SINGLE_DEVICE_DRIVER
|
||||
#define VL53L0X_SINGLE_DEVICE_DRIVER 0
|
||||
#endif
|
||||
|
||||
#include "vl53l0x_def.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#ifndef VL53_USE_FREERTOS_DELAY
|
||||
#define VL53_USE_FREERTOS_DELAY 1
|
||||
#endif
|
||||
|
||||
#ifndef VL53L0X_COPYSTRING
|
||||
#define VL53L0X_COPYSTRING(dst, src) strcpy((dst), (src))
|
||||
#endif
|
||||
|
||||
#ifndef VL53L0X_DEFAULT_ADDR_8BIT
|
||||
#define VL53L0X_DEFAULT_ADDR_8BIT 0x52u
|
||||
#endif
|
||||
|
||||
typedef struct {
|
||||
VL53L0X_DevData_t Data;
|
||||
uint8_t I2cDevAddr; /* ST API expects 8-bit address, default 0x52 */
|
||||
uint8_t comms_type;
|
||||
uint16_t comms_speed_khz;
|
||||
|
||||
I2C_HandleTypeDef *hi2c;
|
||||
GPIO_TypeDef *xshut_port;
|
||||
uint16_t xshut_pin;
|
||||
GPIO_TypeDef *gpio1_port; /* optional */
|
||||
uint16_t gpio1_pin;
|
||||
|
||||
void *bus_lock; /* optional shared mutex/lock handle */
|
||||
const char *name;
|
||||
uint8_t id; /* user label: 1=左上, 2=左下, 3=右上, 4=右下 */
|
||||
uint8_t is_present;
|
||||
uint16_t io_timeout_ms;
|
||||
} VL53L0X_Dev_t;
|
||||
|
||||
typedef VL53L0X_Dev_t* VL53L0X_DEV;
|
||||
|
||||
#define PALDevDataGet(Dev, field) ((Dev)->Data.field)
|
||||
#define PALDevDataSet(Dev, field, data) ((Dev)->Data.field = (data))
|
||||
|
||||
VL53L0X_Error VL53L0X_LockSequenceAccess(VL53L0X_DEV Dev);
|
||||
VL53L0X_Error VL53L0X_UnlockSequenceAccess(VL53L0X_DEV Dev);
|
||||
|
||||
VL53L0X_Error VL53L0X_WriteMulti(VL53L0X_DEV Dev, uint8_t index, uint8_t *pdata, uint32_t count);
|
||||
VL53L0X_Error VL53L0X_ReadMulti(VL53L0X_DEV Dev, uint8_t index, uint8_t *pdata, uint32_t count);
|
||||
VL53L0X_Error VL53L0X_WrByte(VL53L0X_DEV Dev, uint8_t index, uint8_t data);
|
||||
VL53L0X_Error VL53L0X_WrWord(VL53L0X_DEV Dev, uint8_t index, uint16_t data);
|
||||
VL53L0X_Error VL53L0X_WrDWord(VL53L0X_DEV Dev, uint8_t index, uint32_t data);
|
||||
VL53L0X_Error VL53L0X_RdByte(VL53L0X_DEV Dev, uint8_t index, uint8_t *data);
|
||||
VL53L0X_Error VL53L0X_RdWord(VL53L0X_DEV Dev, uint8_t index, uint16_t *data);
|
||||
VL53L0X_Error VL53L0X_RdDWord(VL53L0X_DEV Dev, uint8_t index, uint32_t *data);
|
||||
VL53L0X_Error VL53L0X_UpdateByte(VL53L0X_DEV Dev, uint8_t index, uint8_t AndData, uint8_t OrData);
|
||||
VL53L0X_Error VL53L0X_PollingDelay(VL53L0X_DEV Dev);
|
||||
|
||||
void VL53L0X_PlatformAttachBus(VL53L0X_DEV Dev,
|
||||
I2C_HandleTypeDef *hi2c,
|
||||
uint8_t i2c_addr_8bit,
|
||||
uint16_t io_timeout_ms,
|
||||
void *bus_lock);
|
||||
|
||||
void VL53L0X_PlatformAttachPins(VL53L0X_DEV Dev,
|
||||
GPIO_TypeDef *xshut_port,
|
||||
uint16_t xshut_pin,
|
||||
GPIO_TypeDef *gpio1_port,
|
||||
uint16_t gpio1_pin);
|
||||
|
||||
VL53L0X_Error VL53L0X_PlatformSetXShut(VL53L0X_DEV Dev, GPIO_PinState state);
|
||||
VL53L0X_Error VL53L0X_PlatformBootDevice(VL53L0X_DEV Dev, uint32_t reset_low_ms, uint32_t boot_wait_ms);
|
||||
VL53L0X_Error VL53L0X_PlatformChangeAddress(VL53L0X_DEV Dev, uint8_t new_addr_8bit);
|
||||
uint32_t VL53L0X_PlatformGetTick(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* VL53L0X_PLATFORM_H */
|
||||
18
App/VL53L0X_API/platform/vl53l0x_platform_log.h
Normal file
18
App/VL53L0X_API/platform/vl53l0x_platform_log.h
Normal file
@@ -0,0 +1,18 @@
|
||||
#ifndef _VL53L0X_PLATFORM_LOG_H_
|
||||
#define _VL53L0X_PLATFORM_LOG_H_
|
||||
|
||||
/* 1. 解决 TRACE_MODULE_API 未定义的报错 */
|
||||
#define TRACE_MODULE_API 0
|
||||
|
||||
/* 2. 强行屏蔽官方所有【带下划线】的底层日志宏 */
|
||||
#define _LOG_FUNCTION_START(...) (void)0
|
||||
#define _LOG_FUNCTION_END(...) (void)0
|
||||
#define _LOG_FUNCTION_END_FMT(...) (void)0
|
||||
|
||||
/* 3. 强行屏蔽官方所有【不带下划线】的普通日志宏 */
|
||||
#define LOG_FUNCTION_START(...) (void)0
|
||||
#define LOG_FUNCTION_END(...) (void)0
|
||||
#define LOG_FUNCTION_END_FMT(...) (void)0
|
||||
#define VL53L0X_ErrLog(...) (void)0
|
||||
|
||||
#endif /* _VL53L0X_PLATFORM_LOG_H_ */
|
||||
15
App/VL53L0X_API/platform/vl53l0x_types.h
Normal file
15
App/VL53L0X_API/platform/vl53l0x_types.h
Normal file
@@ -0,0 +1,15 @@
|
||||
#ifndef _VL53L0X_TYPES_H_
|
||||
#define _VL53L0X_TYPES_H_
|
||||
|
||||
/* 引入现代 C 语言标准整数类型库 */
|
||||
#include <stdint.h>
|
||||
#include <stddef.h>
|
||||
|
||||
#ifndef NULL
|
||||
#define NULL 0
|
||||
#endif
|
||||
|
||||
/* 核心修复:填补 ST 官方定义的定点数类型 */
|
||||
typedef uint32_t FixPoint1616_t;
|
||||
|
||||
#endif /* _VL53L0X_TYPES_H_ */
|
||||
Reference in New Issue
Block a user