Skip to content
Snippets Groups Projects
Commit aa679ef3 authored by Rene Ebeling's avatar Rene Ebeling
Browse files

created Wirering plan

parent 71e12493
Branches
No related tags found
No related merge requests found
Showing
with 44013 additions and 3 deletions
...@@ -74,9 +74,7 @@ void setup() ...@@ -74,9 +74,7 @@ void setup()
Wire.begin(); //This resets I2C bus to 100kHz Wire.begin(); //This resets I2C bus to 100kHz
Wire.setClock(1000000); //Sensor has max I2C freq of 1MHz Wire.setClock(1000000); //Sensor has max I2C freq of 1MHz
Wire1.setSDA(2);
Wire1.setSCL(3);
Wire1.begin();
digitalWrite(LPn1, HIGH); digitalWrite(LPn1, HIGH);
digitalWrite(LPn2, LOW); digitalWrite(LPn2, LOW);
digitalWrite(LPn3, LOW); digitalWrite(LPn3, LOW);
......
/**
******************************************************************************
* @file VL53L5CX_Sat_HelloWorld.ino
* @author STMicroelectronics
* @version V1.0.0
* @date 11 November 2021
* @brief Arduino test application for the STMicrolectronics VL53L5CX
* proximity sensor satellite based on FlightSense.
* This application makes use of C++ classes obtained from the C
* components' drivers.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2021 STMicroelectronics</center></h2>
*
* 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 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 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.
*
******************************************************************************
*/
/*
* To use these examples you need to connect the VL53L5CX satellite sensor directly to the Nucleo board with wires as explained below:
* pin 1 (GND) of the VL53L5CX satellite connected to GND of the Nucleo board
* pin 2 (IOVDD) of the VL53L5CX satellite connected to 3V3 pin of the Nucleo board
* pin 3 (AVDD) of the VL53L5CX satellite connected to 5V pin of the Nucleo board
* pin 4 (PWREN) of the VL53L5CX satellite connected to pin A5 of the Nucleo board
* pin 5 (LPn) of the VL53L5CX satellite connected to pin A3 of the Nucleo board
* pin 6 (SCL) of the VL53L5CX satellite connected to pin D15 (SCL) of the Nucleo board
* pin 7 (SDA) of the VL53L5CX satellite connected to pin D14 (SDA) of the Nucleo board
* pin 8 (I2C_RST) of the VL53L5CX satellite connected to pin A1 of the Nucleo board
* pin 9 (INT) of the VL53L5CX satellite connected to pin A2 of the Nucleo board
*/
/* Includes ------------------------------------------------------------------*/
#include <Arduino.h>
#include <Wire.h>
#include <vl53l5cx_class.h>
#include <string.h>
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <assert.h>
#include <stdlib.h>
uint8_t status;
char report[64];
#define DEV_I2C Wire
#define SerialPort Serial
#ifndef LED_BUILTIN
#define LED_BUILTIN 13
#endif
#define LedPin LED_BUILTIN
#define LPN_PIN 3
#define I2C_RST_PIN 3
#define PWREN_PIN 3
// Components.
VL53L5CX sensor_vl53l5cx_sat(&DEV_I2C, LPN_PIN, I2C_RST_PIN);
/* Setup ---------------------------------------------------------------------*/
void setup()
{
// Led.
pinMode(LedPin, OUTPUT);
pinMode(LPN_PIN, OUTPUT);
digitalWrite(LPN_PIN, HIGH);
delay(10);
// Initialize serial for output.
SerialPort.begin(115200);
SerialPort.println("Initialize... Please wait, it may take few seconds...");
// Initialize I2C bus.
DEV_I2C.begin();
// Configure VL53L5CX satellite component.
sensor_vl53l5cx_sat.begin();
sensor_vl53l5cx_sat.init_sensor();
status = sensor_vl53l5cx_sat.vl53l5cx_set_resolution(VL53L5CX_RESOLUTION_8X8);
if (status) {
snprintf(report, sizeof(report), "vl53l5cx_set_resolution failed, status %u\r\n", status);
SerialPort.print(report);
}
// Start Measurements
sensor_vl53l5cx_sat.vl53l5cx_start_ranging();
}
void loop()
{
static uint8_t loop_count = 0;
VL53L5CX_ResultsData Results;
uint8_t NewDataReady = 0;
char report[64];
uint8_t status_data;
if (loop_count < 10) {
do {
status_data = sensor_vl53l5cx_sat.vl53l5cx_check_data_ready(&NewDataReady);
} while (!NewDataReady);
if ((!status_data) && (NewDataReady != 0)) {
status_data = sensor_vl53l5cx_sat.vl53l5cx_get_ranging_data(&Results);
/* As the sensor is set in 4x4 mode by default, we have a total
* of 16 zones to print.
*/
snprintf(report, sizeof(report), "Print data no : %3u\r\n", sensor_vl53l5cx_sat.get_stream_count());
SerialPort.print(report);
for (int i = 0; i < 16; i++) {
snprintf(report, sizeof(report), "Zone : %3d, Status : %3u, Distance : %4d mm\r\n",
i,
Results.target_status[VL53L5CX_NB_TARGET_PER_ZONE * i],
Results.distance_mm[VL53L5CX_NB_TARGET_PER_ZONE * i]);
SerialPort.print(report);
}
SerialPort.println("");
loop_count++;
}
} else if (loop_count == 10) {
/* Stop measurements */
status_data = sensor_vl53l5cx_sat.vl53l5cx_stop_ranging();
if (status_data) {
snprintf(report, sizeof(report), "vl53l5cx_stop_ranging failed, status %u\r\n", status_data);
SerialPort.print(report);
}
loop_count++;
/* End of the demo */
SerialPort.println("End of ULD demo");
} else {
delay(1000);
}
}
COPYRIGHT(c) 2020 STMicroelectronics
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 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.
# VL53L3CX
Arduino library to support the VL53L3CX Time-of-Flight ranging sensor with advanced multi-object detection.
## API
This sensor uses I2C to communicate. And I2C instance is required to access to the sensor.
The APIs provide simple distance measure and multi-object detection in both polling and interrupt modes.
## Examples
There are 2 examples with the VL53L3CX library.
In order to use these examples you need to connect the VL53L3CX satellite sensor directly to the Nucleo board with wires as explained below:
- pin 1 (Interrupt) of the VL53L3CX satellite connected to pin A2 of the Nucleo board
- pin 2 (SCL_I) of the VL53L3CX satellite connected to pin D15 (SCL) of the Nucleo board with a Pull-Up resistor of 4.7 KOhm
- pin 3 (XSDN_I) of the VL53L3CX satellite connected to pin A1 of the Nucleo board
- pin 4 (SDA_I) of the VL53L3CX satellite connected to pin D14 (SDA) of the Nucleo board with a Pull-Up resistor of 4.7 KOhm
- pin 5 (VDD) of the VL53L3CX satellite connected to 3V3 pin of the Nucleo board
- pin 6 (GND) of the VL53L3CX satellite connected to GND of the Nucleo board
- pins 7, 8, 9 and 10 are not connected.
* VL53L3CX_Sat_HelloWorld: This example code is to show how to get multi-object detection and proximity
values of the VL53L3CX satellite sensor in polling mode.
* VL53L3CX_Sat_HelloWorld_Interrupt: This example code is to show how to get multi-object detection and proximity
values of the VL53L3CX satellite sensor in interrupt mode.
## Note
The VL53L3CX is a fully integrated miniature module with a low power microcontroller with advanced digital firmware.
Detection with full field of view (FoV) is up to 300 cm +. It works with many types of glass roofing materials.
Xshutdown (reset) and stop GPIO are integrated to optimize remote operation.
## Documentation
You can find the source files at
https://github.com/stm32duino/VL53L3CX
The VL53L3CX datasheet is available at
https://www.st.com/content/st_com/en/products/imaging-and-photonics-solutions/proximity-sensors/vl53l3cx.html
/**
******************************************************************************
* @file VL53L3CX_Sat_HelloWorld.ino
* @author SRA
* @version V1.0.0
* @date 30 July 2020
* @brief Arduino test application for the STMicrolectronics VL53L3CX
* proximity sensor satellite based on FlightSense.
* This application makes use of C++ classes obtained from the C
* components' drivers.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2020 STMicroelectronics</center></h2>
*
* 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 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 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.
*
******************************************************************************
*/
/*
* To use this sketch you need to connect the VL53L3CX satellite sensor directly to the Nucleo board with wires in this way:
* pin 1 (Interrupt) of the VL53L3CX satellite connected to pin A2 of the Nucleo board
* pin 2 (SCL_I) of the VL53L3CX satellite connected to pin D15 (SCL) of the Nucleo board with a Pull-Up resistor of 4.7 KOhm
* pin 3 (XSDN_I) of the VL53L3CX satellite connected to pin A1 of the Nucleo board
* pin 4 (SDA_I) of the VL53L3CX satellite connected to pin D14 (SDA) of the Nucleo board with a Pull-Up resistor of 4.7 KOhm
* pin 5 (VDD) of the VL53L3CX satellite connected to 3V3 pin of the Nucleo board
* pin 6 (GND) of the VL53L3CX satellite connected to GND of the Nucleo board
* pins 7, 8, 9 and 10 are not connected.
*/
/* Includes ------------------------------------------------------------------*/
#include <Arduino.h>
#include <Wire.h>
#include <vl53lx_class.h>
#include <string.h>
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <assert.h>
#include <stdlib.h>
#define DEV_I2C Wire
#define SerialPort Serial
#ifndef LED_BUILTIN
#define LED_BUILTIN 13
#endif
#define LedPin LED_BUILTIN
// Components.
VL53LX sensor_vl53lx_sat(&DEV_I2C, A1);
/* Setup ---------------------------------------------------------------------*/
void setup()
{
// Led.
pinMode(LedPin, OUTPUT);
// Initialize serial for output.
SerialPort.begin(115200);
SerialPort.println("Starting...");
// Initialize I2C bus.
DEV_I2C.begin();
// Configure VL53LX satellite component.
sensor_vl53lx_sat.begin();
// Switch off VL53LX satellite component.
sensor_vl53lx_sat.VL53LX_Off();
//Initialize VL53LX satellite component.
sensor_vl53lx_sat.InitSensor(0x12);
// Start Measurements
sensor_vl53lx_sat.VL53LX_StartMeasurement();
}
void loop()
{
VL53LX_MultiRangingData_t MultiRangingData;
VL53LX_MultiRangingData_t *pMultiRangingData = &MultiRangingData;
uint8_t NewDataReady = 0;
int no_of_object_found = 0, j;
char report[64];
int status;
do
{
status = sensor_vl53lx_sat.VL53LX_GetMeasurementDataReady(&NewDataReady);
} while (!NewDataReady);
//Led on
digitalWrite(LedPin, HIGH);
if((!status)&&(NewDataReady!=0))
{
status = sensor_vl53lx_sat.VL53LX_GetMultiRangingData(pMultiRangingData);
no_of_object_found=pMultiRangingData->NumberOfObjectsFound;
snprintf(report, sizeof(report), "VL53LX Satellite: Count=%d, #Objs=%1d ", pMultiRangingData->StreamCount, no_of_object_found);
SerialPort.print(report);
for(j=0;j<no_of_object_found;j++)
{
if(j!=0)SerialPort.print("\r\n ");
SerialPort.print("status=");
SerialPort.print(pMultiRangingData->RangeData[j].RangeStatus);
SerialPort.print(", D=");
SerialPort.print(pMultiRangingData->RangeData[j].RangeMilliMeter);
SerialPort.print("mm");
SerialPort.print(", Signal=");
SerialPort.print((float)pMultiRangingData->RangeData[j].SignalRateRtnMegaCps/65536.0);
SerialPort.print(" Mcps, Ambient=");
SerialPort.print((float)pMultiRangingData->RangeData[j].AmbientRateRtnMegaCps/65536.0);
SerialPort.print(" Mcps");
}
SerialPort.println("");
if (status==0)
{
status = sensor_vl53lx_sat.VL53LX_ClearInterruptAndStartMeasurement();
}
}
digitalWrite(LedPin, LOW);
}
/**
******************************************************************************
* @file VL53L3CX_Sat_HelloWorld_Interrupt.ino
* @author SRA
* @version V1.0.0
* @date 30 July 2020
* @brief Arduino test application for the STMicrolectronics VL53L3CX
* proximity sensor satellite based on FlightSense.
* This application makes use of C++ classes obtained from the C
* components' drivers.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2020 STMicroelectronics</center></h2>
*
* 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 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 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.
*
******************************************************************************
*/
//On some boards like the Arduino Uno the pin used by the sensor to raise interrupts (A2)
//can't be mapped as an interrupt pin. For this this reason this sketch will not work
//unless some additional cabling is done and the interrupt pin is changed.
/*
* To use this sketch you need to connect the VL53L3CX satellite sensor directly to the Nucleo board with wires in this way:
* pin 1 (Interrupt) of the VL53L3CX satellite connected to pin A2 of the Nucleo board
* pin 2 (SCL_I) of the VL53L3CX satellite connected to pin D15 (SCL) of the Nucleo board with a Pull-Up resistor of 4.7 KOhm
* pin 3 (XSDN_I) of the VL53L3CX satellite connected to pin A1 of the Nucleo board
* pin 4 (SDA_I) of the VL53L3CX satellite connected to pin D14 (SDA) of the Nucleo board with a Pull-Up resistor of 4.7 KOhm
* pin 5 (VDD) of the VL53L3CX satellite connected to 3V3 pin of the Nucleo board
* pin 6 (GND) of the VL53L3CX satellite connected to GND of the Nucleo board
* pins 7, 8, 9 and 10 are not connected.
*/
/* Includes ------------------------------------------------------------------*/
#include <Arduino.h>
#include <Wire.h>
#include <vl53lx_class.h>
#include <string.h>
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <assert.h>
#include <stdlib.h>
#define DEV_I2C Wire
#define SerialPort Serial
#ifndef LED_BUILTIN
#define LED_BUILTIN 13
#endif
#define LedPin LED_BUILTIN
#define interruptPin A2
// Components.
VL53LX sensor_vl53lx_sat(&DEV_I2C, A1);
volatile int interruptCount=0;
void measure()
{
interruptCount=1;
}
void setup()
{
VL53LX_Error status;
// Led.
pinMode(LedPin, OUTPUT);
pinMode(interruptPin, INPUT_PULLUP);
attachInterrupt(interruptPin, measure, FALLING);
// Initialize serial for output.
SerialPort.begin(115200);
SerialPort.println("Starting...");
// Initialize I2C bus.
DEV_I2C.begin();
// Configure VL53LX satellite component.
sensor_vl53lx_sat.begin();
// Switch off VL53LX satellite component.
sensor_vl53lx_sat.VL53LX_Off();
// Initialize VL53LX satellite component.
status = sensor_vl53lx_sat.InitSensor(0x12);
if(status)
{
SerialPort.println("Init sensor_vl53lx_sat failed...");
}
sensor_vl53lx_sat.VL53LX_StartMeasurement();
}
void loop()
{
VL53LX_MultiRangingData_t MultiRangingData;
VL53LX_MultiRangingData_t *pMultiRangingData = &MultiRangingData;
uint8_t NewDataReady = 0;
int no_of_object_found = 0, j;
char report[64];
if (interruptCount)
{
int status;
interruptCount=0;
// Led blinking.
digitalWrite(LedPin, HIGH);
status = sensor_vl53lx_sat.VL53LX_GetMeasurementDataReady(&NewDataReady);
if((!status)&&(NewDataReady!=0))
{
status = sensor_vl53lx_sat.VL53LX_GetMultiRangingData(pMultiRangingData);
no_of_object_found=pMultiRangingData->NumberOfObjectsFound;
snprintf(report, sizeof(report), "Count=%d, #Objs=%1d ", pMultiRangingData->StreamCount, no_of_object_found);
SerialPort.print(report);
for(j=0;j<no_of_object_found;j++)
{
if(j!=0)SerialPort.print("\r\n ");
SerialPort.print("status=");
SerialPort.print(pMultiRangingData->RangeData[j].RangeStatus);
SerialPort.print(", D=");
SerialPort.print(pMultiRangingData->RangeData[j].RangeMilliMeter);
SerialPort.print("mm");
SerialPort.print(", Signal=");
SerialPort.print((float)pMultiRangingData->RangeData[j].SignalRateRtnMegaCps/65536.0);
SerialPort.print(" Mcps, Ambient=");
SerialPort.print((float)pMultiRangingData->RangeData[j].AmbientRateRtnMegaCps/65536.0);
SerialPort.print(" Mcps");
}
SerialPort.println("");
if (status==0)
{
status = sensor_vl53lx_sat.VL53LX_ClearInterruptAndStartMeasurement();
}
}
digitalWrite(LedPin, LOW);
}
}
pres
\ No newline at end of file
This diff is collapsed.
name=STM32duino VL53L3CX
version=2.0.0
author=STMicroelectronics
maintainer=stm32duino
sentence=Allows controlling the VL53L3CX (Time-of-Flight ranging sensor with multi target detection)
paragraph= This library provides simple measure distance in mm, single swipe gesture detection, directional (left/right) swipe gesture detection and single tap gesture detection.
category=Device Control
url= https://github.com/stm32duino/VL53L3CX
architectures=stm32
/**
******************************************************************************
* @file ComponentObject.h
* @author AST
* @version V1.0.0
* @date April 13th, 2015
* @brief This file contains the abstract class describing the interface of a
* generic component.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2015 STMicroelectronics</center></h2>
*
* 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 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 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __COMPONENT_OBJECT_CLASS_H
#define __COMPONENT_OBJECT_CLASS_H
/* Includes ------------------------------------------------------------------*/
#include <stdint.h>
/* Classes ------------------------------------------------------------------*/
/** An abstract class for Generic components.
*/
class ComponentObject {
public:
/**
* @brief Initializing the component.
* @param[in] init pointer to device specific initialization structure.
* @retval "0" in case of success, an error code otherwise.
*/
virtual int Init() = 0;
/**
* @brief Getting the ID of the component.
* @param[out] id pointer to an allocated variable to store the ID into.
* @retval "0" in case of success, an error code otherwise.
*/
virtual int ReadID() = 0;
};
#endif /* __COMPONENT_OBJECT_CLASS_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
/**
******************************************************************************
* @file RangeSensor.h
* @author AST / EST
* @version V0.0.1
* @date 13-April-2015
* @brief This file contains the abstract class describing in general
* the interfaces of a range sensor
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2015 STMicroelectronics</center></h2>
*
* 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 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 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.
*
******************************************************************************
*/
/* Define to prevent from recursive inclusion --------------------------------*/
#ifndef __RANGE_SENSOR_CLASS_H
#define __RANGE_SENSOR_CLASS_H
/* Includes ------------------------------------------------------------------*/
#include <ComponentObject.h>
/* Classes ------------------------------------------------------------------*/
/** An abstract class for range sensors
*/
class RangeSensor : public ComponentObject {
public:
/**
* @brief Get current range [mm]
* @param[out] piData Pointer to where to store range to
* @return 0 in case of success, an error code otherwise
*/
virtual int GetDistance(uint32_t *piData) = 0;
};
#endif /* __RANGE_SENSOR_CLASS_H */
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
COPYRIGHT(c) 2021 STMicroelectronics
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 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 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.
# VL53L4CD
Arduino library to support the VL53L4CD Time-of-Flight ranging sensor.
## API
This sensor uses I2C to communicate. And I2C instance is required to access to the sensor.
The APIs provide simple distance measure in both polling and interrupt modes.
## Examples
There are 2 examples with the VL53L4CD library.
In order to use these examples you need to connect the VL53L4CD satellite sensor directly to the Nucleo board with wires as explained below:
- pin 1 (GND) of the VL53L4CD satellite connected to GND of the Nucleo board
- pin 2 (VDD) of the VL53L4CD satellite connected to 3V3 pin of the Nucleo board
- pin 3 (SCL) of the VL53L4CD satellite connected to pin D15 (SCL) of the Nucleo board
- pin 4 (SDA) of the VL53L4CD satellite connected to pin D14 (SDA) of the Nucleo board
- pin 5 (GPIO1) of the VL53L4CD satellite connected to pin A2 of the Nucleo board
- pin 6 (XSHUT) of the VL53L4CD satellite connected to pin A1 of the Nucleo board
* VL53L4CD_Sat_HelloWorld: This example code is to show how to get proximity
values of the VL53L4CD satellite sensor in polling mode.
* VL53L4CD_Sat_HelloWorld_Interrupt: This example code is to show how to get proximity
values of the VL53L4CD satellite sensor in interrupt mode.
## Documentation
You can find the source files at
https://github.com/stm32duino/VL53L4CD
The VL53L4CD datasheet is available at
https://www.st.com/content/st_com/en/products/imaging-and-photonics-solutions/proximity-sensors/vl53l4cd.html
/**
******************************************************************************
* @file VL53L4CD_Sat_HelloWorld.ino
* @author STMicroelectronics
* @version V1.0.0
* @date 29 November 2021
* @brief Arduino test application for the STMicrolectronics VL53L4CD
* proximity sensor satellite based on FlightSense.
* This application makes use of C++ classes obtained from the C
* components' drivers.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2021 STMicroelectronics</center></h2>
*
* 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 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 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.
*
******************************************************************************
*/
/*
* To use this sketch you need to connect the VL53L4CD satellite sensor directly to the Nucleo board with wires in this way:
* pin 1 (GND) of the VL53L4CD satellite connected to GND of the Nucleo board
* pin 2 (VDD) of the VL53L4CD satellite connected to 3V3 pin of the Nucleo board
* pin 3 (SCL) of the VL53L4CD satellite connected to pin D15 (SCL) of the Nucleo board
* pin 4 (SDA) of the VL53L4CD satellite connected to pin D14 (SDA) of the Nucleo board
* pin 5 (GPIO1) of the VL53L4CD satellite connected to pin A2 of the Nucleo board
* pin 6 (XSHUT) of the VL53L4CD satellite connected to pin A1 of the Nucleo board
*/
/* Includes ------------------------------------------------------------------*/
#include <Arduino.h>
#include <Wire.h>
#include <vl53l4cd_class.h>
#include <string.h>
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <assert.h>
#include <stdlib.h>
#define DEV_I2C Wire
#define SerialPort Serial
#ifndef LED_BUILTIN
#define LED_BUILTIN 13
#endif
#define LedPin LED_BUILTIN
// Components.
VL53L4CD sensor_vl53l4cd_sat(&DEV_I2C, A1);
/* Setup ---------------------------------------------------------------------*/
void setup()
{
// Led.
pinMode(LedPin, OUTPUT);
// Initialize serial for output.
SerialPort.begin(115200);
SerialPort.println("Starting...");
// Initialize I2C bus.
DEV_I2C.begin();
// Configure VL53L4CD satellite component.
sensor_vl53l4cd_sat.begin();
// Switch off VL53L4CD satellite component.
sensor_vl53l4cd_sat.VL53L4CD_Off();
//Initialize VL53L4CD satellite component.
sensor_vl53l4cd_sat.InitSensor();
// Program the highest possible TimingBudget, without enabling the
// low power mode. This should give the best accuracy
sensor_vl53l4cd_sat.VL53L4CD_SetRangeTiming(200, 0);
// Start Measurements
sensor_vl53l4cd_sat.VL53L4CD_StartRanging();
}
void loop()
{
uint8_t NewDataReady = 0;
VL53L4CD_Result_t results;
uint8_t status;
char report[64];
do {
status = sensor_vl53l4cd_sat.VL53L4CD_CheckForDataReady(&NewDataReady);
} while (!NewDataReady);
//Led on
digitalWrite(LedPin, HIGH);
if ((!status) && (NewDataReady != 0)) {
// (Mandatory) Clear HW interrupt to restart measurements
sensor_vl53l4cd_sat.VL53L4CD_ClearInterrupt();
// Read measured distance. RangeStatus = 0 means valid data
sensor_vl53l4cd_sat.VL53L4CD_GetResult(&results);
snprintf(report, sizeof(report), "Status = %3u, Distance = %5u mm, Signal = %6u kcps/spad\r\n",
results.range_status,
results.distance_mm,
results.signal_per_spad_kcps);
SerialPort.print(report);
}
//Led off
digitalWrite(LedPin, LOW);
}
/**
******************************************************************************
* @file VL53L4CD_Sat_HelloWorld_Interrupt.ino
* @author STMicroelectronics
* @version V1.0.0
* @date 29 November 2021
* @brief Arduino test application for the STMicrolectronics VL53L4CD
* proximity sensor satellite based on FlightSense.
* This application makes use of C++ classes obtained from the C
* components' drivers.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2021 STMicroelectronics</center></h2>
*
* 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 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 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.
*
******************************************************************************
*/
//On some boards like the Arduino Uno the pin used by the sensor to raise interrupts (A2)
//can't be mapped as an interrupt pin. For this this reason this sketch will not work
//unless some additional cabling is done and the interrupt pin is changed.
/*
* To use this sketch you need to connect the VL53L4CD satellite sensor directly to the Nucleo board with wires in this way:
* pin 1 (GND) of the VL53L4CD satellite connected to GND of the Nucleo board
* pin 2 (VDD) of the VL53L4CD satellite connected to 3V3 pin of the Nucleo board
* pin 3 (SCL) of the VL53L4CD satellite connected to pin D15 (SCL) of the Nucleo board
* pin 4 (SDA) of the VL53L4CD satellite connected to pin D14 (SDA) of the Nucleo board
* pin 5 (GPIO1) of the VL53L4CD satellite connected to pin A2 of the Nucleo board
* pin 6 (XSHUT) of the VL53L4CD satellite connected to pin A1 of the Nucleo board
*/
/* Includes ------------------------------------------------------------------*/
#include <Arduino.h>
#include <Wire.h>
#include <vl53l4cd_class.h>
#include <string.h>
#include <stdlib.h>
#include <stdio.h>
#include <stdint.h>
#include <assert.h>
#include <stdlib.h>
#define DEV_I2C Wire
#define SerialPort Serial
#ifndef LED_BUILTIN
#define LED_BUILTIN 13
#endif
#define LedPin LED_BUILTIN
#define interruptPin A2
// Components.
VL53L4CD sensor_vl53l4cd_sat(&DEV_I2C, A1);
volatile int interruptCount = 0;
void measure()
{
interruptCount = 1;
}
/* Setup ---------------------------------------------------------------------*/
void setup()
{
// Led.
pinMode(LedPin, OUTPUT);
// Interrupt
pinMode(interruptPin, INPUT_PULLUP);
attachInterrupt(interruptPin, measure, FALLING);
// Initialize serial for output.
SerialPort.begin(115200);
SerialPort.println("Starting...");
// Initialize I2C bus.
DEV_I2C.begin();
// Configure VL53L4CD satellite component.
sensor_vl53l4cd_sat.begin();
// Switch off VL53L4CD satellite component.
sensor_vl53l4cd_sat.VL53L4CD_Off();
//Initialize VL53L4CD satellite component.
sensor_vl53l4cd_sat.InitSensor();
// Program the highest possible TimingBudget, without enabling the
// low power mode. This should give the best accuracy
sensor_vl53l4cd_sat.VL53L4CD_SetRangeTiming(200, 0);
// Start Measurements
sensor_vl53l4cd_sat.VL53L4CD_StartRanging();
}
void loop()
{
uint8_t NewDataReady = 0;
VL53L4CD_Result_t results;
uint8_t status;
char report[64];
if (interruptCount) {
interruptCount = 0;
status = sensor_vl53l4cd_sat.VL53L4CD_CheckForDataReady(&NewDataReady);
//Led on
digitalWrite(LedPin, HIGH);
if ((!status) && (NewDataReady != 0)) {
// (Mandatory) Clear HW interrupt to restart measurements
sensor_vl53l4cd_sat.VL53L4CD_ClearInterrupt();
// Read measured distance. RangeStatus = 0 means valid data
sensor_vl53l4cd_sat.VL53L4CD_GetResult(&results);
snprintf(report, sizeof(report), "Status = %3u, Distance = %5u mm, Signal = %6u kcps/spad\r\n",
results.range_status,
results.distance_mm,
results.signal_per_spad_kcps);
SerialPort.print(report);
}
//Led off
digitalWrite(LedPin, LOW);
}
}
#######################################
# Syntax Coloring Map For VL53L4CD
#######################################
#######################################
# Datatypes (KEYWORD1)
#######################################
VL53L4CD KEYWORD1
#######################################
# Methods and Functions (KEYWORD2)
#######################################
begin KEYWORD2
end KEYWORD2
VL53L4CD_On KEYWORD2
VL53L4CD_Off KEYWORD2
InitSensor KEYWORD2
VL53L4CD_GetSWVersion KEYWORD2
VL53L4CD_SetI2CAddress KEYWORD2
VL53L4CD_GetSensorId KEYWORD2
VL53L4CD_SensorInit KEYWORD2
VL53L4CD_ClearInterrupt KEYWORD2
VL53L4CD_StartRanging KEYWORD2
VL53L4CD_StopRanging KEYWORD2
VL53L4CD_CheckForDataReady KEYWORD2
VL53L4CD_SetRangeTiming KEYWORD2
VL53L4CD_GetRangeTiming KEYWORD2
VL53L4CD_GetResult KEYWORD2
VL53L4CD_SetOffset KEYWORD2
VL53L4CD_GetOffset KEYWORD2
VL53L4CD_SetXtalk KEYWORD2
VL53L4CD_GetXtalk KEYWORD2
VL53L4CD_SetDetectionThresholds KEYWORD2
VL53L4CD_GetDetectionThresholds KEYWORD2
VL53L4CD_SetSignalThreshold KEYWORD2
VL53L4CD_GetSignalThreshold KEYWORD2
VL53L4CD_SetSigmaThreshold KEYWORD2
VL53L4CD_GetSigmaThreshold KEYWORD2
VL53L4CD_StartTemperatureUpdate KEYWORD2
VL53L4CD_CalibrateOffset KEYWORD2
VL53L4CD_CalibrateXtalk KEYWORD2
#######################################
# Constants (LITERAL1)
#######################################
VL53L4CD_IMPLEMENTATION_VER_MAJOR LITERAL1
VL53L4CD_IMPLEMENTATION_VER_MINOR LITERAL1
VL53L4CD_IMPLEMENTATION_VER_BUILD LITERAL1
VL53L4CD_IMPLEMENTATION_VER_REVISION LITERAL1
VL53L4CD_ERROR_NONE LITERAL1
VL53L4CD_ERROR_INVALID_ARGUMENT LITERAL1
VL53L4CD_ERROR_TIMEOUT LITERAL1
VL53L4CD_SOFT_RESET LITERAL1
VL53L4CD_I2C_SLAVE_DEVICE_ADDRESS LITERAL1
VL53L4CD_VHV_CONFIG_TIMEOUT_MACROP_LOOP_BOUND LITERAL1
VL53L4CD_XTALK_PLANE_OFFSET_KCPS LITERAL1
VL53L4CD_XTALK_X_PLANE_GRADIENT_KCPS LITERAL1
VL53L4CD_XTALK_Y_PLANE_GRADIENT_KCPS LITERAL1
VL53L4CD_RANGE_OFFSET_MM LITERAL1
VL53L4CD_INNER_OFFSET_MM LITERAL1
VL53L4CD_OUTER_OFFSET_MM LITERAL1
VL53L4CD_I2C_FAST_MODE_PLUS LITERAL1
VL53L4CD_GPIO_HV_MUX_CTRL LITERAL1
VL53L4CD_GPIO_TIO_HV_STATUS LITERAL1
VL53L4CD_SYSTEM_INTERRUPT LITERAL1
VL53L4CD_RANGE_CONFIG_A LITERAL1
VL53L4CD_RANGE_CONFIG_B LITERAL1
VL53L4CD_RANGE_CONFIG_SIGMA_THRESH LITERAL1
VL53L4CD_MIN_COUNT_RATE_RTN_LIMIT_MCPS LITERAL1
VL53L4CD_INTERMEASUREMENT_MS LITERAL1
VL53L4CD_THRESH_HIGH LITERAL1
VL53L4CD_THRESH_LOW LITERAL1
VL53L4CD_SYSTEM_INTERRUPT_CLEAR LITERAL1
VL53L4CD_SYSTEM_START LITERAL1
VL53L4CD_RESULT_RANGE_STATUS LITERAL1
VL53L4CD_RESULT_SPAD_NB LITERAL1
VL53L4CD_RESULT_SIGNAL_RATE LITERAL1
VL53L4CD_RESULT_AMBIENT_RATE LITERAL1
VL53L4CD_RESULT_SIGMA LITERAL1
VL53L4CD_RESULT_DISTANCE LITERAL1
VL53L4CD_RESULT_OSC_CALIBRATE_VAL LITERAL1
VL53L4CD_FIRMWARE_SYSTEM_STATUS LITERAL1
VL53L4CD_IDENTIFICATION_MODEL_ID LITERAL1
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment