configs/olimex-stm32-e407: Add VL53L1 support. drivers/sensors/vl53l1x.c: A few compiler errors fixed, possibly incorrectly. DRIVER DOES NOT COMPILE. Marked EXPERIMENTAL in the Kconfig file.

This commit is contained in:
Gregory Nutt 2019-06-28 15:45:00 -06:00
parent ee32b449a6
commit 4083d89244
6 changed files with 204 additions and 60 deletions

View file

@ -1,7 +1,7 @@
############################################################################
# configs/olimex-stm32-e407/src/Makefile
#
# Copyright (C) 2016 Gregory Nutt. All rights reserved.
# Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
@ -69,7 +69,7 @@ CSRCS += stm32_usb.c
endif
ifeq ($(CONFIG_ADC),y)
CSRCS += stm32_adc.c
CSRCS += stm32_adc.c
endif
ifeq ($(CONFIG_CAN),y)
@ -80,4 +80,8 @@ ifeq ($(CONFIG_ARCH_FPU),y)
CSRCS += stm32_ostest.c
endif
ifeq ($(CONFIG_SENSORS_VL53L1X),y)
CSRCS += stm32_vl53l1x.c
endif
include $(TOPDIR)/configs/Board.mk

View file

@ -59,6 +59,7 @@
#define HAVE_SDIO 1
#define HAVE_RTC_DRIVER 1
#define HAVE_NETMONITOR 1
#define HAVE_VL53L1 1
/* Can't support USB host or device features if USB OTG FS is not enabled */
@ -108,6 +109,39 @@
# endif
#endif
/* VL53L1 */
#if !defined(CONFIG_I2C) || !defined(CONFIG_SENSORS_VL53L1X) || \
!defined(CONFIG_STM32_I2C1)
# undef HAVE_VL53L1
#endif
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define VL53L1X_I2C_PORTNO 1 /* On I2C1 */
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_vl53l1xinitialize
*
* Description:
* Initialize and register the VL53L1X distance/light Sensor driver.
*
* Input parameters:
* devpath - The full path to the driver to register. E.g., "/dev/tof0"
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int stm32_vl53l1xinitialize(FAR const char *devpath)
/* Olimex-STM32-E407 GPIOs ****************************************************/
/* LEDs */

View file

@ -196,13 +196,13 @@ int board_app_initialize(uintptr_t arg)
}
#endif
#ifdef CONFIG_ADC
/* Initialize ADC and register the ADC driver. */
#ifdef HAVE_VL53L1
/* Initialize ADC and register the VL53L1X distance/light Sensor driver. */
ret = stm32_adc_setup();
ret = stm32_vl53l1xinitialize("/dev/vl53l1");
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: stm32_adc_setup failed: %d\n", ret);
syslog(LOG_ERR, "ERROR: stm32_vl53l1xinitialize failed: %d\n", ret);
}
#endif

View file

@ -0,0 +1,105 @@
/****************************************************************************
* configs/olimex-stm32-e407/src/stm32_vl53l1x.c
*
* Copyright (C) 2019 Acutronics Robotics. All rights reserved.
* Author: Acutronics Robotics (Juan Flores Muñoz) <juan@erlerobotics.com>
*
* 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 NuttX 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 OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/spi/spi.h>
#include <nuttx/sensors/vl53l1x.h>
#include "stm32.h"
#include "stm32_i2c.h"
#include "olimex-stm32-e407.h"
#ifdef HAVE_VL53L1
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define VL53L1X_I2C_PORTNO 1 /* On I2C1 */
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_vl53l1xinitialize
*
* Description:
* Initialize and register the VL53L1X distance/light Sensor driver.
*
* Input parameters:
* devpath - The full path to the driver to register. E.g., "/dev/tof0"
*
* Returned Value:
* Zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
int stm32_vl53l1xinitialize(FAR const char *devpath)
{
FAR struct i2c_master_s *i2c;
int ret;
sninfo("Initializing VL53L1X!\n");
/* Initialize I2C */
i2c = stm32_i2cbus_initialize(1);
if (!i2c)
{
return -ENODEV;
}
/* Then register the barometer sensor */
ret = vl53l1x_register(devpath, i2c);
if (ret < 0)
{
snerr("ERROR: Error registering VL53L1X\n");
}
return ret;
}
#endif /* HAVE_VL53L1 */

View file

@ -728,6 +728,7 @@ config SENSORS_VL53L1X
bool "ST VL53L1X TOF sensor"
default n
select I2C
depends on EXPERIMENTAL
---help---
Enable driver support for the VL53L1X Time Of Flight sensor.

View file

@ -5,32 +5,32 @@
* Copyright (C) 2019 Acutronics Robotics. All rights reserved.
* Author: Acutronics Robotics (Juan Flores Muñoz) <juan@erlerobotics.com>
*
* redistribution and use in source and binary forms, with or without
* 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
* 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 nuttx nor the Names of its contributors may be
* used to endorse or promote products derived from This software
* 3. Neither the name NuttX 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 owner 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.
* 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 OWNER 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.
*
****************************************************************************/
@ -258,13 +258,13 @@ static void vl53l1x_setsigmathreshold(FAR struct vl53l1x_dev_s *priv,
uint16_t sigma);
static void vl53l1x_getsigmathreshold(FAR struct vl53l1x_dev_s *priv,
FAR uint16_t *signal);
static void vl53l1x_starttemperatureupdate();
static void vl53l1x_starttemperatureupdate(FAR struct vl53l1x_dev_s *priv);
static void vl53l1x_calibrateoffset(FAR struct vl53l1x_dev_s *priv,
uint16_t targetdistinmm,
FAR int16_t *offset);
static int8_t vl53l1x_calibratextalk(FAR struct vl53l1x_dev_s *priv,
uint16_t targetdistinmm,
FAR uint16_t *xtalk);
static void vl53l1x_calibratextalk(FAR struct vl53l1x_dev_s *priv,
uint16_t targetdistinmm,
FAR uint16_t *xtalk);
/* Character driver methods */
@ -274,7 +274,8 @@ static ssize_t vl53l1x_read(FAR struct file *filep, FAR char *buffer,
size_t buflen);
static ssize_t vl53l1x_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen);
static ssize_t vl53l1x_ioctl(FAR struct file *filep, int cmd, uint16_t arg);
static ssize_t vl53l1x_ioctl(FAR struct file *filep, int cmd,
unsigned long arg);
/****************************************************************************
* Private Data
@ -286,13 +287,13 @@ static const struct file_operations g_vl53l1xfops =
vl53l1x_close, /* close */
vl53l1x_read, /* read */
vl53l1x_write, /* write */
null, /* seek */
NULL, /* seek */
vl53l1x_ioctl, /* ioctl */
#ifndef CONFIG_DISABLE_POLL
null, /* poll */
NULL, /* poll */
#endif
#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS
null, /* unlink */
NULL, /* unlink */
#endif
};
@ -435,11 +436,8 @@ static void vl53l1x_settimingbudgetinms(FAR struct vl53l1x_dev_s *priv,
{
uint16_t dm;
vl53l1x_getdistancemode(priv, &dm);
if (dm == 0)
{
return 1;
}
else if (dm == 1) /* Short distancemode */
if (dm == 1) /* Short distancemode */
{
switch (timingbudgetinms)
{
@ -680,10 +678,11 @@ static void vl53l1x_getintermeasurementinms(FAR struct vl53l1x_dev_s *priv,
uint32_t tmp;
tmp = vl53l1x_getreg32(priv, VL53L1_SYSTEM__INTERMEASUREMENT_PERIOD);
*pim = (uint16_t)tmp;
vl53l1_getreg16(priv, VL53L1_RESULT__OSC_CALIBRATE_VAL, &clockpll);
clockpll = clockpll & 0x3ff;
*pim = (uint16_t)(*pim / (clockpll * 1.065));
clockpll = vl53l1x_getreg16(priv, VL53L1_RESULT__OSC_CALIBRATE_VAL);
clockpll &= 0x3ff;
*pim = (uint16_t)(tmp / (clockpll * 1.065));
}
/****************************************************************************
@ -1169,14 +1168,12 @@ static void vl53l1x_getsignalthreshold(FAR struct vl53l1x_dev_s *priv,
static void vl53l1x_setsigmathreshold(FAR struct vl53l1x_dev_s *priv,
uint16_t sigma)
{
if (sigma > (0xffff >> 2))
if (sigma <= (0xffff >> 2))
{
return 1;
/* 16 bits register 14.2 format */
vl53l1x_putreg16(priv, RANGE_CONFIG__SIGMA_THRESH, sigma << 2);
}
/* 16 bits register 14.2 format */
vl53l1x_putreg16(priv, RANGE_CONFIG__SIGMA_THRESH, sigma << 2);
}
/****************************************************************************
@ -1273,14 +1270,14 @@ static void vl53l1x_calibrateoffset(FAR struct vl53l1x_dev_s *priv,
* Name: vl53l1x_calibratextalk
*
* Description:
* the function returns the xtalk value found and programs the xtalk
* This function returns the xtalk value found and programs the xtalk
* compensation to the device.
*
****************************************************************************/
static int8_t vl53l1x_calibratextalk(FAR struct vl53l1x_dev_s *priv,
uint16_t targetdistinmm,
FAR uint16_t *xtalk)
static void vl53l1x_calibratextalk(FAR struct vl53l1x_dev_s *priv,
uint16_t targetdistinmm,
FAR uint16_t *xtalk)
{
uint8_t i;
uint8_t tmp = 0;
@ -1614,7 +1611,7 @@ static void vl53l1x_putreg32(FAR struct vl53l1x_dev_s *priv, uint16_t regaddr,
static int vl53l1x_open(FAR struct file *filep)
{
return ok;
return OK;
}
/****************************************************************************
@ -1627,7 +1624,7 @@ static int vl53l1x_open(FAR struct file *filep)
static int vl53l1x_close(FAR struct file *filep)
{
return ok;
return OK;
}
/****************************************************************************
@ -1644,6 +1641,8 @@ static ssize_t vl53l1x_read(FAR struct file *filep, FAR char *buffer,
vl53l1x_startranging(priv);
vl53l1x_getdistance(priv, aux);
vl53l1x_stopranging(priv);
return sizeof(uint16_t);
}
/****************************************************************************
@ -1653,14 +1652,15 @@ static ssize_t vl53l1x_read(FAR struct file *filep, FAR char *buffer,
static ssize_t vl53l1x_write(FAR struct file *filep, FAR const char *buffer,
size_t buflen)
{
return -enosys;
return -ENOSYS;
}
/****************************************************************************
* Name: vl53l1x_ioctl
****************************************************************************/
static ssize_t vl53l1x_ioctl(FAR struct file *filep, int cmd, uint16_t arg)
static ssize_t vl53l1x_ioctl(FAR struct file *filep, int cmd,
unsigned long arg)
{
FAR struct inode *inode = filep->f_inode;
FAR struct vl53l1x_dev_s *priv = inode->i_private;
@ -1709,13 +1709,13 @@ static ssize_t vl53l1x_ioctl(FAR struct file *filep, int cmd, uint16_t arg)
* Description:
* register the vl53l1x character device as 'devpath'
*
* input parameters:
* Input Parameters:
* devpath - the full path to the driver to register. e.g., "/dev/tof"
* i2c - an instance of the i2c interface to use to communicate with
* vl53l1x tof
*
* returned value:
* zero (ok) on success; a negated errno value on failure.
* Returned Value:
* zero (OK) on success; a negated errno value on failure.
*
****************************************************************************/
@ -1731,7 +1731,7 @@ int vl53l1x_register(FAR const char *devpath, FAR struct i2c_master_s *i2c)
if (!priv)
{
snerr("ERROR: failed to allocate instance\n");
return -enomem;
return -ENOMEM;
}
priv->i2c = i2c;