Coder Social home page Coder Social logo

vl53l0x-arduino's Introduction

VL53L0X library for Arduino

www.pololu.com

Summary

This is a library for the Arduino IDE that helps interface with ST's VL53L0X time-of-flight distance sensor. The library makes it simple to configure the sensor and read range data from it via I²C.

Supported platforms

This library is designed to work with the Arduino IDE versions 1.6.x or later; we have not tested it with earlier versions. This library should support any Arduino-compatible board, including the Pololu A-Star 32U4 controllers.

Getting started

Hardware

A VL53L0X carrier can be purchased from Pololu's website. Before continuing, careful reading of the product page as well as the VL53L0X datasheet is recommended.

Make the following connections between the Arduino and the VL53L0X board:

5V Arduino boards

(including Arduino Uno, Leonardo, Mega; Pololu A-Star 32U4)

Arduino   VL53L0X board
-------   -------------
     5V - VIN
    GND - GND
    SDA - SDA
    SCL - SCL

3.3V Arduino boards

(including Arduino Due)

Arduino   VL53L0X board
-------   -------------
    3V3 - VIN
    GND - GND
    SDA - SDA
    SCL - SCL

Software

If you are using version 1.6.2 or later of the Arduino software (IDE), you can use the Library Manager to install this library:

  1. In the Arduino IDE, open the "Sketch" menu, select "Include Library", then "Manage Libraries...".
  2. Search for "VL53L0X".
  3. Click the VL53L0X entry in the list.
  4. Click "Install".

If this does not work, you can manually install the library:

  1. Download the latest release archive from GitHub and decompress it.
  2. Rename the folder "vl53l0x-arduino-master" to "VL53L0X".
  3. Move the "VL53L0X" folder into the "libraries" directory inside your Arduino sketchbook directory. You can view your sketchbook location by opening the "File" menu and selecting "Preferences" in the Arduino IDE. If there is not already a "libraries" folder in that location, you should make the folder yourself.
  4. After installing the library, restart the Arduino IDE.

Examples

Several example sketches are available that show how to use the library. You can access them from the Arduino IDE by opening the "File" menu, selecting "Examples", and then selecting "VL53L0X". If you cannot find these examples, the library was probably installed incorrectly and you should retry the installation instructions above.

ST's VL53L0X API and this library

Most of the functionality of this library is based on the VL53L0X API provided by ST (STSW-IMG005), and some of the explanatory comments in the code are quoted or paraphrased from the API source code, API user manual (UM2039), and the VL53L0X datasheet. For more explanation about the library code and how it was derived from the API, see the comments in VL53L0X.cpp.

This library is intended to provide a quicker and easier way to get started using the VL53L0X with an Arduino-compatible controller, in contrast to customizing and compiling ST's API for the Arduino. The library has a more streamlined interface, as well as smaller storage and memory footprints. However, it does not implement some of the more advanced functionality available in the API (for example, calibrating the sensor to work well under a cover glass), and it has less robust error checking. For advanced applications, especially when storage and memory are less of an issue, consider using the VL53L0X API directly.

Library reference

  • uint8_t last_status
    The status of the last I²C write transmission. See the Wire.endTransmission() documentation for return values.

  • VL53L0X()
    Constructor.

  • void setBus(TwoWire * bus)
    Configures this object to use the specified I²C bus. bus should be a pointer to a TwoWire object; the default bus is Wire, which is typically the first or only I²C bus on an Arduino. If your Arduino has more than one I²C bus and you have the VL53L0X connected to the second bus, which is typically called Wire1, you can call sensor.setBus(&Wire1);.

  • TwoWire * getBus()
    Returns a pointer to the I²C bus this object is using.

  • void setAddress(uint8_t new_addr)
    Changes the I²C slave device address of the VL53L0X to the given value (7-bit).

  • uint8_t getAddress()
    Returns the I²C address this object is using.

  • bool init(bool io_2v8 = true)
    Iniitializes and configures the sensor. If the optional argument io_2v8 is true (the default if not specified), the sensor is configured for 2V8 mode (2.8 V I/O); if false, the sensor is left in 1V8 mode. The return value is a boolean indicating whether the initialization completed successfully.

  • void writeReg(uint8_t reg, uint8_t value)
    Writes an 8-bit sensor register with the given value.

    Register address constants are defined by the regAddr enumeration type in VL53L0X.h.
    Example use: sensor.writeReg(VL53L0X::SYSRANGE_START, 0x01);

  • void writeReg16Bit(uint8_t reg, uint16_t value)
    Writes a 16-bit sensor register with the given value.

  • void writeReg32Bit(uint8_t reg, uint32_t value)
    Writes a 32-bit sensor register with the given value.

  • uint8_t readReg(uint8_t reg)
    Reads an 8-bit sensor register and returns the value read.

  • uint16_t readReg16Bit(uint8_t reg)
    Reads a 16-bit sensor register and returns the value read.

  • uint32_t readReg32Bit(uint8_t reg)
    Reads a 32-bit sensor register and returns the value read.

  • void writeMulti(uint8_t reg, uint8_t const * src, uint8_t count)
    Writes an arbitrary number of bytes from the given array to the sensor, starting at the given register.

  • void readMulti(uint8_t reg, uint8_t * dst, uint8_t count)
    Reads an arbitrary number of bytes from the sensor, starting at the given register, into the given array.

  • bool setSignalRateLimit(float limit_Mcps)
    Sets the return signal rate limit to the given value in units of MCPS (mega counts per second). This is the minimum amplitude of the signal reflected from the target and received by the sensor necessary for it to report a valid reading. Setting a lower limit increases the potential range of the sensor but also increases the likelihood of getting an inaccurate reading because of reflections from objects other than the intended target. This limit is initialized to 0.25 MCPS by default. The return value is a boolean indicating whether the requested limit was valid.

  • float getSignalRateLimit()
    Returns the current return signal rate limit in MCPS.

  • bool setMeasurementTimingBudget(uint32_t budget_us)
    Sets the measurement timing budget to the given value in microseconds. This is the time allowed for one range measurement; a longer timing budget allows for more accurate measurements. The default budget is about 33000 microseconds, or 33 ms; the minimum is 20 ms. The return value is a boolean indicating whether the requested budget was valid.

  • uint32_t getMeasurementTimingBudget()
    Returns the current measurement timing budget in microseconds.

  • bool setVcselPulsePeriod(vcselPeriodType type, uint8_t period_pclks) Sets the VCSEL (vertical cavity surface emitting laser) pulse period for the given period type (VL53L0X::VcselPeriodPreRange or VL53L0X::VcselPeriodFinalRange) to the given value (in PCLKs). Longer periods increase the potential range of the sensor. Valid values are (even numbers only):

    Pre: 12 to 18 (initialized to 14 by default)
    Final: 8 to 14 (initialized to 10 by default)

    The return value is a boolean indicating whether the requested period was valid.

  • uint8_t getVcselPulsePeriod(vcselPeriodType type)
    Returns the current VCSEL pulse period for the given period type.

  • void startContinuous(uint32_t period_ms = 0)
    Starts continuous ranging measurements. If the optional argument period_ms is 0 (the default if not specified), continuous back-to-back mode is used (the sensor takes measurements as often as possible); if it is nonzero, continuous timed mode is used, with the specified inter-measurement period in milliseconds determining how often the sensor takes a measurement.

  • void stopContinuous()
    Stops continuous mode.

  • uint16_t readRangeContinuousMillimeters()
    Returns a range reading in millimeters when continuous mode is active.

  • uint16_t readRangeSingleMillimeters()
    Performs a single-shot ranging measurement and returns the reading in millimeters.

  • void setTimeout(uint16_t timeout)
    Sets a timeout period in milliseconds after which read operations will abort if the sensor is not ready. A value of 0 disables the timeout.

  • uint16_t getTimeout()
    Returns the current timeout period setting.

  • bool timeoutOccurred()
    Indicates whether a read timeout has occurred since the last call to timeoutOccurred().

Version history

  • 1.3.1 (2022-04-05): Explicitly cast Wire.write() arguments to uint8_t. Removed 20ms hard limit for timing budget to match API 1.0.4.
  • 1.3.0 (2020-09-24): Added support for alternative I²C buses (thanks KurtE).
  • 1.2.0 (2019-10-31): Incorporated some updates from ST's VL53L0X API version 1.0.2 (this library was originally based on API version 1.0.0).
  • 1.1.0 (2019-10-29): Improved init() and added a check for its return value in examples; fixed a few other issues.
  • 1.0.2 (2017-06-27): Fixed a typo in a register modification in getSpadInfo() (thanks @tridge).
  • 1.0.1 (2016-12-08): Fixed type error in readReg32Bit().
  • 1.0.0 (2016-08-12): Original release.

vl53l0x-arduino's People

Contributors

davidegrayson avatar kevin-pololu avatar kurte avatar mirkix avatar peterchmurciak avatar shervinemami avatar tridge avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

vl53l0x-arduino's Issues

Can't use your board with an I2C OLED display

Hi,

I am using POLOLU CJMCU-530 with your library, and it works fine with the examples.
I am also using an SSD1306 I2C OLED display (which is normally working with u8g2 lib) but, as soon as the sketch runs sensor.init(), the display witches off and doesn't work. The 2 I2C devices (sensor and OLED) are on 2 different addresses.
I am using an Arduino Nano, and I am attaching the schematic.
htay-schematic

Implementation of software i2c

Hello! I'm planning on using the vl53l0x with a pro micro, which pins sda and scl are occupied by other interrupt devices. I was wondering is it easy to implement software i2c?

Thanks in advance

Does this library work properly with ESP8266?

Is this library also supposed to work with ESP8266?

I tried using it but got a lot of weird problems like reboot-loops. This happened even with the Single.ino example. One suspicion is that the initialisation sequence (calls sensor.init(), setSignalRateLimit(), setMeasurementTimingBudget()) takes too long. I was able to "fix" this by splitting the initialisation sequence up, but I don't feel very confident about the library in combination with the ESP8266. Using the same sensor with an atmel avr does seem to work.

Can't initialize VL53L0/1XV2 sensor on ESP32 (lolin32)

I tried all examples but I my sensor never achieve to init() itself.
The sensor is detected with an i2c scanner (address 0x29) but beside that I can never init() properly.
Sensor VIN is plugged to 3V3, GND to my esp32 GND, SDA/SCL to SDA/SCL on my esp32 board (pin 21 & 22).
Code is as simple as:

#define I2C_SDA 21
#define I2C_SCL 22

#include <SPI.h>
#include <VL53L0X.h>
#include <Wire.h>

VL53L0X sensor;
void setup()
{
    Serial.begin(9600);

    // wait until serial port opens for native USB devices
    while (!Serial) {
        delay(1);
    }

    Wire.begin(I2C_SDA, I2C_SCL);

    //sensor.setAddress((uint8_t)0x29);
    sensor.setTimeout(500);
    if (!sensor.init()) {
        Serial.println("Failed to detect and initialize sensor!");
        while (42);
    }
}

I always get "Failed to detect and initialize sensor!" on my serial console.
An i2c scanner returns:

Found address: 41 (0x29)
Done.
Found 1 device(s).

Any idea why that happens?
My sensor is labeled VL53L0/1XV2.

Timeout overflow

Timeout variables shall be unsigned long, so if sensor init() is called latter after MCU start up they do not overflow. This happened to me !!

uint16_t io_timeout; => unsigned long io_timeout;
uint16_t timeout_start_ms; => unsigned long timeout_start_ms;

Also timeout functions signatures shall also be unsigned long:

inline void setTimeout(unsigned long timeout)
inline unsigned long getTimeout(void)

Init error

If sensor not present, the init procedure still returns true.

Thank you for your work.

Reboot loop when I2C Bus is not in a good state

Hello

I'm experiencing a boot loop in certain circumstances I'm trying to discover.

The ESP8266 continuously reboot very quickly.

As far as I know, the problem arise only when these conditions are met together
1 - The Chip (Vl53) is in a kind of bad state
2 - We attempt to change the timing budget (sensor.setMeasurementTimingBudget(20000); right after init.

My reduced sketch is

sensor.setTimeout(500);
if (!sensor.init()) { ... }
sensor.setMeasurementTimingBudget(20000);

debugPrint.c error in atmega2560

Hi,

I am using atmel studio 7.0 for the code, however in the library debugPrint.c in function 'void debugInit()' there is an error when I build a solution and says that 'PRR' has not been declared. I don´t know what PRR is doing or what it is so I have no idea on how to proceed.

Francisco.

Calibration

First of all, thanks for sharing your work and sorry for posting a question as an issue. Couldn't find any other better place to post it.

I now the readme says that this library is not providing a calibration API. However, I'd like to ask if it's possible to hardcode a calibration somewhere?

I really want to use this library as it's super thin and it works well with my setup, but I'm using the sensor under a cover glass making it to throw a lot of false positives.

Thanks in advance and sorry for the inconvenience.

Sensor time out after day's of operation

I am using you library with 2 vl53l0x sensors, and noticed a recent change in behaviour. After a random amount of time, ranging from ~20 hours to a few days, the sensors start to time out.
I have 2 sensors connected to an wemos d1 mini. The cause might have been related to updating to the latest library.

I've updated the sketch a few days ago, and sinds then the sensors seem to start timing out, i.e giving a range of 65535. Sometimes it is only one of the sensors, but mostly both will stop working.

The Library I used was 1.0.2 and now I am using the latest available. I do not really know if this is the cause, but since nothing else changed, I thought this might be a starting point..

A soft reset will get the sensors back up again, so not a real issue, but it would be nice to run the ESP without resetting it all the time.

any idea why this could be happening?

Range offset

Hello,
just got the sensor.
Using this library, the free sensor returns values more or less 80mm bigger that real.
I did not cover the sensor, just a ranging test and i get this big offset.
I was wondering if this is common, because i see the library has not implemented the offset command provided for by the sensor.
Thanks

Sensors on different I2C channels

Hi there,

for an ESP32-based project, we needed a way to distribute sensors on the two separate hardware wires (Wire. and Wire1.). The modified version of the lib is attached (VL53L0X-2xI2C.zip).

@kevin-pololu Changes are straight forward. Would be great if this could be integrated into the master branch at some point.

How to use:

#include <Wire.h>
#include "VL53L0X-2xI2C.h"

VL53L0X sensor;
VL53L0X sensor2;

Wire.begin(GPIOSDA,GPIOSCL); // initialize I2C w/ I2C pins from config
present = sensor.init(true, &Wire);

Wire1.begin(GPIOSDA2,GPIOSCL2); // initialize I2C w/ I2C pins from config
present2 = sensor2.init(true, &Wire1);

Cheers,
Torben

Getting below compilation errors when try to run examples

Am using Version 1.3.0 with Raspberry Pi Pico

/Users/Documents/Arduino/libraries/VL53L0X/VL53L0X.cpp: In member function 'void VL53L0X::writeReg32Bit(uint8_t, uint32_t)':
/Users/Documents/Arduino/libraries/VL53L0X/VL53L0X.cpp:309:34: error: call of overloaded 'write(long unsigned int)' is ambiguous
   bus->write((value >> 24) & 0xFF); // value highest byte
                                  ^
In file included from /Users/Documents/Arduino/libraries/VL53L0X/VL53L0X.h:5:0,
                 from /Users/Documents/Arduino/libraries/VL53L0X/VL53L0X.cpp:6:
/Users/Library/Arduino15/packages/arduino/hardware/mbed_rp2040/2.8.0/libraries/Wire/Wire.h:59:20: note: candidate: virtual size_t arduino::MbedI2C::write(uint8_t)
     virtual size_t write(uint8_t data);
                    ^~~~~
/Users/Library/Arduino15/packages/arduino/hardware/mbed_rp2040/2.8.0/libraries/Wire/Wire.h:60:20: note: candidate: virtual size_t arduino::MbedI2C::write(int)
     virtual size_t write(int data) {
                    ^~~~~
/Users/Documents/Arduino/libraries/VL53L0X/VL53L0X.cpp:310:34: error: call of overloaded 'write(long unsigned int)' is ambiguous
   bus->write((value >> 16) & 0xFF);
                                  ^
In file included from /Users/Documents/Arduino/libraries/VL53L0X/VL53L0X.h:5:0,
                 from /Users/Documents/Arduino/libraries/VL53L0X/VL53L0X.cpp:6:
/Users/Library/Arduino15/packages/arduino/hardware/mbed_rp2040/2.8.0/libraries/Wire/Wire.h:59:20: note: candidate: virtual size_t arduino::MbedI2C::write(uint8_t)
     virtual size_t write(uint8_t data);
                    ^~~~~
/Users/Library/Arduino15/packages/arduino/hardware/mbed_rp2040/2.8.0/libraries/Wire/Wire.h:60:20: note: candidate: virtual size_t arduino::MbedI2C::write(int)
     virtual size_t write(int data) {
                    ^~~~~
/Users/Documents/Arduino/libraries/VL53L0X/VL53L0X.cpp:311:34: error: call of overloaded 'write(long unsigned int)' is ambiguous
   bus->write((value >>  8) & 0xFF);
                                  ^
In file included from /Users/Documents/Arduino/libraries/VL53L0X/VL53L0X.h:5:0,
                 from /Users/Documents/Arduino/libraries/VL53L0X/VL53L0X.cpp:6:
/Users/Library/Arduino15/packages/arduino/hardware/mbed_rp2040/2.8.0/libraries/Wire/Wire.h:59:20: note: candidate: virtual size_t arduino::MbedI2C::write(uint8_t)
     virtual size_t write(uint8_t data);
                    ^~~~~
/Users/Library/Arduino15/packages/arduino/hardware/mbed_rp2040/2.8.0/libraries/Wire/Wire.h:60:20: note: candidate: virtual size_t arduino::MbedI2C::write(int)
     virtual size_t write(int data) {
                    ^~~~~
/Users/Documents/Arduino/libraries/VL53L0X/VL53L0X.cpp:312:34: error: call of overloaded 'write(long unsigned int)' is ambiguous
   bus->write( value        & 0xFF); // value lowest byte
                                  ^
In file included from /Users/Documents/Arduino/libraries/VL53L0X/VL53L0X.h:5:0,
                 from /Users/Documents/Arduino/libraries/VL53L0X/VL53L0X.cpp:6:
/Users/Library/Arduino15/packages/arduino/hardware/mbed_rp2040/2.8.0/libraries/Wire/Wire.h:59:20: note: candidate: virtual size_t arduino::MbedI2C::write(uint8_t)
     virtual size_t write(uint8_t data);
                    ^~~~~
/Users/Library/Arduino15/packages/arduino/hardware/mbed_rp2040/2.8.0/libraries/Wire/Wire.h:60:20: note: candidate: virtual size_t arduino::MbedI2C::write(int)
     virtual size_t write(int data) {
                    ^~~~~
exit status 1
Error compiling for board Raspberry Pi Pico.

Multiple devices

Hello,

I am trying to use multiple devices with this library, currently with adafruit one I can change the I2c adress with this code: lox.begin(0x30)

But I do not know where to change it here.

Let me know,

Thanks

Is this a type error?

That local uint16_t value should be a uint32_t, or not?

// Read a 32-bit register
uint32_t VL53L0X::readReg32Bit(uint8_t reg)
{
  uint16_t value;

  Wire.beginTransmission(address);
  Wire.write(reg);
  last_status = Wire.endTransmission();

  Wire.requestFrom(address, (uint8_t)4);
  value  = (uint32_t)Wire.read() << 24; // value highest byte
  value |= (uint32_t)Wire.read() << 16;
  value |= (uint16_t)Wire.read() <<  8;
  value |=           Wire.read();       // value lowest byte

  return value;
}

Sensor on ESP32

Have you ever had the code working with the ESP32? I have a sensor that functions fine on the ESP8266. Load the single and/or continuous sketch again for the ESP32 and it fails to get anywhere. There is simply no output on the serial monitor. I did try with and without using external pullup resistors. I found and loaded an IC2 scanner sketch and once loaded it does recognize the sensor.

Any thoughts?

VL53L0X and ESP8226 - Failed to detect ...

Hi,

I get a "Failed to detect and initialize sensor!" when using the Pololu VL53L0X Arduino library.
Arduino version ist 1.8.13. VL53L0X version is 1.3, downgrading to 1.2 didn't help. I'm compiling
for a Wemos D1 mini (ESP8226).

Using Your original code example 'single' will produce the above error and also cause repetitive reboots.
This can easily be remedied by inserting delays:

if (!sensor.init()) { Serial.println("Failed to detect and initialize sensor!"); while (1) {delay(1);} }

instead of

if (!sensor.init()) { Serial.println("Failed to detect and initialize sensor!"); while (1) {} }

Any suggestions?
Thanks,
Christoph

Making rover move with VL53L0X attached on servo motor (to detect obstacle), IR Sensor to detect line/ path

Hi, I am trying to code a rover that will detect obstacle using vl53l0x and stay clear from it. Also, in case obstacle is not there, it should follow it's path which can be detected using two IR line sensors.

I have written partial code so far. The rover works only with IR sensors in the previous version of code. When i try to incorporate the time of flight sensor VL53L0X too, the motors doesn't move. (Only the servo motor moves the 45 degrees as i have coded here.

Here is my code block:

#include<Wire.h>
#include<VL53L0X.h>
#include<Servo.h>

int servoPin =4;
VL53L0X sensor;
Servo Servo1;

#define HIGH_SPEED

int sensorval;
int obstacle =150;

const int NORMAl_SPEED = 90;
const int TURN_SPEED_H = 100;

//Motor pins
const int motorSpeedPinA = 9;
const int motorDirPinA = 7;
const int motorSpeedPinB = 10;
const int motorDirPinB = 8;
const int modePin = 11;

//IR pins
const int leftSensor = A0;
const int rightSensor = A1;

boolean leftFlag = 0;
boolean rightFlag = 0;

void setup()
{
pinMode(motorSpeedPinA, OUTPUT);
pinMode(motorSpeedPinB, OUTPUT);
pinMode(motorDirPinA, OUTPUT);
pinMode(motorDirPinB, OUTPUT);
pinMode(modePin, OUTPUT);
digitalWrite(modePin, HIGH);
pinMode(leftSensor, INPUT);
pinMode(rightSensor, INPUT);
Servo1.attach(servoPin);
Servo1.write(90);
Serial.begin(9600);
Wire.begin();

sensor.setTimeout(500);
if (!sensor.init())
{
Serial.println("Failed to detect and initialize sensor!");
while (1) {}
}

#if defined HIGH_SPEED
// reduce timing budget to 20 ms (default is about 33 ms)
sensor.setMeasurementTimingBudget(20000);
#endif

stop_vehicle();
}

void loop()
{
leftFlag = !digitalRead(leftSensor);
rightFlag = !digitalRead(rightSensor);
sensorval = sensor.readRangeSingleMillimeters();
Serial.print(sensorval);
if (sensor.timeoutOccurred()) { Serial.print(" TIMEOUT"); }
Serial.println();

if(sensorval < 150)
{
Servo1.write(45);
delay(500);
turn_left_vehicle();
}
if(leftFlag)
{
//Serial.println("Left");
turn_right_vehicle();
}
else if(rightFlag)
{
//Serial.println("Right");
turn_left_vehicle();
}
else
{
forward_vehicle();

}

delay(20);
}

void stop_vehicle()
{
analogWrite(motorSpeedPinA, 0);
analogWrite(motorSpeedPinB, 0);
}

void forward_vehicle()
{
digitalWrite(motorDirPinA, HIGH);
digitalWrite(motorDirPinB, HIGH);
analogWrite(motorSpeedPinA, NORMAl_SPEED);
analogWrite(motorSpeedPinB, NORMAl_SPEED);

}

void turn_left_vehicle()
{
digitalWrite(motorDirPinA, LOW);
digitalWrite(motorDirPinB, HIGH);
analogWrite(motorSpeedPinA, TURN_SPEED_H);
analogWrite(motorSpeedPinB, NORMAl_SPEED);
}

void turn_right_vehicle()
{
digitalWrite(motorDirPinA, HIGH);
digitalWrite(motorDirPinB, LOW);
analogWrite(motorSpeedPinA, NORMAl_SPEED);
analogWrite(motorSpeedPinB, TURN_SPEED_H);
}

/*void object_detected()
{

Servo1.write(45);
delay(500);
turn_left_vehicle();   

}*/

i2c freezes

hi, I have connected VL530L0X, I run the "Continuous" example and there is nothing in the serial monitor. It's the same with Adafarit.
I started the i2c scanner and it also froze. I tested it on nano, mega and uno. at first I sinned on serial, but it works. what should I do?

Soft reset sensors

Whats the correct way to soft reset sensors? I tried to perform the steps which are initially used in the setup() function again but that is not working.

  pinMode(ROOM_XSHUT, OUTPUT);
  pinMode(CORRIDOR_XSHUT, OUTPUT);

  pinMode(ROOM_XSHUT, INPUT);
  wait(10);
  ROOM_SENSOR.setAddress(ROOM_SENSOR_newAddress);
  pinMode(CORRIDOR_XSHUT, INPUT);
  wait(10);
  CORRIDOR_SENSOR.setAddress(CORRIDOR_SENSOR_newAddress);
  ROOM_SENSOR.init();
  CORRIDOR_SENSOR.init();
  ROOM_SENSOR.setTimeout(500);
  CORRIDOR_SENSOR.setTimeout(500);

Background: It happend sometimes that the sensors are getting timeouts or wrong values after a few days. When that is happening i just want to soft reset them instead of power off the whole system.

Xtalk issue

Thank you for your fine work.
Now I have known that it was necessary to set Xtalk compensation with cover window.
Though I also read some documents about STM api, it was too difficult to understand it.
Could you add the code about setting that?
Many thanks

Fix interrupt and waiting

Sorry, I don't yet know hot to make a pull request but i thought this might be useful to others.

In the cpp file init method change line 239 to:
writeReg(GPIO_HV_MUX_ACTIVE_HIGH, readReg(GPIO_HV_MUX_ACTIVE_HIGH) & 0xEF);

this will make the GPIO pin go low when a measurement is done.

I would also add this two methods (maybe you have a better name for the second one) which splits the continuous read in two parts.

bool VL53L0X::dataAvailable(void)
{
if((readReg(RESULT_INTERRUPT_STATUS) & 0x07) == 0)
return false;
else return true;
}

uint16_t VL53L0X::readRangeDataContinuous(void)
{
uint16_t range = readReg16Bit(RESULT_RANGE_STATUS + 10);
writeReg(SYSTEM_INTERRUPT_CLEAR, 0x01);
return range;
}

You can use it like so:

if(sensor.dataAvailable())
{
Serial.println(sensor.readRangeDataContinuous());
}

Reading the sensor like this is leaves much more time for other stuff. Checking for data takes about 120 us and reading takes 230us on a tennsy 3.2. The original way takes around 20 ms. Using the interrupt pin makes checking even faster:). I measured this with the Wire clock at 400000.

Using multiple sensors on the same i2c bus

Thank you very much for your work so far. I am trying to use two sensors on the same i2c bus of an arduino. I do use the Satellite boards by ST, however I think there shouldn't be much difference.
My question is: Have you tried using to instances of the sensor at the same time? Maybe I am doing something wrong?
Here is the code I try to use ATM:
The XShut pins of the sensors are connected to pins 4 and 5 of the arduino.

#include <Wire.h>
#include <VL53L0X.h>

VL53L0X sensor;
VL53L0X sensor2;

void setup()
{

  pinMode(5, OUTPUT);
  pinMode(4, OUTPUT);
  digitalWrite(4, LOW);
  digitalWrite(5, LOW);

  delay(500);
  Wire.begin();


  Serial.begin (9600);

  digitalWrite(4, HIGH);
  delay(150);
  Serial.println("00");
  sensor.init(true);

  Serial.println("01");
  delay(100);
  sensor.setAddress((uint8_t)22);
  Serial.println("02");

  digitalWrite(5, HIGH);
    delay(150);
  sensor2.init(true);
  Serial.println("03");
  delay(100);
  sensor2.setAddress((uint8_t)25);
  Serial.println("04");

  Serial.println("addresses set");



}

void loop()
{
  Serial.println ("I2C scanner. Scanning ...");
  byte count = 0;


  for (byte i = 1; i < 120; i++)
  {

    Wire.beginTransmission (i);
    if (Wire.endTransmission () == 0)
    {
      Serial.print ("Found address: ");
      Serial.print (i, DEC);
      Serial.print (" (0x");
      Serial.print (i, HEX);
      Serial.println (")");
      count++;
      delay (1);  // maybe unneeded?
    } // end of good response
  } // end of for loop
  Serial.println ("Done.");
  Serial.print ("Found ");
  Serial.print (count, DEC);
  Serial.println (" device(s).");

  delay(3000);
}

It will stop after line 29, at the first init. If I only connect one sensor and change its address it works fine.
Any hints are highly appreciated! And again, thanks for the library!

multiple devices

hello, i don't have much experience with i2c connection.

how can i connect 6 different vl53L0x in one bus?

i have tried to connect all of them parallel; 5V, GND, SDA, SCL. it just shows one address, connected 2.2k resistors between main sda , scl cables and 5v, didn't worked also.

am i doing something wrong?

having trouble booting sensor "failed to boot VL53L0x

hi, I recently got a icstation VL53L0x laser distance sensor and when I connect it to an Arduino nano(properly I am pretty sure) I get a "failed to boot Vl53L0x" error message. I am using the adafruit example to test the sensor and get a handle of it for later projects.
my connections are as follows
5v to VCC
ground to ground
SCL to A5
SDA to A4

checkTimeoutExpired() comparison does integer promotion incorrectly

We noticed an integer promotion bug in the checkTimeoutExpired() macro (the subtraction result should be cast to uint16_t, not millis()); should fix and make a new release. This should work:
((io_timeout > 0) && ((uint16_t)(millis() - timeout_start_ms) > io_timeout))

Multiple Sensors

Hi !
What is the default address? And how can we use multiple sensors? Can there be a short code to assign addresses?
Thanks

ESP8266 divide by 0 reboot when device not present

On my ESP8266, this library caused reboots during init when the device wasn't found on the I2C bus. I tracked it down to the 'setMeasurementTimingBudget' call and then to the return line in the timeoutMicrosecondsToMclks routine.
1016: return (((timeout_period_us * 1000) + (macro_period_ns / 2)) / macro_period_ns);

The 'macro_period_ns' variable was zero which generated a Div0 error\crash.
I added the line below to fix it, but I'm sure there is a better way.
if (!macro_period_ns) macro_period_ns++; //avoid divide by zero

Great library, Thanks for contributing it.

Reading from pH sensor and dissolved oxygen sensor on same i2c bus

I am trying to read from these sensors but only 1 sensor's reading is coming on the serial monitor on sending the 'R' character. the code is
`#include <Wire.h> //enable I2C.
#define address 97 //default I2C ID number for EZO D.O. Circuit.
#define address_pH 99 //default I2C ID number for EZO pH Circuit.

char computerdata[20]; //we make a 20 byte character array to hold incoming data from a pc/mac/other.
byte received_from_computer = 0; //we need to know how many characters have been received.
byte code = 0; //used to hold the I2C response code.
char DO_data[20]; //we make a 20 byte character array to hold incoming data from the D.O. circuit.
byte in_char = 0; //used as a 1 byte buffer to store inbound bytes from the D.O. Circuit.
int time_ = 900; //used to change the delay needed depending on the command sent to the EZO Class D.O. Circuit.
float DO_float; //float var used to hold the float value of the DO.
char *DO; //char pointer used in string parsing.
char *sat; //char pointer used in string parsing.
float do_float; //float var used to hold the float value of the dissolved oxygen.
float sat_float; //float var used to hold the float value of the saturation percentage.

char computerdata_pH[20]; //we make a 20 byte character array to hold incoming data from a pc/mac/other.
byte received_from_computer_pH = 0; //we need to know how many characters have been received.
byte code_pH = 0; //used to hold the I2C response code_pH.
char pH_data[20]; //we make a 20-byte character array to hold incoming data from the pH circuit.
byte in_char_pH = 0; //used as a 1 byte buffer to store inbound bytes from the pH Circuit.
byte i = 0; //counter used for ph_data array.
int time_pH = 900; //used to change the delay needed depending on the command sent to the EZO Class pH Circuit.
float ph_float; //float var used to hold the float value of the pH.

void setup() //hardware initialization.
{
Serial.begin(9600); //enable serial port.
Wire.begin(); //enable I2C port.
}

void loop() { //the main loop.
byte i = 0; //counter used for DO_data array.

if (Serial.available() > 0) { //if data is holding in the serial buffer
received_from_computer = Serial.readBytesUntil(13, computerdata, 20); //we read the data sent from the serial monitor(pc/mac/other) until we see a . We also count how many characters have been received.
computerdata[received_from_computer] = 0; //stop the buffer from transmitting leftovers or garbage.
/* computerdata[0] = tolower(computerdata[0]); //we make sure the first char in the string is lower case.*/
if (computerdata[0] == 'c' || computerdata[0] == 'r')time_ = 900; //if a command has been sent to calibrate or take a reading we wait 600ms so that the circuit has time to take the reading.
else time_ = 300; //if not 300ms will do

Wire.beginTransmission(address);                                      //call the circuit by its ID number.

Wire.write(computerdata);                                             //transmit the command that was sent through the serial port.

   if (strcmp(computerdata, "sleep") != 0) {  //if the command that has been sent is NOT the sleep command, wait the correct amount of time and request data.
  //if it is the sleep command, we do nothing. Issuing a sleep command and then requesting data will wake the D.O. circuit.


  delay(time_);                     //wait the correct amount of time for the circuit to complete its instruction.

  Wire.requestFrom(address, 20, 1); //call the circuit and request 20 bytes (this may be more than we need)

  code = Wire.read();               //the first byte is the response code, we read this separately.

  switch (code) {                   //switch case based on what the response code is.
    case 1:                         //decimal 1.
      Serial.println("Success");    //means the command was successful.
      break;                        //exits the switch case.

    case 2:                         //decimal 2.
      Serial.println("Failed");     //means the command has failed.
      break;                        //exits the switch case.

    case 254:                      //decimal 254.
      Serial.println("Pending");   //means the command has not yet been finished calculating.
      break;                       //exits the switch case.

    case 255:                      //decimal 255.
      Serial.println("No Data from do");   //means there is no further data to send.
      break;                       //exits the switch case.
  }
}
while (Wire.available()) {       //are there bytes to receive.
  in_char = Wire.read();         //receive a byte.
  DO_data[i] = in_char;          //load this byte into our array.
  i += 1;
  if (in_char == 0 || in_char_pH == 0) {            //if we see that we have been sent a null command.
    i = 0;                       //reset the counter i to 0.
    Wire.endTransmission();      //end the I2C data transmission.
    break;                       //exit the while loop.
    Serial.println(DO_data);
    delay(100);
    Wire.beginTransmission(address_pH);                                      //call the circuit by its ID number.
    Wire.write(computerdata_pH);                                             //transmit the command that was sent through the serial port.
    Wire.endTransmission();                                               //end the I2C data transmission.
    if (isDigit(DO_data[0])) {
      string_pars();                  //If the first char is a number we know it is a DO reading, lets parse the DO reading
    }
    else {                            //if it’s not a number
      Serial.println(DO_data);        //print the data.
      for (i = 0; i < 20; i++) {      //step through each char
        DO_data[i] = 0;               //set each one to 0 this clears the memory
      }
    }

    if (strcmp(computerdata_pH, "sleep") != 0) {  //if the command that has been sent is NOT the sleep command, wait the correct amount of time and request data.
      //if it is the sleep command, we do nothing. Issuing a sleep command and then requesting data will wake the D.O. circuit.
    }
  }
}

}

   if (Serial.available() > 0) {                                           //if data is holding in the serial buffer
received_from_computer = Serial.readBytesUntil(13, computerdata, 20); //we read the data sent from the serial monitor(pc/mac/other) until we see a <CR>. We also count how many characters have been received.
computerdata[received_from_computer] = 0;                             //stop the buffer from transmitting leftovers or garbage.
/* computerdata[0] = tolower(computerdata[0]);                           //we make sure the first char in the string is lower case.*/
if (computerdata[0] == 'c' || computerdata[0] == 'r')time_ = 900;     //if a command has been sent to calibrate or take a reading we wait 600ms so that the circuit has time to take the reading.
else time_ = 300;                                                     //if not 300ms will do


Wire.beginTransmission(address);                                      //call the circuit by its ID number.

Wire.write(computerdata);                                             //transmit the command that was sent through the serial port.
   
   delay(time_pH);                     //wait the correct amount of time for the circuit to complete its instruction.
   
   Wire.requestFrom(address_pH, 20, 1); //call the circuit and request 20 bytes (this may be more than we need)
      code_pH = Wire.read();               //the first byte is the response code, we read this separately.
      switch (code_pH) {                  //switch case based on what the response code is.
        case 1:                         //decimal 1.
          Serial.println("Success");    //means the command was successful.
          break;                        //exits the switch case.

        case 2:                         //decimal 2.
          Serial.println("Failed");     //means the command has failed.
          break;                        //exits the switch case.

        case 254:                      //decimal 254.
          Serial.println("Pending");   //means the command has not yet been finished calculating.
          break;                       //exits the switch case.

        case 255:                      //decimal 255.
          Serial.println("No Data from pH");   //means there is no further data to send.
          break;                       //exits the switch case.

      }

  while (Wire.available()) {         //are there bytes to receive.
  in_char_pH = Wire.read();           //receive a byte.
  pH_data[i] = in_char_pH;            //load this byte into our array.
  i += 1;                          //incur the counter for the array element.
  if (in_char_pH == 0) {              //if we see that we have been sent a null command.
    i = 0;                         //reset the counter i to 0.
    Wire.endTransmission();        //end the I2C data transmission.
    break;                         //exit the while loop.
  }
}
     Serial.println(pH_data);          //print the data.
    }

}
void string_pars() { //this function will break up the CSV string into its 2 individual parts, DO and %sat.
byte flag = 0; //this is used to indicate is a “,” was found in the string array
byte i = 0; //counter used for DO_data array.

for (i = 0; i < 20; i++) {          //Step through each char
  if (DO_data[i] == ',') {          //do we see a ','
    flag = 1;                       //if so we set the var flag to 1 by doing this we can identify if the string being sent from the DO circuit is a CSV string containing tow values
  }
}

if (flag != 1) {                    //if we see the there WAS NOT a ‘,’ in the string array
  Serial.print("DO:");              //print the identifier
  Serial.println(DO_data);          //print the reading
}

if (flag == 1) {                    //if we see the there was a ‘,’ in the string array
  DO = strtok(DO_data, ",");        //let's pars the string at each comma
  sat = strtok(NULL, ",");          //let's pars the string at each comma
  Serial.print("DO:");              //print the identifier
  Serial.println(DO);               //print the reading
  Serial.print("Sat:");             //print the identifier
  Serial.println(sat);              //print the reading
  flag = 0;                         //reset the flag
}

/*                                //uncomment this section if you want to take the ASCII values and convert them into a floating point number.
  DO_float=atof(DO);
  sat_float=atof(sat);
*/

}`
only 1 sensor ,dissolved oxygen sensor is able to respond as can also be seen on the green led blink on the sensor. can you please help on this issue.?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.