Skip to main content
ADP1114
Associate III
August 15, 2019
Solved

Adding multiple vl53l0x sensors

  • August 15, 2019
  • 16 replies
  • 10884 views

Hi all

I have successfully implemented a single vl53l0x sensor, but wish to add more. I found the "AN4846 Application note Using multiple VL53L0X in a single design" documentation:

https://www.st.com/content/ccc/resource/technical/document/application_note/group0/0e/0a/96/1b/82/19/4f/c2/DM00280486/files/DM00280486.pdf/jcr:content/translations/en.DM00280486.pdf

Under "VL53L0X API management" it specifies:

In vl53L0x_platform.h API file set VL53L0x_SINGLE_DEVICE_DRIVER macro to 0 so that API implementation will be automatically adapted to a multi-device context.

But I cannot find anything called "VL53L0x_SINGLE_DEVICE_DRIVER" in the vl53L0x_platform.h file.

Where can I find it? Or has the files updated without the documentation being updated? If so should this step just be skipped?

Best answer by John E KVAM

​If you have one working, you are all set. There is a bit of a trick to it though.

Start with all sensors in shutdown.

Then bring up the first one by raising the shutdown pin. The sensor will come up to the default address.

Issue the command to change address.  - SetI2CAddress

Then bring up the second sensor.

Issue the command to change address. 

Repeat until all sensors have different addresses. - I use 0x62, 0x64, 0x66, 0x68, 0x6A...

Technically you don't have to change the address of the last one, but if you do you can use the default address as a health check. If you ever ping it and get an answer, one or more of your sensors has reset.

Then the trick is to insure you have the correct address set when making calls.

The psudo-code would look like this (it's for an L1X chip, but yours is similar:

void ResetAndInitializeAllSensors(void)
{
	VL53L1X_ERROR status;
 
	uint8_t i, Sensor, temp;
	int16_t Offset;
 
	ResetAllSensors();
	HAL_Delay(10);
	for (i = 0; i < NumOfTOFSensors; i++)
	{
		Dev[i] = 0x52;
		TurnOnSensor(i);
		HAL_Delay(5);
		do {
			status = VL53L1X_BootState(Dev[i], &temp);
			HAL_Delay(5);
			if (status) {
				UART_Print("BootState returned bad status\n");
			}
 
		} while (temp != 3);
 
 
		status += VL53L1X_SensorInit(Dev[i]);	/* Initialize sensor */
		status += VL53L1X_SetI2CAddress(Dev[i], DevAddr[i]);	/* Change i2c address Left is now 0x62 and Dev1 */
 
		CHECK_ERROR(status);
 
		Dev[i] = DevAddr[i];
		//status += VL53L1X_SensorInit(Dev[i]);	/* Initialize sensor */
	}
	UART_Print("All Chips booted\n");

16 replies

John E KVAM
John E KVAMBest answer
ST Employee
August 15, 2019

​If you have one working, you are all set. There is a bit of a trick to it though.

Start with all sensors in shutdown.

Then bring up the first one by raising the shutdown pin. The sensor will come up to the default address.

Issue the command to change address.  - SetI2CAddress

Then bring up the second sensor.

Issue the command to change address. 

Repeat until all sensors have different addresses. - I use 0x62, 0x64, 0x66, 0x68, 0x6A...

Technically you don't have to change the address of the last one, but if you do you can use the default address as a health check. If you ever ping it and get an answer, one or more of your sensors has reset.

Then the trick is to insure you have the correct address set when making calls.

The psudo-code would look like this (it's for an L1X chip, but yours is similar:

void ResetAndInitializeAllSensors(void)
{
	VL53L1X_ERROR status;
 
	uint8_t i, Sensor, temp;
	int16_t Offset;
 
	ResetAllSensors();
	HAL_Delay(10);
	for (i = 0; i < NumOfTOFSensors; i++)
	{
		Dev[i] = 0x52;
		TurnOnSensor(i);
		HAL_Delay(5);
		do {
			status = VL53L1X_BootState(Dev[i], &temp);
			HAL_Delay(5);
			if (status) {
				UART_Print("BootState returned bad status\n");
			}
 
		} while (temp != 3);
 
 
		status += VL53L1X_SensorInit(Dev[i]);	/* Initialize sensor */
		status += VL53L1X_SetI2CAddress(Dev[i], DevAddr[i]);	/* Change i2c address Left is now 0x62 and Dev1 */
 
		CHECK_ERROR(status);
 
		Dev[i] = DevAddr[i];
		//status += VL53L1X_SensorInit(Dev[i]);	/* Initialize sensor */
	}
	UART_Print("All Chips booted\n");

ADP1114
ADP1114Author
Associate III
August 16, 2019

Ah, thank you so much, does that mean the gpio pin isn't needed when working with multiple sensors?

John E KVAM
ST Employee
August 16, 2019

Try this - you said you got the initial sensor working. So change the HAL_GPIO_WritePin(XShut1_GPIO_Port,XShut1_Pin,1); to XShut2 and hit the other shutdown pin.

This will prove that both sensors are working and you don't have a hardware issue somewhere.

Once we know both are working - then we have to figure out what is going on.

There is a point of vulnerability just after having changing the I2C address - if you do it wrong, you lose the communication.

But your code looks fine to me.

Is vl53dev[0] identical to vl53dev[1] when you start out? I'm reasonably certain nothing in that structure matters except the address, but make them identical anyway.

Generally I like to use a "Status += " in front of all my function calls. You don't have to continue checking it, but during debug it's handy to look at. if it is ever non-zero, you know something went wrong.

Try changing the address PRIOR to doing the DataInit(). That might tell you something.

ADP1114
ADP1114Author
Associate III
August 16, 2019

I switched the XShut pins and the other sensor works just fine.

The only difference between vl53dev[0] and vl53dev[1] was the Id and DevLetter (I declared it because it was declared in the example code).

I made them identical and it didn't change anything. I switched the DataInit() and HAL_GPIO_WritePin(), but unfortunately it didn't change anything either. :(

John E KVAM
ST Employee
August 16, 2019

if you have one sensor working you don't need a HAL_I2C_IsDeviceReady(). Skip that step and just assume the I2C is ready. I have no idea what that does - it's an STM32 function, and the Sensor does not know about it.

Decide if the sensor is working by telling it to start and seeing if it ranges.

The extra ping makes no sense.

ADP1114
ADP1114Author
Associate III
August 16, 2019

Okay, I removed it, but the sensors give the same reading (exact digits) even though I am holding an object at different distances.

The second sensor doesn't cause a change in value, but the first sensor does..

John E KVAM
ST Employee
August 16, 2019

Make VERY sure BOTH parts were in reset before you started!!

If both sensors receive the change address command, you will get this type of behavior.

When you make a call try using getting the Status on all your calls. i.e. Status+= VL53L0X_PerformSingleRangingMeasurement().

I'm guessing because you use the same structure for both, when the second fails your structure remains unchanged.

Or you can zero the structure between calls.

When you get the &DistanceData structure back from the PerformSingleRangingMeasurement() function, look at the .RangingStatus. It could be the range fails for some reason. If you get a non-zero RangeStatus it will give you an idea of what went wrong.

ADP1114
ADP1114Author
Associate III
August 17, 2019

Okay, I now added the VL53L0X_ResetDevice() function before each device's VL53L0X_DataInit(). The reading still doesn't change for the second sensor. Should I reset the device before each reading, or just before the DataInit?

I then added a new struct in order to save sensors in different structs. It also didn't change anything.

I added a new variable to save the distance data in separate variables rather than overwriting one. The second sensor now only gives a reading of 0. So it would seem that the data isn't being updated when VL53L0X_PerformSingleRangingMeasurement() is called.

I checked the range status for sensor 2, it also gives 0.

When I switch the sensors (through the previously done XShut method). The 2nd sensor gives a reading, but the first sensor does not.

I also tried switching the sensors off (by bringing xshut low) when not in use. But that didn't do anything either.

I added the status+= and found a value of 236 when resetting the second sensor. If I remove the reset and just use DataInit() the status = 236. The initialization, reset and address change of the first sensor gave 0 values.

FPayn.1
Associate III
June 5, 2020

I'm planning to use two arrays of three VL53L0X sensors each in a robotics application using a Teensy (Arduino-ish) microcontroller. I have one array of three sensors working already, using the technique described by John. I have a fairly detailed post, with software on my blog site at https://www.fpaynter.com/2020/06/replacing-hc-sro4-ultrasonic-sensors-with-vl53l0x-arrays/

KNawa.1
Associate II
June 19, 2022

I have similar situation. I want to use 2 sensors, but when they are both online(XSHUT=1) measurement data is wrong and random when I use one sensor data is OK. I add my code maybe I do something wrong...

Config:

#define sensor_qty 2			// max. 2
 
#define original_addr 	0x52
#define sensor1_addr 	0x53
#define sensor2_addr 	0x54

main:

uint8_t Message[64];
uint8_t MessageLen;
 
VL53L0X_RangingMeasurementData_t RangingData[sensor_qty];
VL53L0X_Dev_t vl53l0x_c[sensor_qty]; 			// center module
 
VL53L0X_DEV Dev = &vl53l0x_c[0];
VL53L0X_DEV Dev1 = &vl53l0x_c[1];
 
//
// VL53L0X initialisation stuff
//
uint32_t refSpadCount;
uint8_t isApertureSpads;
uint8_t VhvSettings;
uint8_t PhaseCal;
 
uint16_t sensorMeasure[sensor_qty];
 Dev->I2cHandle = &hi2c1;
 Dev1->I2cHandle = &hi2c1;
 Dev->I2cDevAddr = Dev1->I2cDevAddr = original_addr;
 
 HAL_GPIO_WritePin(TOF_XSHUT1_GPIO_Port, TOF_XSHUT1_Pin, GPIO_PIN_RESET); 	// Disable XSHUT
 HAL_GPIO_WritePin(TOF_XSHUT2_GPIO_Port, TOF_XSHUT2_Pin, GPIO_PIN_RESET); 	// Disable XSHUT
 HAL_Delay(10);
 
 // addr change 1st sensor
 HAL_GPIO_WritePin(TOF_XSHUT1_GPIO_Port, TOF_XSHUT1_Pin, GPIO_PIN_SET); 		// Enable XSHUT
 HAL_Delay(20);
 
 //VL53L0X_ResetDevice(Dev);
 VL53L0X_WaitDeviceBooted(Dev);
 VL53L0X_DataInit( Dev );
 MessageLen = sprintf((char*)Message,"Addr change 1: %i \n\r\n\r", VL53L0X_SetDeviceAddress(Dev, sensor1_addr));
 HAL_UART_Transmit(&huart1, Message, MessageLen, 100);
 Dev->I2cDevAddr = sensor1_addr;
 
	 VL53L0X_WaitDeviceBooted( Dev );
	 //VL53L0X_DataInit( Dev );
	 VL53L0X_StaticInit( Dev );
	 VL53L0X_PerformRefCalibration(Dev, &VhvSettings, &PhaseCal);
	 VL53L0X_PerformRefSpadManagement(Dev, &refSpadCount, &isApertureSpads);
	 VL53L0X_SetDeviceMode(Dev, VL53L0X_DEVICEMODE_SINGLE_RANGING);
 
	 // Enable/Disable Sigma and Signal check
	 VL53L0X_SetLimitCheckEnable(Dev, VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE, 1);
	 VL53L0X_SetLimitCheckEnable(Dev, VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE, 1);
	 VL53L0X_SetLimitCheckValue(Dev, VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE, (FixPoint1616_t)(0.1*65536));
	 VL53L0X_SetLimitCheckValue(Dev, VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE, (FixPoint1616_t)(60*65536));
	 VL53L0X_SetMeasurementTimingBudgetMicroSeconds(Dev, 33000);
	 VL53L0X_SetVcselPulsePeriod(Dev, VL53L0X_VCSEL_PERIOD_PRE_RANGE, 18);
	 VL53L0X_SetVcselPulsePeriod(Dev, VL53L0X_VCSEL_PERIOD_FINAL_RANGE, 14);
 
 
 // addr change 2nd sensor
 HAL_GPIO_WritePin(TOF_XSHUT2_GPIO_Port, TOF_XSHUT2_Pin, GPIO_PIN_SET); 		// Enable XSHUT
 HAL_Delay(20);
 
 //VL53L0X_ResetDevice(Dev1);
 VL53L0X_WaitDeviceBooted(Dev1);
 //VL53L0X_DataInit( Dev1 );
 MessageLen = sprintf((char*)Message,"Addr change 2: %i \n\r\n\r", VL53L0X_SetDeviceAddress(Dev1, sensor2_addr));
 HAL_UART_Transmit(&huart1, Message, MessageLen, 100);
 Dev1->I2cDevAddr = sensor2_addr;
 
	 VL53L0X_WaitDeviceBooted( Dev1 );
	 VL53L0X_DataInit( Dev1 );
	 VL53L0X_StaticInit( Dev1 );
	 VL53L0X_PerformRefCalibration(Dev1, &VhvSettings, &PhaseCal);
	 VL53L0X_PerformRefSpadManagement(Dev1, &refSpadCount, &isApertureSpads);
	 VL53L0X_SetDeviceMode(Dev1, VL53L0X_DEVICEMODE_SINGLE_RANGING);
 
	 // Enable/Disable Sigma and Signal check
	 VL53L0X_SetLimitCheckEnable(Dev1, VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE, 1);
	 VL53L0X_SetLimitCheckEnable(Dev1, VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE, 1);
	 VL53L0X_SetLimitCheckValue(Dev1, VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE, (FixPoint1616_t)(0.1*65536));
	 VL53L0X_SetLimitCheckValue(Dev1, VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE, (FixPoint1616_t)(60*65536));
	 VL53L0X_SetMeasurementTimingBudgetMicroSeconds(Dev1, 33000);
	 VL53L0X_SetVcselPulsePeriod(Dev1, VL53L0X_VCSEL_PERIOD_PRE_RANGE, 18);
	 VL53L0X_SetVcselPulsePeriod(Dev1, VL53L0X_VCSEL_PERIOD_FINAL_RANGE, 14);

measure loop:

	 	if(VL53L0X_PerformSingleRangingMeasurement(Dev, &RangingData[0]) == 0){
		 	if(RangingData[0].RangeStatus == 0){
		 		sensorMeasure[0]= RangingData[0].RangeMilliMeter;
		 	}else{
		 		//MessageLen = sprintf((char*)Message, "STATUS1: %i\n\r", RangingData.RangeStatus);
		 		//HAL_UART_Transmit(&huart1, Message, MessageLen, 100);
		 	}
	 	}else{
	 	 //MessageLen = sprintf((char*)Message, "BRAK POMIARU!\n\r");
	 	 //HAL_UART_Transmit(&huart1, Message, MessageLen, 100);
	 	}
 
 
	 	if(VL53L0X_PerformSingleRangingMeasurement(Dev1, &RangingData[1]) == 0){
		 	if(RangingData[1].RangeStatus == 0){
		 		sensorMeasure[1]= RangingData[1].RangeMilliMeter;
		 	}else{
		 		//MessageLen = sprintf((char*)Message, "STATUS2: %i\n\r", RangingData.RangeStatus);
		 		//HAL_UART_Transmit(&huart1, Message, MessageLen, 100);
		 	}
	 	}else{
	 		//MessageLen = sprintf((char*)Message, "BRAK POMIARU!\n\r");
	 		//HAL_UART_Transmit(&huart1, Message, MessageLen, 100);
	 	}
 
 
 		MessageLen = sprintf((char*)Message, "Pomiar odleglosci: %imm %imm\n\r", sensorMeasure[0], sensorMeasure[1]);
 		HAL_UART_Transmit(&huart1, Message, MessageLen, 100);

FPayn.1
Associate III
June 19, 2022
Hi,
I have been using 7ea VL53L0X in my robotics projects for quite some time with no problems after I figured out how to initialize them to unique addresses (this must be done each time in setup()). Here is a link to my blog site where you can see how it is done. You should be able to copy/paste my setup() function into your code and modify for just 2ea VL53L0X
Hope this helps,
Frank
KNawa.1
Associate II
June 19, 2022

thx, but Your code is for Arduino my is written in Cube based on ST API. I assume here can be an issue...

KNawa.1
Associate II
June 20, 2022

thx, i will check based on Your advice!

John E KVAM
ST Employee
June 21, 2022

I have another suggestion that might also help. There is a project on ST.com.:

STSW-IMG017 Embedded SoftwareImaging software2D LIDAR using multiple VL53L1X Time-of-Flight long distance ranging sensors.

This project is for the VL53L1X, but just look over the initialization section. It inits 9 sensors. It also

uses a Nucleo board, so that might help as well.

But I do have to admit that Knawa.1's code is pretty good and should get you rolling.

  • john

John E KVAM
ST Employee
June 21, 2022

Oops - I found the bug. In your code

#define original_addr 	0x52
#define sensor1_addr 	0x53
#define sensor2_addr 	0x54

your addresses are too close together.

Each I2C device has a write address and a read address. And the read is has the LSB set.

So only use even addresss to set them. That leaves the odd addresses open for the reads.

I use 62,72,82 ... but you could use 54, 56, 58... just as easily.

KNawa.1
Associate II
June 21, 2022

John,

thx!, You were right! everything was OK excepts addressing I have changed to:

#define original_addr 	0x52
#define sensor1_addr 	0x54
#define sensor2_addr 	0x56

and now works! I missed address is devided by 2

BTW: AN4846 is not valid any more when 2.2 is not updated to newst API

John E KVAM
ST Employee
May 28, 2024

Could you open a new issue on this topic? 

It gets confusing when topics change. 

But the answer is our engineers called those GPIOs when they invented the chip. But then gave the defined roles and don't have any option to change those roles. So, they are no longer GPIOs and should have been renamed. But that is not our way apparently. 

Long story short - unfortunately you cannot cheat. You need one line for the Xshut on every sensor.