Ardupilot I2c devices not communicating after address change

So I have an indoor i2c lidar array using vl53l1x modules. These modules need to be onlined in sequence using their XSet pins at startup in order to program their addresses. I implemented a XAIO rp2040 to handle the setup procedure:

  • Sequentially online the sensors and assign their addresses.
  • Test each sensor by acquiring a measurement
  • Release the interrupts and deinit the I2c bus.
  • Re-init the I2c bus as a peripheral device.
  • Ardupilot’s boot delay expires and the flight controller takes over as I2c master.

Code: # Write your code here :-)# https://github.com/adafruit/Adafruit_CircuitPython - Pastebin.com

Library: Adafruit_CircuitPython_VL53L1X/adafruit_vl53l1x.py at main · adafruit/Adafruit_CircuitPython_VL53L1X · GitHub

All of this works, I can test the sensors, everything seems perfect… Except Ardupilot just reports “rangefinder x: no data” (Note that it’s not the “not detected” message so it IS seeing the device).

In addition to this I have other devices on the same I2c bus that are working without issue, it strikes me that there is a specific state that Ardupilot wants the devices in in order to begin communication; however, I am unsure of how to identify the specifics.

Params:
nonworking.param (19.4 KB)

I am baffled on how to address this issue, any help would be great.

To narrow the possibilities I have revised my code to exclude I2C altogether:

All I am going here is powering off all the sensors except for one, and then attempting to read the data. The result is the same “rangefinder 1: no data”.

In hopes of further isolating the issue, I have set up a known-working scenario to get a baseline here:

Then I reverted ardupilot to defaults and configured it to use only the single sensor over I2c:


PulseViewData.zip (4.5 KB)

I believe the read is at the end:

From the adafruit driver:
_PHASECAL_CONFIG__TIMEOUT_MACROP = const(0x004B)
This is the range_mode address, the range measurement is stored in:
_VL53L1X_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0 = const(0x0096)

After reading the rangefinder file in the repo, Everything appears to line up, so I doubt this is the origin of the problem.

Common issues would be more along the lines of forgetting to terminate the end of the bus with a resistor, a clash in address space (two devices with the same i2c address), an issue with the bus speed negotiation, or a length issue. Off the top of my head you get 3ft.

Oh and voltage incompatibilities like the whole bus needs to be 3.3 or 5v, where you need a logic level shifter to jump between and I have also had issues with clock stretching.

With one Benewake serial TFMini downwards, and four I2C TFLuna’s front/back/left/right (addresses changed), the five supplied with an independent 5V supply, I have observed similar effects. I think turning off and on was the only solution, since everything seemed right. Here it all worked.

This setup is all 3.3v, the drone is small so I know it’s far less than three feet, what kind of resistor setup did you use for the termination?

I have already used a 328 to change the sensor addresses, i never flight tested it.

Whats interesting is I can’t get the sensor to communicate even when I use a single unit with the default address. This is a 3.3v system, what’s odd is the sensors are indeed detected at the target address, but data sampling never initiates.

This is very similar to my script, with the exception that mine opens and takes a reading from each sensor to confirm it’s functioning. I’m still baffled as to why Ardupilot cannot receive data from only the VL53L0x sensors, the I2c compass modules work without issue on the same bus.

The FC is a JHEMCU-GSF405A (it’s a small drone):

are you sure the driver is there for it? have you used the custom firmware builder to make a firmware with the rangefinder drivers?

I have indeed
selected_features.txt (275 Bytes)

I think you need to add the VL53l0x driver, when I use the VL53l1x in my rover im using it set as type 16 the same as the VL53l0x,

RNGFND1_ADDR,41
RNGFND1_FUNCTION,0
RNGFND1_GNDCLEAR,50
RNGFND1_MAX_CM,120
RNGFND1_MIN_CM,5
RNGFND1_OFFSET,0
RNGFND1_ORIENT,0
RNGFND1_PIN,-1
RNGFND1_POS_X,0
RNGFND1_POS_Y,0
RNGFND1_POS_Z,0
RNGFND1_PWRRNG,0
RNGFND1_RMETRIC,1
RNGFND1_SCALING,1
RNGFND1_STOP_PIN,-1
RNGFND1_TYPE,16

I have RANGEFINDER_VL53L1X selected

select both rangefinders.

what you have selected is
28 VL53L1X-ShortRange mode, so if you set your rangefinder to type 28 it will probably start working. or add the VL53l0x driver so it works as type 16.

That might explain some things, ill give it a try, thanks

Recompiled with the added options, sadly, the issue is unchanged.

Have you tried both type 16 and 28?