diff --git a/drivers/sensor/CMakeLists.txt b/drivers/sensor/CMakeLists.txt index 61333fe6121dd..ff62725441f84 100644 --- a/drivers/sensor/CMakeLists.txt +++ b/drivers/sensor/CMakeLists.txt @@ -55,5 +55,6 @@ add_subdirectory_ifdef(CONFIG_TH02 th02) add_subdirectory_ifdef(CONFIG_TMP007 tmp007) add_subdirectory_ifdef(CONFIG_TMP112 tmp112) add_subdirectory_ifdef(CONFIG_VL53L0X vl53l0x) +add_subdirectory_ifdef(CONFIG_VL53L1X vl53l1x) zephyr_sources_ifdef(CONFIG_USERSPACE sensor_handlers.c) diff --git a/drivers/sensor/Kconfig b/drivers/sensor/Kconfig index 0bf9a127ba3a1..0035327961465 100644 --- a/drivers/sensor/Kconfig +++ b/drivers/sensor/Kconfig @@ -135,4 +135,6 @@ source "drivers/sensor/tmp112/Kconfig" source "drivers/sensor/vl53l0x/Kconfig" +source "drivers/sensor/vl53l1x/Kconfig" + endif # SENSOR diff --git a/drivers/sensor/vl53l1x/CMakeLists.txt b/drivers/sensor/vl53l1x/CMakeLists.txt new file mode 100644 index 0000000000000..9df21487227b5 --- /dev/null +++ b/drivers/sensor/vl53l1x/CMakeLists.txt @@ -0,0 +1,8 @@ +# SPDX-License-Identifier: Apache-2.0 + +zephyr_library() + +zephyr_library_sources( + vl53l1.c + vl53l1_platform.c +) diff --git a/drivers/sensor/vl53l1x/Kconfig b/drivers/sensor/vl53l1x/Kconfig new file mode 100644 index 0000000000000..9391cbf631421 --- /dev/null +++ b/drivers/sensor/vl53l1x/Kconfig @@ -0,0 +1,57 @@ +# Kconfig - VL53L1X time of flight sensor configuration options + +# +# Copyright (c) 2019 Makaio GmbH +# +# SPDX-License-Identifier: Apache-2.0 +# + +menuconfig VL53L1X + bool "VL53L1X time of flight sensor" + depends on I2C && HAS_DTS_I2C + select HAS_STLIB + help + Enable driver for VL53L1X I2C-based time of flight sensor. + +if VL53L1X + +config VL53L1X_XSHUT_CONTROL_ENABLE + bool "Enable XSHUT pin control" + help + Enable it if XSHUT pin is controlled by host. + +config VL53L1X_XSHUT_GPIO_DEV_NAME + string "GPIO device" + depends on VL53L1X_XSHUT_CONTROL_ENABLE + help + The device name of the GPIO device to which the VL53L1X xshut pin + is connected. + +config VL53L1X_XSHUT_GPIO_PIN_NUM + int "Interrupt GPIO pin number" + depends on VL53L1X_XSHUT_CONTROL_ENABLE + help + The number of the GPIO on which the xshut signal from the VL53L1X + is connected. + +config VL53L1X_PROXIMITY_THRESHOLD + int "Proximity threshold in millimeters" + default 100 + help + Threshold used for proximity detection when sensor is used with SENSOR_CHAN_PROX. + +config VL53L1X_MEAS_TIMING_BUDGET + int "Default measurement timing budget" + default 50 + help + Timing budget for measurements in ms. + Can be overridden in dts with measurement-timing-budget. + +config VL53L1X_INTERMEASUREMENT_PERIOD + int "Inter measurement period in ms" + default 500 + help + Time between measurements in ms. Must be > timing budget + 4ms. + Can be overridden in dts with inter-measurement-period. + +endif # VL53L1X diff --git a/drivers/sensor/vl53l1x/vl53l1.c b/drivers/sensor/vl53l1x/vl53l1.c new file mode 100644 index 0000000000000..650560925b5ff --- /dev/null +++ b/drivers/sensor/vl53l1x/vl53l1.c @@ -0,0 +1,198 @@ +/* vl53l1.c - Driver for ST VL53L1X time of flight sensor */ +/* + * Copyright (c) 2017 STMicroelectronics + * Copyright (c) 2019 Makaio GmbH + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "vl53l1_api.h" +#include "vl53l1_platform.h" + + + +#define LOG_LEVEL CONFIG_SENSOR_LOG_LEVEL +LOG_MODULE_REGISTER(VL53L1X); + +struct vl53l1x_pin_config { + bool use; + u32_t gpios_pin; + char *gpios_ctrl; +}; + +struct vl53l1x_data { + char *i2c_dev_name; + u16_t i2c_addr; + VL53L1_Dev_t vl53l1x; + VL53L1_RangingMeasurementData_t RangingMeasurementData; + int inter_measurement_period; + int timing_budget; + struct vl53l1x_pin_config irq_config; + struct vl53l1x_pin_config xshut_config; + u8_t instance_id; +}; + +static void vl53l1x_print_device_settings(struct device *dev) +{ + struct vl53l1x_data *drv_data = dev->driver_data; + + struct vl53l1x_pin_config *irq_cfg = &drv_data->irq_config; + + LOG_DBG("Name:\t\t%s", log_strdup(dev->config->name)); + LOG_DBG("Instance ID:\t%u", drv_data->instance_id); + LOG_DBG("I2C Address:\t0x%02x", drv_data->i2c_addr); + + if (irq_cfg && irq_cfg->use) { + LOG_DBG("IRQ:\t\tenabled, ctrl %s, pin %u", + irq_cfg->gpios_ctrl, irq_cfg->gpios_pin); + } else { + LOG_DBG("IRQ:\t\tdisabled"); + } + + struct vl53l1x_pin_config *xshut_cfg = &drv_data->xshut_config; + + if (xshut_cfg && xshut_cfg->use) { + LOG_DBG("XSHUT:\t\tenabled, ctrl %s, pin %u", + xshut_cfg->gpios_ctrl, xshut_cfg->gpios_pin); + } else { + LOG_DBG("XSHUT:\t\tdisabled"); + } + + +} + +static int vl53l1x_init(struct device *dev) +{ + struct vl53l1x_data *drv_data = dev->driver_data; + VL53L1_Error ret; + u16_t vl53l1x_id = 0U; + VL53L1_DeviceInfo_t vl53l1x_dev_info; + + LOG_DBG("enter in %s", __func__); + + vl53l1x_print_device_settings(dev); + + VL53L1_Dev_t vl53l1dev = { + .I2cDevAddr = drv_data->i2c_addr, + .I2cHandle = device_get_binding(drv_data->i2c_dev_name) + }; + drv_data->vl53l1x = vl53l1dev; + + if (vl53l1dev.I2cHandle == NULL) { + LOG_ERR("Could not get pointer to %s device.", + drv_data->i2c_dev_name); + return -EINVAL; + } + + ret = VL53L1_WaitDeviceBooted(&drv_data->vl53l1x); + + if (ret) { + return -ETIMEDOUT; + } + + LOG_DBG("VL53L1_WaitDeviceBooted succeeded"); + + /* sensor init */ + ret = VL53L1_DataInit(&drv_data->vl53l1x); + if (ret < 0) { + LOG_ERR("VL53L1X_DataInit return error (%d)", ret); + return -ENOTSUP; + } + + LOG_DBG("VL53L1_DataInit succeeded"); + + /* static init */ + ret = VL53L1_StaticInit(&drv_data->vl53l1x); + if (ret < 0) { + LOG_ERR("VL53L1_StaticInit return error (%d)", ret); + return -ENOTSUP; + } + + LOG_DBG("VL53L1_StaticInit succeeded"); + + ret = VL53L1_SetDistanceMode(&drv_data->vl53l1x, + VL53L1_DISTANCEMODE_LONG); + if (ret < 0) { + LOG_ERR("VL53L1_SetDistanceMode return error (%d)", ret); + return -ENOTSUP; + } + + LOG_DBG("VL53L1_SetDistanceMode succeeded"); + + ret = VL53L1_StartMeasurement(&drv_data->vl53l1x); + + return 0; +} + +#define VL53L1X_PIN_CFG(id, pintype) \ +static const struct vl53l1x_pin_config\ + vl53l1x_##pintype##_##id##_cfg = { \ + .use = true, \ + .gpios_pin = \ + DT_INST_##id##_ST_VL53L1X_##pintype##_GPIOS_PIN, \ + .gpios_ctrl = \ + DT_INST_##id##_ST_VL53L1X_##pintype##_GPIOS_CONTROLLER \ +} + +#define VL53L1X_NOPIN_CFG(id, pintype) \ +static const struct vl53l1x_pin_config \ + vl53l1x_##pintype##_##id##_cfg = { \ +/* this is unnecessary, but let's keep it for clarity */ \ + .use = false, \ + } + + + + +#define VL53L1X_INST_INIT(id) \ +static struct vl53l1x_data vl53l1x_driver_##id##_data = { \ + .instance_id = id, \ + .i2c_dev_name = DT_INST_##id##_ST_VL53L1X_BUS_NAME, \ + .i2c_addr = DT_INST_##id##_ST_VL53L1X_BASE_ADDRESS, \ + .irq_config = vl53l1x_IRQ_##id##_cfg, \ + .xshut_config = vl53l1x_XSHUT_##id##_cfg, \ + .inter_measurement_period = \ + DT_INST_##id##_ST_VL53L1X_INTER_MEASUREMENT_PERIOD, \ + .timing_budget = \ + DT_INST_##id##_ST_VL53L1X_MEASUREMENT_TIMING_BUDGET \ +}; \ +DEVICE_AND_API_INIT(vl53l1x, \ + DT_INST_##id##_ST_VL53L1X_LABEL, \ + vl53l1x_init, \ + &vl53l1x_driver_##id##_data, \ +NULL, POST_KERNEL, CONFIG_SENSOR_INIT_PRIORITY, NULL) + +#ifdef DT_INST_0_ST_VL53L1X_BASE_ADDRESS +#ifndef DT_INST_0_ST_VL53L1X_INTER_MEASUREMENT_PERIOD +#define DT_INST_0_ST_VL53L1X_INTER_MEASUREMENT_PERIOD + CONFIG_VL53L1X_INTERMEASUREMENT_PERIOD +#endif +#ifndef DT_INST_0_ST_VL53L1X_MEASUREMENT_TIMING_BUDGET +#define DT_INST_0_ST_VL53L1X_MEASUREMENT_TIMING_BUDGET + CONFIG_VL53L1X_MEAS_TIMING_BUDGET +#endif +#ifdef DT_INST_0_ST_VL53L1X_IRQ_GPIOS_PIN +VL53L1X_PIN_CFG(0, IRQ); +#else +VL53L1X_NOPIN_CFG(0, IRQ); +#endif +#ifdef DT_INST_0_ST_VL53L1X_XSHUT_GPIOS_PIN +VL53L1X_PIN_CFG(0, XSHUT); +#else +VL53L1X_NOPIN_CFG(0, XSHUT); +#endif +VL53L1X_INST_INIT(0); +#endif + diff --git a/drivers/sensor/vl53l1x/vl53l1_platform.c b/drivers/sensor/vl53l1x/vl53l1_platform.c new file mode 100644 index 0000000000000..c00e2c1508792 --- /dev/null +++ b/drivers/sensor/vl53l1x/vl53l1_platform.c @@ -0,0 +1,340 @@ +/* + * Copyright (c) 2017, STMicroelectronics - All Rights Reserved + * Copyright (c) 2019 Makaio GmbH + * + * This file is part of VL53L1 Core and is dual licensed, + * either 'STMicroelectronics + * Proprietary license' + * or 'BSD 3-clause "New" or "Revised" License' , at your option. + * + ****************************************************************************** + * + * 'STMicroelectronics Proprietary license' + * + ****************************************************************************** + * + * License terms: STMicroelectronics Proprietary in accordance with licensing + * terms at www.st.com/sla0081 + * + * STMicroelectronics confidential + * Reproduction and Communication of this document is strictly prohibited + * unless specifically authorized in writing by STMicroelectronics. + * + * + ****************************************************************************** + * + * Alternatively, VL53L1 Core may be distributed under the terms of + * 'BSD 3-clause "New" or "Revised" License', in which case the following + * provisions apply instead of the ones mentioned above : + * + ****************************************************************************** + * + * License terms: BSD 3-clause "New" or "Revised" License. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. 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. + * + * 3. Neither the name of the copyright holder 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 AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS 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 "vl53l1_platform.h" +#include "vl53l1_api.h" +#include +#include +#include +#include +#include +#include + +#define LOG_LEVEL CONFIG_SENSOR_LOG_LEVEL +LOG_MODULE_DECLARE(VL53L1X); + +#include + +VL53L1_Error VL53L1_WriteMulti(VL53L1_DEV Dev, u16_t index, + u8_t *pdata, us32_t count) +{ + LOG_DBG("Write multi (count: %u)", count); + + VL53L1_Error Status = VL53L1_ERROR_NONE; + s32_t status_int; + u8_t I2CBuffer[count + 2]; + + u8_t reg_addr[] = { index >> 8, index & 0xff }; + + memcpy(&I2CBuffer[2], pdata, count); + + status_int = i2c_write(Dev->I2cHandle, I2CBuffer, count + 2, + Dev->I2cDevAddr); + + + if (status_int < 0) { + Status = VL53L1_ERROR_CONTROL_INTERFACE; + LOG_ERR("i2c_write failed (%d)", status_int); + } + + return Status; +} + +VL53L1_Error VL53L1_ReadMulti(VL53L1_DEV Dev, u16_t index, + u8_t *pdata, us32_t count) +{ + LOG_DBG("Read multi"); + + VL53L1_Error Status = VL53L1_ERROR_NONE; + s32_t status_int; + + u8_t reg_addr[] = { index >> 8, index & 0xff }; + + status_int = i2c_write_read(Dev->I2cHandle, Dev->I2cDevAddr, + reg_addr, ARRAY_SIZE(reg_addr), + pdata, count); + + if (status_int < 0) { + Status = VL53L1_ERROR_CONTROL_INTERFACE; + LOG_ERR("i2c_write_read failed (%d)", Status); + } + + return Status; +} + +VL53L1_Error VL53L1_WrByte(VL53L1_DEV Dev, u16_t index, u8_t data) +{ + LOG_DBG("Write byte"); + VL53L1_Error Status = VL53L1_ERROR_NONE; + s32_t status_int; + + u8_t I2CBuffer[] = { + (index >> 8), + (index & 0xff), + data + }; + + status_int = i2c_write(Dev->I2cHandle, I2CBuffer, + ARRAY_SIZE(I2CBuffer), Dev->I2cDevAddr); + + if (status_int < 0) { + Status = VL53L1_ERROR_CONTROL_INTERFACE; + LOG_ERR("i2c_write failed (%d)", Status); + } + + return Status; +} + +VL53L1_Error VL53L1_WrWord(VL53L1_DEV Dev, u16_t index, u16_t data) +{ + LOG_DBG("Write word"); + + VL53L1_Error Status = VL53L1_ERROR_NONE; + s32_t status_int; + u8_t I2CBuffer[] = { + (index >> 8), + (index & 0xff), + data >> 8, + data & 0x00FF + }; + + status_int = i2c_write(Dev->I2cHandle, I2CBuffer, + ARRAY_SIZE(I2CBuffer), Dev->I2cDevAddr); + + if (status_int < 0) { + Status = VL53L1_ERROR_CONTROL_INTERFACE; + LOG_ERR("i2c_write failed (%d)", Status); + } + + return Status; +} + +VL53L1_Error VL53L1_WrDWord(VL53L1_DEV Dev, u16_t index, us32_t data) +{ + VL53L1_Error Status = VL53L1_ERROR_NONE; + s32_t status_int; + u8_t I2CBuffer[] = { + (index >> 8), + (index & 0xff), + (data >> 24) & 0xFF, + (data >> 16) & 0xFF, + (data >> 8) & 0xFF, + (data >> 0) & 0xFF + }; + + status_int = i2c_write(Dev->I2cHandle, I2CBuffer, + ARRAY_SIZE(I2CBuffer), Dev->I2cDevAddr); + + if (status_int < 0) { + Status = VL53L1_ERROR_CONTROL_INTERFACE; + LOG_ERR("i2c_write failed (%d)", Status); + } + + return Status; +} + +VL53L1_Error VL53L1_UpdateByte(VL53L1_DEV Dev, u16_t index, + u8_t AndData, u8_t OrData) +{ + VL53L1_Error Status = VL53L1_ERROR_NONE; + u8_t data; + + s32_t status_int = VL53L1_RdByte(Dev, index, &data); + + if (status_int < 0) { + return VL53L1_ERROR_CONTROL_INTERFACE; + } + + data = (data & AndData) | OrData; + status_int = VL53L1_WrByte(Dev, index, data); + if (status_int != 0) { + return VL53L1_ERROR_CONTROL_INTERFACE; + } + + return Status; +} + +VL53L1_Error VL53L1_RdByte(VL53L1_DEV Dev, u16_t index, u8_t *data) +{ + LOG_DBG("Read byte"); + + VL53L1_Error Status = VL53L1_ERROR_NONE; + s32_t status_int; + + u8_t reg_addr[] = { index >> 8, index & 0xff }; + + status_int = i2c_write_read(Dev->I2cHandle, Dev->I2cDevAddr, + reg_addr, ARRAY_SIZE(reg_addr), + data, 1); + + if (status_int < 0) { + Status = VL53L1_ERROR_CONTROL_INTERFACE; + LOG_ERR("i2c_write_read failed (%d)", Status); + } + + return Status; +} + +VL53L1_Error VL53L1_RdWord(VL53L1_DEV Dev, u16_t index, u16_t *data) +{ + LOG_DBG("Read word"); + + VL53L1_Error Status = VL53L1_ERROR_NONE; + + s32_t status_int; + + u8_t reg_addr[] = { index >> 8, index & 0xff }; + u8_t buf[2]; + + status_int = i2c_write_read(Dev->I2cHandle, Dev->I2cDevAddr, + reg_addr, ARRAY_SIZE(reg_addr), + buf, ARRAY_SIZE(buf)); + + if (status_int < 0) { + LOG_ERR("i2c_write_read failed"); + return -EIO; + } + + *data = ((u16_t)buf[0] << 8) + (u16_t)buf[1]; + + return Status; +} + +VL53L1_Error VL53L1_RdDWord(VL53L1_DEV Dev, u16_t index, us32_t *data) +{ + VL53L1_Error Status = VL53L1_ERROR_NONE; + + LOG_ERR("Implement %s", log_strdup(__func__)); + + return Status; +} + +VL53L1_Error VL53L1_GetTickCount( + us32_t *ptick_count_ms) +{ + VL53L1_Error status = VL53L1_ERROR_NONE; + + *ptick_count_ms = k_uptime_get_32(); + return status; +} + +VL53L1_Error VL53L1_GetTimerFrequency(s32_t *ptimer_freq_hz) +{ + LOG_ERR("Not implemented"); + return VL53L1_ERROR_NOT_IMPLEMENTED; +} + +VL53L1_Error VL53L1_WaitMs(VL53L1_Dev_t *pdev, s32_t wait_ms) +{ + VL53L1_Error status = VL53L1_ERROR_NONE; + + k_sleep(wait_ms); + + return status; +} + +VL53L1_Error VL53L1_WaitUs(VL53L1_Dev_t *pdev, s32_t wait_us) +{ + VL53L1_Error status = VL53L1_ERROR_NONE; + + k_busy_wait(wait_us); + + return status; +} + +VL53L1_Error VL53L1_WaitValueMaskEx( + VL53L1_Dev_t *pdev, + us32_t timeout_ms, + u16_t index, + u8_t value, + u8_t mask, + us32_t poll_delay_ms) +{ + u8_t register_value = 0; + + VL53L1_Error status = VL53L1_ERROR_NONE; + + s32_t attempts = timeout_ms / poll_delay_ms; + + for (s32_t x = 0; x < attempts; x++) { + + status = VL53L1_RdByte( + pdev, + index, + ®ister_value); + + if (status == VL53L1_ERROR_NONE && + (register_value & mask) == value) { + return VL53L1_ERROR_NONE; + } + k_sleep(poll_delay_ms); + } + + return VL53L1_ERROR_TIME_OUT; +} + + + + diff --git a/drivers/sensor/vl53l1x/vl53l1_platform.h b/drivers/sensor/vl53l1x/vl53l1_platform.h new file mode 100644 index 0000000000000..970cdecb3ee5b --- /dev/null +++ b/drivers/sensor/vl53l1x/vl53l1_platform.h @@ -0,0 +1,173 @@ +/* + * Copyright (c) 2017, STMicroelectronics - All Rights Reserved + * + * This file is part of VL53L1 Core and is dual licensed, + * either 'STMicroelectronics + * Proprietary license' + * or 'BSD 3-clause "New" or "Revised" License' , at your option. + * + ****************************************************************************** + * + * 'STMicroelectronics Proprietary license' + * + ****************************************************************************** + * + * License terms: STMicroelectronics Proprietary in accordance with licensing + * terms at www.st.com/sla0081 + * + * STMicroelectronics confidential + * Reproduction and Communication of this document is strictly prohibited + * unless specifically authorized in writing by STMicroelectronics. + * + * + ****************************************************************************** + * + * Alternatively, VL53L1 Core may be distributed under the terms of + * 'BSD 3-clause "New" or "Revised" License', in which case the following + * provisions apply instead of the ones mentioned above : + * + ****************************************************************************** + * + * License terms: BSD 3-clause "New" or "Revised" License. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. 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. + * + * 3. Neither the name of the copyright holder 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 AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS 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 _VL53L1_PLATFORM_H_ +#define _VL53L1_PLATFORM_H_ + +#include "vl53l1_ll_def.h" +#include "vl53l1_platform_log.h" + +#define VL53L1_IPP_API +#include "vl53l1_platform_user_data.h" + +#ifdef __cplusplus +extern "C" +{ +#endif + +VL53L1_Error VL53L1_CommsInitialise( + VL53L1_Dev_t *pdev, + u8_t comms_type, + u16_t comms_speed_khz); + +VL53L1_Error VL53L1_CommsClose( + VL53L1_Dev_t *pdev); + +VL53L1_Error VL53L1_WriteMulti( + VL53L1_Dev_t *pdev, + u16_t index, + u8_t *pdata, + u32_t count); + +VL53L1_Error VL53L1_ReadMulti( + VL53L1_Dev_t *pdev, + u16_t index, + u8_t *pdata, + u32_t count); + +VL53L1_Error VL53L1_WrByte( + VL53L1_Dev_t *pdev, + u16_t index, + u8_t VL53L1_PRM_00005); + +VL53L1_Error VL53L1_WrWord( + VL53L1_Dev_t *pdev, + u16_t index, + u16_t VL53L1_PRM_00005); + +VL53L1_Error VL53L1_WrDWord( + VL53L1_Dev_t *pdev, + u16_t index, + u32_t VL53L1_PRM_00005); + +VL53L1_Error VL53L1_RdByte( + VL53L1_Dev_t *pdev, + u16_t index, + u8_t *pdata); + +VL53L1_Error VL53L1_RdWord( + VL53L1_Dev_t *pdev, + u16_t index, + u16_t *pdata); + +VL53L1_Error VL53L1_RdDWord( + VL53L1_Dev_t *pdev, + u16_t index, + u32_t *pdata); + +VL53L1_Error VL53L1_WaitUs( + VL53L1_Dev_t *pdev, + int32_t wait_us); + +VL53L1_Error VL53L1_WaitMs( + VL53L1_Dev_t *pdev, + int32_t wait_ms); + +VL53L1_Error VL53L1_GetTimerFrequency(int32_t *ptimer_freq_hz); + +VL53L1_Error VL53L1_GetTimerValue(int32_t *ptimer_count); + +VL53L1_Error VL53L1_GpioSetMode(u8_t pin, u8_t mode); + +VL53L1_Error VL53L1_GpioSetValue(u8_t pin, u8_t value); + +VL53L1_Error VL53L1_GpioGetValue(u8_t pin, u8_t *pvalue); + +VL53L1_Error VL53L1_GpioXshutdown(u8_t value); + +VL53L1_Error VL53L1_GpioCommsSelect(u8_t value); + +VL53L1_Error VL53L1_GpioPowerEnable(u8_t value); + +VL53L1_Error VL53L1_GpioInterruptEnable( + void (*function)(void), + u8_t edge_type); + +VL53L1_Error VL53L1_GpioInterruptDisable(void); + +VL53L1_Error VL53L1_GetTickCount( + u32_t *ptime_ms); + +VL53L1_Error VL53L1_WaitValueMaskEx( + VL53L1_Dev_t *pdev, + u32_t timeout_ms, + u16_t index, + u8_t value, + u8_t mask, + u32_t poll_delay_ms); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/drivers/sensor/vl53l1x/vl53l1_platform_log.h b/drivers/sensor/vl53l1x/vl53l1_platform_log.h new file mode 100644 index 0000000000000..a6a13858288e9 --- /dev/null +++ b/drivers/sensor/vl53l1x/vl53l1_platform_log.h @@ -0,0 +1,265 @@ +/* + * Copyright (c) 2017, STMicroelectronics - All Rights Reserved + * + * This file is part of VL53L1 Core and is dual licensed, + * either 'STMicroelectronics + * Proprietary license' + * or 'BSD 3-clause "New" or "Revised" License' , at your option. + * + ****************************************************************************** + * + * 'STMicroelectronics Proprietary license' + * + ****************************************************************************** + * + * License terms: STMicroelectronics Proprietary in accordance with licensing + * terms at www.st.com/sla0081 + * + * STMicroelectronics confidential + * Reproduction and Communication of this document is strictly prohibited + * unless specifically authorized in writing by STMicroelectronics. + * + * + ****************************************************************************** + * + * Alternatively, VL53L1 Core may be distributed under the terms of + * 'BSD 3-clause "New" or "Revised" License', in which case the following + * provisions apply instead of the ones mentioned above : + * + ****************************************************************************** + * + * License terms: BSD 3-clause "New" or "Revised" License. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. 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. + * + * 3. Neither the name of the copyright holder 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 AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS 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 vl53l1_platform_log.h + * + * @brief EwokPlus25 platform logging function definition + */ + + +#ifndef _VL53L1_PLATFORM_LOG_H_ +#define _VL53L1_PLATFORM_LOG_H_ + + +#ifdef VL53L1_LOG_ENABLE + #include "vl53l1_platform_user_config.h" + + #ifdef _MSC_VER + # define EWOKPLUS_EXPORTS __declspec(dllexport) + #else + # define EWOKPLUS_EXPORTS + #endif + + #include "vl53l1_types.h" + + #ifdef __cplusplus +extern "C" { + #endif + + #include + +/** + * @brief Set the level, output and specific functions for module logging. + * + * + * @param filename - full path of output log file, NULL for print to stdout + * + * @param modules - Module or None or All to trace + * VL53L1_TRACE_MODULE_NONE + * VL53L1_TRACE_MODULE_API + * VL53L1_TRACE_MODULE_CORE + * VL53L1_TRACE_MODULE_TUNING + * VL53L1_TRACE_MODULE_CHARACTERISATION + * VL53L1_TRACE_MODULE_PLATFORM + * VL53L1_TRACE_MODULE_ALL + * + * @param level - trace level + * VL53L1_TRACE_LEVEL_NONE + * VL53L1_TRACE_LEVEL_ERRORS + * VL53L1_TRACE_LEVEL_WARNING + * VL53L1_TRACE_LEVEL_INFO + * VL53L1_TRACE_LEVEL_DEBUG + * VL53L1_TRACE_LEVEL_ALL + * VL53L1_TRACE_LEVEL_IGNORE + * + * @param functions - function level to trace; + * VL53L1_TRACE_FUNCTION_NONE + * VL53L1_TRACE_FUNCTION_I2C + * VL53L1_TRACE_FUNCTION_ALL + * + * @return status - always VL53L1_ERROR_NONE + * + */ + + #define VL53L1_TRACE_LEVEL_NONE 0x00000000 + #define VL53L1_TRACE_LEVEL_ERRORS 0x00000001 + #define VL53L1_TRACE_LEVEL_WARNING 0x00000002 + #define VL53L1_TRACE_LEVEL_INFO 0x00000004 + #define VL53L1_TRACE_LEVEL_DEBUG 0x00000008 + #define VL53L1_TRACE_LEVEL_ALL 0x00000010 + #define VL53L1_TRACE_LEVEL_IGNORE 0x00000020 + + #define VL53L1_TRACE_FUNCTION_NONE 0x00000000 + #define VL53L1_TRACE_FUNCTION_I2C 0x00000001 + #define VL53L1_TRACE_FUNCTION_ALL 0x7fffffff + + #define VL53L1_TRACE_MODULE_NONE 0x00000000 + #define VL53L1_TRACE_MODULE_API 0x00000001 + #define VL53L1_TRACE_MODULE_CORE 0x00000002 + #define VL53L1_TRACE_MODULE_PROTECTED 0x00000004 + #define VL53L1_TRACE_MODULE_HISTOGRAM 0x00000008 + #define VL53L1_TRACE_MODULE_REGISTERS 0x00000010 + #define VL53L1_TRACE_MODULE_PLATFORM 0x00000020 + #define VL53L1_TRACE_MODULE_NVM 0x00000040 + #define VL53L1_TRACE_MODULE_CALIBRATION_DATA 0x00000080 + #define VL53L1_TRACE_MODULE_NVM_DATA 0x00000100 + #define VL53L1_TRACE_MODULE_HISTOGRAM_DATA 0x00000200 + #define VL53L1_TRACE_MODULE_RANGE_RESULTS_DATA 0x00000400 + #define VL53L1_TRACE_MODULE_XTALK_DATA 0x00000800 + #define VL53L1_TRACE_MODULE_OFFSET_DATA 0x00001000 + #define VL53L1_TRACE_MODULE_DATA_INIT 0x00002000 + #define VL53L1_TRACE_MODULE_REF_SPAD_CHAR 0x00004000 + #define VL53L1_TRACE_MODULE_SPAD_RATE_MAP 0x00008000 + #ifdef PAL_EXTENDED + #define VL53L1_TRACE_MODULE_SPAD 0x01000000 + #define VL53L1_TRACE_MODULE_FMT 0x02000000 + #define VL53L1_TRACE_MODULE_UTILS 0x04000000 + #define VL53L1_TRACE_MODULE_BENCH_FUNCS 0x08000000 + #endif + #define VL53L1_TRACE_MODULE_CUSTOMER_API 0x40000000 + #define VL53L1_TRACE_MODULE_ALL 0x7fffffff + + +extern u32_t _trace_level; + +/* + * NOTE: dynamically exported if we enable logging. + * this way, Python interfaces can access this function, but we don't + * need to include it in the .def files. + */ +EWOKPLUS_EXPORTS int8_t VL53L1_trace_config( + char *filename, + u32_t modules, + u32_t level, + u32_t functions); + +/** + * @brief Print trace module function. + * + * @param module - ?? + * @param level - ?? + * @param function - ?? + * @param format - ?? + * + */ + +EWOKPLUS_EXPORTS void VL53L1_trace_print_module_function( + u32_t module, + u32_t level, + u32_t function, + const char *format, ...); + +/** + * @brief Get global _trace_functions parameter + * + * @return _trace_functions + */ + +u32_t VL53L1_get_trace_functions(void); + +/** + * @brief Set global _trace_functions parameter + * + * @param[in] function : new function code + */ + +void VL53L1_set_trace_functions(u32_t function); + + +/* + * @brief Returns the current system tick count in [ms] + * + * @return time_ms : current time in [ms] + * + */ + +u32_t VL53L1_clock(void); + + #define LOG_GET_TIME() \ + ((int)VL53L1_clock()) + + #define _LOG_TRACE_PRINT(module, level, function, ...) \ + VL53L1_trace_print_module_function(module, level, \ + function, ## __VA_ARGS__) + + #define _LOG_FUNCTION_START(module, fmt, ...) \ + VL53L1_trace_print_module_function(module, _trace_level, \ + VL53L1_TRACE_FUNCTION_ALL, "%6ld %s "fmt "\n", \ + LOG_GET_TIME(), __func__, ## __VA_ARGS__) + + #define _LOG_FUNCTION_END(module, status, ...) \ + VL53L1_trace_print_module_function(module, _trace_level, \ + VL53L1_TRACE_FUNCTION_ALL, "%6ld %s %d\n", \ + LOG_GET_TIME(), __func__, (int)status, ## __VA_ARGS__) + + #define _LOG_FUNCTION_END_FMT(module, status, fmt, ...) \ + VL53L1_trace_print_module_function(module, _trace_level, \ + VL53L1_TRACE_FUNCTION_ALL, "%6ld %s %d "fmt "\n", \ + LOG_GET_TIME(), __func__, (int)status, ## __VA_ARGS__) + + #define _LOG_GET_TRACE_FUNCTIONS() \ + VL53L1_get_trace_functions() + + #define _LOG_SET_TRACE_FUNCTIONS(functions) \ + VL53L1_set_trace_functions(functions) + + #define _LOG_STRING_BUFFER(x) char x[VL53L1_MAX_STRING_LENGTH] + + #ifdef __cplusplus +} + #endif + +#else /* VL53L1_LOG_ENABLE - no logging */ + + #define _LOG_TRACE_PRINT(module, level, function, ...) + #define _LOG_FUNCTION_START(module, fmt, ...) + #define _LOG_FUNCTION_END(module, status, ...) + #define _LOG_FUNCTION_END_FMT(module, status, fmt, ...) + #define _LOG_GET_TRACE_FUNCTIONS() 0 + #define _LOG_SET_TRACE_FUNCTIONS(functions) + #define _LOG_STRING_BUFFER(x) + +#endif /* VL53L1_LOG_ENABLE */ + +#endif /* _VL53L1_PLATFORM_LOG_H_ */ diff --git a/drivers/sensor/vl53l1x/vl53l1_platform_user_config.h b/drivers/sensor/vl53l1x/vl53l1_platform_user_config.h new file mode 100644 index 0000000000000..564f34f24e129 --- /dev/null +++ b/drivers/sensor/vl53l1x/vl53l1_platform_user_config.h @@ -0,0 +1,124 @@ +/* + * Copyright (c) 2017, STMicroelectronics - All Rights Reserved + * + * This file is part of VL53L1 Core and is dual licensed, + * either 'STMicroelectronics + * Proprietary license' + * or 'BSD 3-clause "New" or "Revised" License' , at your option. + * + ****************************************************************************** + * + * 'STMicroelectronics Proprietary license' + * + ****************************************************************************** + * + * License terms: STMicroelectronics Proprietary in accordance with licensing + * terms at www.st.com/sla0081 + * + * STMicroelectronics confidential + * Reproduction and Communication of this document is strictly prohibited + * unless specifically authorized in writing by STMicroelectronics. + * + * + ****************************************************************************** + * + * Alternatively, VL53L1 Core may be distributed under the terms of + * 'BSD 3-clause "New" or "Revised" License', in which case the following + * provisions apply instead of the ones mentioned above : + * + ****************************************************************************** + * + * License terms: BSD 3-clause "New" or "Revised" License. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. 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. + * + * 3. Neither the name of the copyright holder 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 AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS 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 vl53l1_platform_user_config.h + * + * @brief EwokPlus compile time user modifiable configuration + */ + + +#ifndef _VL53L1_PLATFORM_USER_CONFIG_H_ +#define _VL53L1_PLATFORM_USER_CONFIG_H_ + +#define VL53L1_BYTES_PER_WORD 2 +#define VL53L1_BYTES_PER_DWORD 4 + +/* Define polling delays */ +#define VL53L1_BOOT_COMPLETION_POLLING_TIMEOUT_MS 500 +#define VL53L1_RANGE_COMPLETION_POLLING_TIMEOUT_MS 2000 +#define VL53L1_TEST_COMPLETION_POLLING_TIMEOUT_MS 60000 + +#define VL53L1_POLLING_DELAY_MS 1 + +/* Define LLD TuningParms Page Base Address + * - Part of Patch_AddedTuningParms_11761 + */ +#define VL53L1_TUNINGPARM_PUBLIC_PAGE_BASE_ADDRESS 0x8000 +#define VL53L1_TUNINGPARM_PRIVATE_PAGE_BASE_ADDRESS 0xC000 + +#define VL53L1_GAIN_FACTOR__STANDARD_DEFAULT 0x0800 +/*!< Default standard ranging gain correction factor + * 1.11 format. 1.0 = 0x0800, 0.980 = 0x07D7 + */ + +#define VL53L1_OFFSET_CAL_MIN_EFFECTIVE_SPADS 0x0500 +/*!< Lower Limit for the MM1 effective SPAD count during offset + * calibration Format 8.8 0x0500 -> 5.0 effective SPADs + */ + +#define VL53L1_OFFSET_CAL_MAX_PRE_PEAK_RATE_MCPS 0x1900 +/*!< Max Limit for the pre range peak rate during offset + * calibration Format 9.7 0x1900 -> 50.0 Mcps. + * If larger then in pile up + */ + +#define VL53L1_OFFSET_CAL_MAX_SIGMA_MM 0x0040 +/*!< Max sigma estimate limit during offset calibration + * Check applies to pre-range, mm1 and mm2 ranges + * Format 14.2 0x0040 -> 16.0mm. + */ + +#define VL53L1_MAX_USER_ZONES 169 +/*!< Max number of user Zones - maximal limitation from + * FW stream divide - value of 254 + */ + +#define VL53L1_MAX_RANGE_RESULTS 2 +/*!< Allocates storage for return and reference restults */ + + +#define VL53L1_MAX_STRING_LENGTH 512 + +#endif /* _VL53L1_PLATFORM_USER_CONFIG_H_ */ + diff --git a/drivers/sensor/vl53l1x/vl53l1_platform_user_data.h b/drivers/sensor/vl53l1x/vl53l1_platform_user_data.h new file mode 100644 index 0000000000000..2604701d52a91 --- /dev/null +++ b/drivers/sensor/vl53l1x/vl53l1_platform_user_data.h @@ -0,0 +1,99 @@ + +/* + * Copyright (c) 2017, STMicroelectronics - All Rights Reserved + * + * This file is part of VL53L1 Core and is dual licensed, + * either 'STMicroelectronics + * Proprietary license' + * or 'BSD 3-clause "New" or "Revised" License' , at your option. + * + ****************************************************************************** + * + * 'STMicroelectronics Proprietary license' + * + ****************************************************************************** + * + * License terms: STMicroelectronics Proprietary in accordance with licensing + * terms at www.st.com/sla0081 + * + * STMicroelectronics confidential + * Reproduction and Communication of this document is strictly prohibited + * unless specifically authorized in writing by STMicroelectronics. + * + * + ****************************************************************************** + * + * Alternatively, VL53L1 Core may be distributed under the terms of + * 'BSD 3-clause "New" or "Revised" License', in which case the following + * provisions apply instead of the ones mentioned above : + * + ****************************************************************************** + * + * License terms: BSD 3-clause "New" or "Revised" License. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. 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. + * + * 3. Neither the name of the copyright holder 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 AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS 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 _VL53L1_PLATFORM_USER_DATA_H_ +#define _VL53L1_PLATFORM_USER_DATA_H_ +#include "vl53l1_def.h" +#include +#ifdef __cplusplus +extern "C" +{ +#endif + + +typedef struct device I2C_HandleTypeDef; + +typedef struct { + + VL53L1_DevData_t Data; + + u8_t I2cDevAddr; + u8_t comms_type; + u16_t comms_speed_khz; + u32_t new_data_ready_poll_duration_ms; + I2C_HandleTypeDef *I2cHandle; + +} VL53L1_Dev_t; + +typedef VL53L1_Dev_t *VL53L1_DEV; + +#define VL53L1DevDataGet(Dev, field) (Dev->Data.field) +#define VL53L1DevDataSet(Dev, field, VL53L1_PRM_00005) \ + ((Dev->Data.field) = (VL53L1_PRM_00005)) +#define VL53L1DevStructGetLLDriverHandle(Dev) (&Dev->Data.LLData) +#define VL53L1DevStructGetLLResultsHandle(Dev) (&Dev->Data.llresults) +#ifdef __cplusplus +} +#endif +#endif diff --git a/drivers/sensor/vl53l1x/vl53l1_platform_user_defines.h b/drivers/sensor/vl53l1x/vl53l1_platform_user_defines.h new file mode 100644 index 0000000000000..351c1030c7a1c --- /dev/null +++ b/drivers/sensor/vl53l1x/vl53l1_platform_user_defines.h @@ -0,0 +1,133 @@ +/* + * Copyright (c) 2017, STMicroelectronics - All Rights Reserved + * + * This file is part of VL53L1 Core and is dual licensed, + * either 'STMicroelectronics + * Proprietary license' + * or 'BSD 3-clause "New" or "Revised" License' , at your option. + * + ****************************************************************************** + * + * 'STMicroelectronics Proprietary license' + * + ****************************************************************************** + * + * License terms: STMicroelectronics Proprietary in accordance with licensing + * terms at www.st.com/sla0081 + * + * STMicroelectronics confidential + * Reproduction and Communication of this document is strictly prohibited + * unless specifically authorized in writing by STMicroelectronics. + * + * + ****************************************************************************** + * + * Alternatively, VL53L1 Core may be distributed under the terms of + * 'BSD 3-clause "New" or "Revised" License', in which case the following + * provisions apply instead of the ones mentioned above : + * + ****************************************************************************** + * + * License terms: BSD 3-clause "New" or "Revised" License. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. 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. + * + * 3. Neither the name of the copyright holder 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 AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS 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 _VL53L1_PLATFORM_USER_DEFINES_H_ +#define _VL53L1_PLATFORM_USER_DEFINES_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif + +/** + * @file vl53l1_platform_user_defines.h + * + * @brief All end user OS/platform/application definitions + */ + + +/** + * @def do_division_u + * @brief customer supplied division operation - 64-bit unsigned + * + * @param dividend unsigned 64-bit numerator + * @param divisor unsigned 64-bit denominator + */ +#define do_division_u(dividend, divisor) (dividend / divisor) + + +/** + * @def do_division_s + * @brief customer supplied division operation - 64-bit signed + * + * @param dividend signed 64-bit numerator + * @param divisor signed 64-bit denominator + */ +#define do_division_s(dividend, divisor) (dividend / divisor) + + +/** + * @def WARN_OVERRIDE_STATUS + * @brief customer supplied macro to optionally output info + * when a specific error has been overridden with + * success within the EwokPlus driver + * + * @param __X__ the macro which enabled the suppression + */ +#define WARN_OVERRIDE_STATUS(__X__) \ + trace_print ( \ + VL53L1_TRACE_LEVEL_WARNING, #__X__ \ + ) + +#define USE_I2C_2V8 + +#ifdef _MSC_VER +#define DISABLE_WARNINGS() { \ + __pragma(warning(push)); \ + __pragma(warning(disable:4127)); \ + } +#define ENABLE_WARNINGS() { \ + __pragma(warning(pop)); \ + } +#else + #define DISABLE_WARNINGS() + #define ENABLE_WARNINGS() +#endif + + +#ifdef __cplusplus +} +#endif + +#endif /* _VL53L1_PLATFORM_USER_DEFINES_H_ */ diff --git a/drivers/sensor/vl53l1x/vl53l1_types.h b/drivers/sensor/vl53l1x/vl53l1_types.h new file mode 100644 index 0000000000000..735b5578af6fb --- /dev/null +++ b/drivers/sensor/vl53l1x/vl53l1_types.h @@ -0,0 +1,32 @@ +/* vl53l0x_types.h - Zephyr customization of ST vl53l0x library, + * basic type definition. + */ + +/* + * Copyright (c) 2017 STMicroelectronics + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#ifndef ZEPHYR_DRIVERS_SENSOR_VL53L0X_VL53L1_TYPES_H_ +#define ZEPHYR_DRIVERS_SENSOR_VL53L0X_VL53L1_TYPES_H_ + + +/* Zephyr provides stdint.h and stddef.h, so this is enough to include it. + * If it was not the case, we would defined here all signed and unsigned + * basic types... + */ +#include +#include + +#ifndef NULL +#error "Error NULL definition should be done. Please add required include " +#endif + +/** use where fractional values are expected + * + * Given a floating point value f it's .16 bit point is (int)(f*(1<<16)) + */ +typedef u32_t FixPoint1616_t; + +#endif /* ZEPHYR_DRIVERS_SENSOR_VL53L0X_VL53L1_TYPES_H_ */ diff --git a/dts/bindings/sensor/st,vl53l1x.yaml b/dts/bindings/sensor/st,vl53l1x.yaml new file mode 100644 index 0000000000000..f485a05d55748 --- /dev/null +++ b/dts/bindings/sensor/st,vl53l1x.yaml @@ -0,0 +1,38 @@ +# +# Copyright (c) 2019, Makaio GmbH +# +# SPDX-License-Identifier: Apache-2.0 +# + +title: STMicroelectronics MEMS sensors VL53L1X +version: 0.1 + +description: > + This binding gives a base representation of VL53L1X Time Of Flight sensor + +inherits: + !include i2c-device.yaml + +properties: + compatible: + constraint: "st,vl53l1x" + + irq-gpios: + type: compound + category: optional + generation: define, use-prop-name + + xshut-gpios: + type: compound + category: optional + generation: define, use-prop-name + + measurement-timing-budget: + type: int + category: optional + description: Timing budget for measurements in ms + + inter-measurement-period: + type: int + category: optional + description: Interval between measurements in ms diff --git a/tests/drivers/build_all/dts_fixup.h b/tests/drivers/build_all/dts_fixup.h index 780bbabb487f2..a34908cb5f5a5 100644 --- a/tests/drivers/build_all/dts_fixup.h +++ b/tests/drivers/build_all/dts_fixup.h @@ -142,6 +142,12 @@ #define DT_INST_0_ST_VL53L0X_BUS_NAME "" #endif +#ifndef DT_INST_0_ST_VL53L1X_LABEL +#define DT_INST_0_ST_VL53L1X_LABEL "" +#define DT_INST_0_ST_VL53L1X_BASE_ADDRESS 0 +#define DT_INST_0_ST_VL53L1X_BUS_NAME "" +#endif + #ifndef DT_INST_0_ST_LSM303DLHC_MAGN_LABEL #define DT_INST_0_ST_LSM303DLHC_MAGN_LABEL "" #define DT_INST_0_ST_LSM303DLHC_MAGN_BUS_NAME "" diff --git a/west.yml b/west.yml index 1a2322ad0a1fa..e71e69e8258c9 100644 --- a/west.yml +++ b/west.yml @@ -62,7 +62,7 @@ manifest: revision: 9151e614c23997074acd1096a3e8a9e5c255d5b9 path: modules/hal/silabs - name: hal_st - revision: 0ec40aed8087f26bd9ac1b70fb5a6c326a6451aa + revision: pull/2/head path: modules/hal/st - name: hal_stm32 revision: 272281a1990ec7097f1844778955ed60fe28662a