Tag Archives: VL53L0X

Wall-E3 Replacing Mega 2560 With Teensy 3.5 Part V

Posted 15 January 2022,

In my last post on this subject I described my effort to get IR Homing functional on my new Wall-E3 robot. This post is intended to document the process of getting the ‘second deck’ from Wall-E2 ported over to Wall-E3. The second deck from Wall-E2 houses the forward-looking PulsedLight (acquired by Garmin in 2015) LIDAR system, the two side-looking VL53L0X arrays, and a rear-looking VL53L0X, as shown in the photo below

Wall-E2’s ‘second deck’ module

The second deck connects to the main system via the 16-pin Amp connector visible in the bottom left-hand corner of the photo above.

Looking at the code, the only pin assignments associated with ‘second deck’ functionality are:

  • const int RED_LASER_DIODE_PIN = 5;//Laser pointer
  • const int LIDAR_MODE_PIN = 2; //LIDAR MODE pin (continuous mode)
  • const int VL53L0X_TEENSY_RESET_PIN = 4; //pulled low for 1 mSec in Setup()

To start the process, I ported the following sections from From FourWD_WAllE2_V12.ino::setup() to T35_WallE3::setup():

  • The code to reset the VL53L0X Teensy on the second deck
  • The code to initialize the above output pins.
  • The entire #pragma region VL53L0X_TEENSY section
  • The entire #ifdef DISTANCES_ONLY section
  • pragma region L/R/FRONT DISTANCE ARRAYS

That should take care of all new declarations and initializations associated with the second deck. And wonder of wonders, the T35_WallE3_V5 project compiled without errors! – time to quit for the night! 🙂

16 January 2022:

Well, of course when I connected up the second deck – nothing worked, so back to basic troubleshooting. First, I connected a USB cable directly to the T3.5 running the VL53L0X array, and determined that I can, in fact, see valid distance values from all seven sensors – yay! Now to determine why I can’t see them from the main processor.

Next, I loaded a basic I2C scanner program onto the main processor to see if the main processor could see the VL53L0X process on Wire1. The I2C scanner reported it could find the MPU6050 IMU module and the Teensy 3.2 IR homing beacon detection processor, but nothing else. After a few more seconds (and yet another face palm!) I realized that the I2C scanner program wasn’t finding the VL53L0X processor because it was only checking the Wire bus, not Wire1 or Wire2 – oops!

So, I modified the basic scanner so it would optionally check Wire1 & Wire2 in addition to Wire1, as shown below:

And here’s the output with all three I2C busses enabled.

So now that I know that the main processor can ‘see’ the VL53L0X Teensy on Wire1, I have to figure out why it’s not working properly. As usual, this turned out to be pretty simple once I knew what I was looking for. The entire solution was to change this line:

To this line:

Wall-E2 used a Mega 2560 processor with only one I2C bus, so everything had to be on that one bus. However, when I changed to the Teensy 3.5, I had more busses available, so I chose to move the VL53L0X array manager to Wire1, but forgot to change the initialization code to use Wire1 vs Wire – oops!

18 January 2022 Update:

Or,….. Maybe not. When I tried to compile the above changes I started running into ‘#include file hell’. I couldn’t figure out whether to use #include <i2c_t3.h> or #include <Wire.h> and every time I changed the include in one file, it seemed to conflict with an earlier change in another – argggghhhhh!

So, I took my troubles to the Teensy forum and asked what the difference was between the ‘i2c_t3.h’ and ‘Wire’ libraries, particularly with respect to multiple I2C bus support. The answer I got from ‘defragster’ (a very experienced Teensy forum contributor) was:

Wire.h is the base i2c supplied and supported by PJRC. It covers all WIRE#’s on various Teensy models: See {local install}\hardware\teensy\avr\libraries\Wire\WireKinetis.h

i2c_t3.h is an alternative library that can be used to instead of WIRE.h when it works or offers some added feature or alternate method.

I took his post to say “use Wire.h” unless you have some specific reason why the i2c_t3.h library offers a needed feature that Wire.h doesn’t offer.

So, now I have to go back through all the code that I have dicked with over the years to make work (like ‘I2C_Anything’, for instance) with multiple I2C buses, and see what needs to be done to, as much as possible, use ‘Wire.h’ in lieu of ‘i2c_t3.h’

The main file for this project has the following #include’s that may require work:

MPU6050_6Axis_MotionApps_V6_12.h: Right away I run into problems; the first thing this file does is #include “I2Cdev.h”, which has the following code:

Which I modified sometime in the distant past to use #include <i2c_t3.h> instead of #include <Wire.h>. At the time I think I was convinced that I had to use i2c_t3.h to get access to multiple I2C buses, but now I know that isn’t necessary. Fortunately this is a ‘local’ file, so changing this back shouldn’t (fingers crossed!) break other programs.

Aside: I did a search on MPU6050_6Axis_MotionApps_V6_12.h and I2Cdev.h in the Arduino folder, and got 48 different hits for MPU6050_6Axis_MotionApps_V6_12.h and 108 hits for ‘I2Cdev.h – ouch!! Not going to worry about this now, but I’m sure I’ll be dealing with this problem forever – if not longer 🙁

Aside2: The ‘I2Cdev.h’ file gets specialized to different hardware in I2CDevLib. For ‘Arduino’ hardware it is this file:

Where it can be seen that sometime in the distant past, I modified the original library file to select ‘I2CDEV_TEENSY_3X_WIRE’, which has the effect of #include <i2c_t3.h> instead of #include <Wire.h> – oops! So, any project that uses the library version of this file will always #include <i2c_t3.h> instead of #include <Wire.h> – double, triple, and quadruple oops! In addition, I discovered that the version of i2cdev.h I am using for this project is at least 6 years out of date – wonderful (at least it looks like the MPU6050_6Axis_MotionApps_V6_12.h is reasonably current (in fact, it is essentially identical to the library version).

To start with, I made sure T35_WallE3_V5 compiles for T3.5 ‘as is’, and then modified the includes to use the library version of MPU6050_6Axis_MotionApps_V6_12.h. This actually worked (yay!), although I discovered I had to use the “file.h” format rather than <file.h> – don’t know why.

23 January 2022 Update:

As usual, there were a few detours on the way to full ‘second-deck’ functionality. To start with, I discovered/realized that I was using the wrong I2C library (i2c_t3.h) for working with multiple I2C busses. The i2c_t3.h library does a lot of nice things, including multiple I2C bus support, but unfortunately isn’t compatible with a lot of the hardware driver libraries I use, most of which assume you are using the ‘Wire.h’ library. I had ‘sort-of’ solved this problem with many of my Teensy projects by hacking the needed hardware driver libraries to use i2c_t3.h instead of Wire.h, but this got old pretty quickly, and even older when I started trying to use multiple I2C bus enabled hardware driver libraries (like Kurt E’s wonderful multiple bus MPU6050 driver).

So, I wound up spending way too many hours tracking down the differences and similarities between i2c_t3.h and the Teensy version of Wire.h See this post for all the gory details. Along the way I learned how to simplify access to deeply buried library files using the Windows 10 flavor of symlinks, which was kinda cool, but I could probably have spent the time more wisely elsewhere. Also, I ran headlong into yet another multiple bus problem with one of my favorite libraries – Nick Gammon’s wonderful ‘I2C_Anything’ library that does just two things – it reads/rights ‘anything’ – ints, floats, unsigned long ints, doubles, whatever – across an I2C connection – no more worrying about how to do that, or being forced to transmit ASCII across the bus and construct/deconstruct as necessary on both ends. Unfortunately, this library is unabashedly single-bus – it expects to be used in a Wire.h environment and that is that. The good news is, by the time I was done the question of ‘why use i2c_t3.h as opposed to Wire.h?’, I was able to intelligently (I hope) modify I2C_Anything.h to accommodate multiple I2C busses (though it still assuming a ‘Wire.h’ environment). At the end, I made a pull request to the I2C_Anything github repo, so maybe others can use this as well.

After all this was done, I still hadn’t even started on getting the second-deck VL53L0X sensors talking to the main Teensy 3.5 processor, but at least now I (kinda) knew what I was doing.

Anyhoo, once I got back to trying to get connected to the VL53L0X array, I was able to reasonably quickly revise both the main Teensy 3.5 processor program and the VL53L0X array management program to use Wire.h vs i2c_t3.h, and to instantiate/initialize the multiple busses required for both processors (the main processor talks to the VL53L0X array manager via Wire1 on its end to Wire0 on the array end, and the array manager talks to the seven VL53L0X modules via its Wire1 & Wire2 busses). And with my newly modified I2C_Anything library, I was ready to get them talking to each other.

Here’s the working Array manager code (pardon the extra comment lines):

And here’s the working main processor code. Note that the code as it is presented here has the ‘DISTANCES_ONLY’ define enabled, and all non-existent hardware modules ‘#defined’ out so I could concentrate on just the VL53L0X array connection.

And here is the ‘multiple I2C bus’ version of I2C_Anything.h, just in case you come across this post before Nick updates the Github repo (assuming he likes what I have done):

Here’s the the test setup:

Main Teensy 3.5 processor on plugboard, connected via I2C to the Teensy 3.5 VL53L0X array manager

Another try at Wall Offset Tracking

Posted 11 September 2021

I’m making another try at getting wall offset capture and tracking right, after several failed attempts. This time I’m starting with a small ‘FourWD_WallTrackTest_V3’ project in VS2019. I think I actually got this working before, but an unfortunate laptop backup catastrophe cost me a couple of months of work, and it has taken me this long to recover. Here’s the current program:

With this code, I ran a test using PID values of 300,0,0 and an offset target of 40cm. The following short video and Excel plot show the results

Now all I have to do is make this same trick work for both the ‘inside offset’ and ‘outside offset’ starting conditions, and then for both the left-side and right-side tracking conditions, then I can integrate the code back into the main robot operating system.

18 September 2021 Update:

After getting the left-side tracking working reasonably well, I started working on right-side tracking, and discovered that what worked for the left side with no problems did not work particularly well for right-side tracking. After the usual number of programming mistakes I did get right-side tracking working, albeit with a significantly different PID parameter set. For left-side tracking, PID = (300,0,0) seemed to work OK, but for right-side tracking I wound up with PID = (300,0,300). Moreover, when I tried even very small (like 10) values for the I parameter, the robot lost track after just two or three oscillations. So, for the moment it looks like (300,0,0) for the left side, and (300,0,300) for the right side. Here’s a short video showing successful right-side tracking.

And here is the ‘finished’ FourWD_WallTrackTest_V3 code:

Stay tuned

Frank

Another Try at Wall Offset Tracking, Part II

Posted 22 June 2021

In my previous post on this subject, I described my effort to improve Wall-E2’s wall tracking performance by leveraging controlled-rate turns and the dual VL53L0X ToF LIDAR arrays. This post describes an enhancement to that effort, aimed at allowing the robot to start from a non-parallel orientation and still capture and track a desired wall offset.

The previous post showed that when starting from a parallel orientation either inside or outside the desired wall offset, the robot would make a turn toward the offset line, move straight ahead until achieving the desired offset, then turn down-track and start tracking the desired offset. The parallel starting condition was chosen to make things easier, but of course that isn’t realistic – the starting orientation may or may not be known. In previous work I created an entire function ‘RotateToParallelOrientation()’ to handle this situation, but I would rather not have to do that. It occurred to me that I might be able to eliminate this function entirely by utilizing the known characteristics of the triple-VL53L0X array. The linear array exhibits a definite relationship between ‘steering value’, (the difference between the front and rear sensor values, divided by 100) and the off-perpendicular orientation of the array. At perpendicular (parallel orientation of the robot), this value is nominally zero, and exhibits a reasonably linear relationship out to about +/- 40º from perpendicular, as shown in the following plot from this post from a year ago.

Array distances and steering value for 30 cm offset. Note steering value zero is very close to parallel orientation

As can be seen above, the ‘Steering’ value is reasonably linear, with a slope of about -0.0625/deg. So, for instance, the calculated value for an offset of 30cm would be -0.0625*30 = -0.1875, which is very close to the actual plotted value above for 30º

So, it should be possible to calculate the off-perpendicular angle of the robot, just from the measured steering value, and from that knowledge calculate the amount of rotation needed to achieve the desired offset line approach angle.

The desired approach angle was set more or less arbitrarily by

and this assumes an initial parallel orientation (i.e. 0º offset in the above plot). If, for instance, the initial steering value was -0.1875, indicating that the robot was pointing 30º away from parallel, then the code to compute the total cut (assuming we are tracking the wall on the left side of the robot) would look something like this:

So, for example, if the robot’s starting orientation was offset 30º away from the wall, and 20cm inside the desired offset line of 30cm, we would have:

cutAngleDeg = WALL_OFFSET_TGTDIST_CM – (int)(Lidar_LeftCenter / 10.f);

cutAngleDeg = 30 – 10 = 20

adjCutAngleDeg = cutAngleDeg – 30 = -10º, so the robot would actually turn 10º CCW (back toward the wall) before starting to move to capture the desired offset line.

If, on the other hand, the robot was starting from outside the desired offset (say at 60cm), but with the same (away from wall) pointing angle, then the result would be

cutAngleDeg = WALL_OFFSET_TGTDIST_CM – (int)(Lidar_LeftCenter / 10.f);

cutAngleDeg = 30 – 60 = -30

adjCutAngleDeg = cutAngleDeg – 30 = -30 – 30 = -60º, so the robot would actually turn 60º CCW (back toward the wall) before starting to move to capture the desired offset line.

26 June 2021 Update:

I modified my test program to just report the rear, center, and front VL53L0X distances, plus the steering value and the computed off-parallel angle, using the -0.0625 slope value obtained from the above plots. Unfortunately, the results were wildly unrealistic, leading me to believe something was badly wrong somewhere along the line. So, I redid the plots, thinking maybe the left side VL53L0X sensors were different enough to make that much of a difference. When I plotted the steering value vs off-parallel angle for 10, 20, 30 & 40cm wall offsets, I got a significantly different plot, as shown below:

As can be seen in the above plot, the slope of steering values to off-parallel angles is nice and linear, and also quite constant over the range of wall offset distances from 10 to 40 cm; this is quite a bit different than the behavior of the right-side sensor array, but it is what it is. In any case, it appears that the slope is close to 1.4/80 = 0.0175, or almost twice the right-side slope derived from the previous right-side plots.

Using the value of 0.0175 in my GetSteeringAngle() function results, and comparing the calculated off-parallel angle with the actual measured angle, I get the following Excel plot.

As can be seen in the above plot, the agreement between measured and calculated off-parallel angles is quite good, using the average slope value of 0.0175.

The above plot shows the raw values that produced the first plot.

So, back to my ‘FourWD_WallTrackTest’ program to develop Wall-E2’s ability to capture and then track a particular desired offset. In my first iteration, I always started with Wall-E2 parallel to the wall, and calculated an intercept angle based on the difference between the robot’s actual and desired offsets from the near wall. This worked very nicely, but didn’t address what happens if the robot doesn’t start in a parallel orientation. However, when I tried to use the data from a previous post, the results were wildly off. Now it is time to try this trick again, using the above data instead. Because the measured steering value/off angle slopes for all selected wall offsets were essentially identical, I can eliminate the intermediate step of calculating the appropriate slope value based on the current wall offset distance.

So, I modified my ‘getSteeringAngle()’ function to drop the ‘ctr_dist_mm’ parameter and to use a constant 0.0175 slope value, as shown below:

With this modification, I was able to get pretty decent results; Wall-E2 successfully captured and tracked the desired offsets from three different ‘inside’ (robot closer to wall than the desired offset) orientations, as shown in the following short videos:

‘Inside’ capture, with initial orientation angle > desired approach angle
‘Inside’ capture with initial orientation angle < desired approach angle
‘Inside’ capture with negative initial orientation angle

04 July 2021 Update:

After succeeding with the ‘inside’ cases, I started working on the ‘outside’ ones. This turned out to be considerably more difficult, as the larger distances from the wall caused considerable variation in the VL53L0X measurements (lower SNR?), which in turn produced more variation in the starting and ‘cut’ angles. However, the result does seem to be reasonably reliable, as shown in the following videos.

‘outside’ capture with initial outward angle
‘outside’ capture with initial inward angle
‘outside’ capture with small outward angle.

05 July Update:

After getting the left-side tracking algorithm working reasonably well, I ported the ‘TrackLeftWallOffset()’ functionality to ‘TrackRightWallOffset()’. After making (and mostly correcting) the usual number of mistakes, I got it going reasonably well, as shown in the following short videos:

Right wall tracking, starting inside desired offset, oriented toward wall
Right wall tracking, starting inside desired offset, oriented away from wall
Right wall tracking, starting outside desired offset, oriented toward wall
Right wall tracking, starting outside desired offset, oriented away from wall

Here is the complete code for my wall capture/track test program:

Here is a link to the above file, plus all required library & ancillary files.

Stay tuned,

Frank

Another Try at Wall Offset Tracking

Posted 22 June 2021

About nine months ago (October 2020) I made a run at getting offset tracking to work (see here and here). This post describes yet another attempt at getting this right, taking advantage of recent work on controlled-rate turns. I constructed a short single-task program to do just the wall tracking task, hopefully simplifying things to the point where I can understand what is happening.

One of the big issues that arose in previous work was the inability to synch my TIMER5 ISR with the PID library’s ‘Compute()’ function. The PID library insists on managing the update timing internally, which meant there was no way to ensure that Compute() would be called every time the ISR ran. I eventually came to the conclusion that I simply could not use the PID library version, and instead wrote my own small function that did the Compute() function, but with the timing value passed in as an argument rather than being managed internally. This forces the PID calculations to actually update in synch with the TIMER5 interrupt. Here’s the new PIDCalcs() function:

As can be seen from the above, this is a very simple routine that just does one thing, and doesn’t incorporate any of the improvements (windup suppression, sample time changes, etc) available in the PID library. The calling function has to manage the persistent parameters, but that’s a small price to pay for clarity and the assurance that the output value will indeed be updated every time the function is called.

With this function in hand, I worked on getting the robot to reliably track a specified offset, but was initially stymied because while I could get it to control the motors so that the robot stayed parallel to the nearest wall, I still couldn’t get it to track a specific offset. I solved this problem by leveraging my new-found ability to make accurate, rate-controlled turns; the robot first turns by an amount proportional to it’s distance from the desired offset, moves straight ahead until the offset is met, and then turns the same number of degrees in the other direction. Assuming the robot started parallel to the wall, this results in it facing the direction of travel, at the desired offset and parallel to the nearest wall. Here is the code for this algorithm.

Here are a couple of videos showing the ability to capture and track a desired offset from either side.

In both of the above videos, the desired wall offset is 30 cm.

Stay Tuned,

Frank

Turn Rate PID Tuning, Part II

Posted 14 May 2021,

In my previous post on this topic, I described my efforts to use the Arduino PID library to manage turns with Wall-E2, my autonomous wall following robot. This post talks about a problem I encountered with the PID library when used in a system that uses an external timing source, like the TIMER5 ISR in my system and a PID input that depends on accurate timing, such as my turn-rate input.

In my autonomous wall-following robot project, I use TIMER5 on the Arduino Mega 2560 to generate an interrupt ever 100 mSec, and update all time-sensitive parameters in the ISR. These include results from all seven VL53L0X ToF distance sensors, the front-mounted LIDAR, and heading information from a MP6050 IMU. This simplifies the software immensely, as now the latest information is available throughout the code, and encapsulates all sensor-related calls to a single routine.

In my initial efforts at turn-rate tuning using the Arduino PID library, I computed the turn rate in the ISR by simply using

This actually worked because, the ISR frequency and the PID::Compute() frequency were more or less the same. However, since the two time intervals are independent of each other there could be a phase shift, which might drift slowly over time. Also, if either timer interval is changed sometime down the road, the system behavior could change dramatically. I thought I had figured out how to handle this issue by moving the turn-rate computation inside the PID::Compute() function block, as shown below

In a typical PID use case, you see code like the following:

After making the above change, I started getting really weird behavior, and all my efforts at PID tuning failed miserably. After a LOT of troubleshooting and head-scratching, I finally figured out what was happening. In the above code configuration, the PID generates a new output value BEFORE the new turn rate is computed, so the PID is always operating on information that is at least 100mSec old – not a good way to run a railroad!

Some of the PID documentation I researched said (or at least implied) that by setting the PID’s sample time to zero using PID::SetSampleTime(0), that Compute() would actually produce a new output value every time it was called. This meant that I could do something like the following:

Great idea, but it didn’t work! After some more troubleshooting and head-scratching, I finally realized that the PID::SetSampleTime() function specifically disallows a value of zero, as it would cause the ‘D’ term to go to infinity – oops! Here’s the relevant code

As can be seen from the above, an argument of zero is simply ignored, and the sample time remains unchanged. When I pointed this out to the developer, he said this was by design, as the ‘ratio’ calculation above would be undefined for an input argument of zero. This is certainly a valid point, but makes it impossible to synch the PID to an external master clock – bummer!

After some more thought, I modified my copy of PID.cpp as follows:

By moving the SampleTime = (unsigned long)NewSampleTime; line out of the ‘if’ block, I can now set the sample time to zero without causing problems with the value of ‘ratio’. Now PID::Compute() will generate a new output value every time it is called, which synchs the PID engine with the program’s master timing source – yay!

I tried out a slightly modified version of this technique on my small 2-wheel robot. The two-wheeler uses an Arduino Uno instead of a Mega, so I didn’t use a TIMER interrupt. Instead I used the ‘elapsedMillisecond’ library and set up an elapsed time of 100 mSec, and also modified the program to turn indefinitely at the desired turn rate in deg/sec.

I experimented with two different methods for controlling the turn rate – a ‘PWM’ method where the wheel motors are pulsed at full speed for a variable pulse width, and a ‘direct’ method where the wheel motor speeds are varied directly to achieve the desired turn rate. I thought the PWM method might work better on a heavier robot for smaller angle turns as there is quite a bit of inertia to overcome, but the ‘direct’ method might be more accurate.

Here’s the code for the ‘direct’ method, where the wheel speeds are varied with

Here’s the code for the PWM method: the only difference is that is the duration of the pulse that is varied, not the wheel speed.

Here’s a short video showing the two-wheel robot doing a spin turn using the PWM technique with a desired turn rate of 90 deg/sec, using PID = (1,0.5,0).

The average turn rate for the entire run was about 85 deg/sec.

Here’s another run, this time on carpet:

Average turn rate for the entire run was about 85 deg/sec

Here’s some data from the ‘direct’ method, on hard flooring

Average turn rate was ~ 85 deg/sec

And on carpet

Average turn rate ~83 deg/sec

So, it appears that either the PWM or ‘direct’ methods are effective in controlling the turn rate, and I don’t really see any huge difference between them. I guess the PWM method might be a little more effective with the 4-wheel robot caused by the wheels having to slide sideways while turning.

Stay Tuned!

Frank

Wall Parallel Find PID Tuning

Posted 10 April 2021

In addition to using PID for homing to its charging station and for turn rate control, Wall-E2 also uses PID for finding the parallel orientation to a nearby wall. After successfully tuning the turn rate and IR Homing PID controllers using the Ziegler-Nichols method for PID tuning, I decided to see what I could do with the PID controller for parallel orientation finding

Wall-E2 uses two 3-element VL53L0X Time-of-Flight distance sensors for parallel orientation finding. The idea is that when all three sensors report the same distance, then the robot must be oriented parallel to the wall. The Teensy 3.5 Array Controller MCU calculates a ‘steering value’ using the expression (shown for the left side array):

This value is fed to the PID engine, which drives the motors to zero it out – thus arriving at a parallel orientation. Originally I just basically ‘winged it’ in choosing PID Kp, Ki & Kd values, arriving emperically at Kp = 200, Ki = 50, Kd = 0. However, after going through the K-N process with Wall-E2’s other two PID control setups, I decided to try it with this one as well.

The first step is to determine Kc, the Kp value for which the system oscillates in a reasonably stable fashion. To accomplish this I started with Kp = 20 and worked my way up in stages, plotting the ‘steering value’ each time. The last three trials (as shown in the following plots) were for Kp = 400, Kp = 500 and Kp = 600:

Looking at the above plots, it looks like Kp = 600 will work for Kc. Using the K-N formula, we get

Using the above values for the Parallel Find PID, we get the following plot:

Which is not exactly what I thought it would be – it looks like my guess for Kc must be off. Trying again with a Kc = 400 –> PID = 200,180,240, we get:

which, to my eye at least, seems a bit better.

To test how this worked with ‘real’ parallel finding, I incorporated these parameter values into my ‘RotateToParallelOrientation()’ routine and ran a couple of tests. Here’s one where Wall-E2 starts in the ‘toed-out’ position:

And here’s the Excel plot from this same run

As can be seen, the robot takes less than two seconds to converge on a pretty decent parallel orientation, starting from a 30-40º angle to the near wall.

Here’s another run where the robot starts in the ‘toed-in’ orientation.

And here’s the Excel plot for the run

Again, the robot gets to a pretty decent parallel orientation within 2 seconds of the start of the run. The only concern I have with this run is that it winds up pretty close to the wall.

Wall-E2 Gets a VL53L0X Array Upgrade

Posted 13 March 2021

Back in May of last year I started the process of replacing the ultrasonic distance sensors on Wall-E2, my autonomous wall-following robot, with two side-looking arrays of STMicroelectronics’ VL53L0X infrared laser ‘Time-of-Flight’ distance sensor. Later that same year I upgraded the installation by adding a rear distance sensor as well, as shown in the following photo:

left-hand VL53L0X array and rear sensor shown. Identical 3-elelment array on the other side

All went swimmingly until I started having problems when Wall-E2 connected up to its charger. Wall-E2 connecting to its charger is a pretty dynamic event, as it has to build up enough speed to make sure the charging probe seats into the charging jack properly. I discovered that about every other time Wall-E2 connected, the distance sensors would start reporting ‘-1’ instead of the actual distances. This meant that when Wall-E2 disconnected from charging, it had no idea what to do or which way to turn. This didn’t happen all the time, but often enough to be very worrisome.

After some head-scratching and program instrumentation I became convinced this was a real issue, and I posted on the ST Micro’s forum about the issue. ST Micro’s VL53L0X expert John E. Kvam answered with this post:

The VL53L0X sensor will not return a -1. The user manual does define a -1 error, but it states that this cannot happen. What does return a -1 is an I2C timeout.
And I think that is what is killing you. The I2C is notorious for being basically unreliable. And the major symptom of a dropped bit (the most likely failure), is that the bus is stuck low. (When nothing is being transmitted both the clock and data lines should be high.) Philips designed the I2C bus and NXP bought Philips. So the NXP site has some documentation on how to tweak the bus. I’d read and understand that.
One other possibility is that one or more of the sensors rebooted – perhaps due to power glitch. If this happens the sensor will revert to it’s base I2C address.
If you’ve changed all your addresses there should be nothing at address 0x29 (0x52/0x53). You could occasionally ping the base address – and if you ever got an answer, you would would know you had a reboot of some kind.

After thinking about this some more, I realized that there is a good chance that the I2C ‘daisy-chain’ wiring and/or the power/ground connections are getting interrupted due to the impulse generated when Wall-E2 hits the charging station stop, and this is causing one or more of the sensors to drop out. I thought I had done a very careful job with the I2C/power ‘daisy-chain’, but I had thought that about a previous effort where I found a faulty ground connection, so I knew it was a possibility.

After thinking about this some more, it occurred to me that I could eliminate most of the point-point wiring issues by creating a PCB to house the VL53L0X modules, with a single 4-pin connector for I2C and power. I had made a PCB some years before using DipTrace that had turned out petty well, so making one for the very simple VL53L0X wiring scheme should be a piece of cake.

Well, as it turned out, designing the PCB was the easy part. However, when it came to the part about having the boards actually manufactured, I was in for a bit of a shock. For my previous board I used DipTrace’s ‘baked-in’ manufacturer Bay Area Circuits to purchase 5 boards for around $30, but when I tried this same trick with my new board, the minimum charge for boards from BAC was $150 – ouch!

After a lot of web searching and research, I eventually found the Chinese company JLCPCB and discovered they have a very nice document that shows how to export the required files from DipTrace and upload them to their site. Took me about 30 minutes to go through the process the first time, and now I have my 5ea boards ordered for a grand total of about $15USD. Only a 10:1 ratio from BAC to JLCPCB. I can’t imagine how BAC can stay in business, and I can’t imagine why DipTrace has that company ‘baked in’ and not JLCPCB. DipTrace must be getting a heck of a kickback from BAC!

Less than 10 days later, I had the finished PCBs in my hand – wow! Here’s a photo showing two PCB’s installed on Wall-E2. I installed 4-pin headers on both ends of the near PCB in order to daisy-chain the I2C and power connections to the rear distance sensor (hidden behind the red ‘rear bumper’ block in the right background).

New VL53L0X array PCB to replace all the hand-wired I2C/Power connections.

Comparing the ‘before’ and ‘after’ photos, it is easy to see that the PCB installation eliminates two 4-pin connectors and a three-loop daisy chain on one side of the robot, and two 4-pin connectors and a four-loop daisy chain on the other side (the one that also connects to the rear distance sensor. Moreover, now none of the 3 connectors used for all seven sensors has more than one wire per pin.

Hopefully this upgrade will eliminate (or at least significantly suppress) wiring and/or connector issues associated with the charger-connect ‘impulse’ – we’ll see

25 March 2021 Update:

After getting the new PCBs installed and some other connection issues solved, Wall-E2’s sensors seem to be a lot more reliable. However, I decided to take this opportunity to study John Kvam’s idea of re-initializing all seven sensors if one of them happens to show up at the default VL53L0X I2C address.

So, I modified the Teensy 3.5 VL53L0X array management code to abstract the sensor init code from setup() to its own function so it can be called if the program detects a sensor at the default I2C address, and then added code in loop() to do just that. Here’s the detection code:

and here’s the new ‘InitAllSensors()’ routine:

And here is the complete Teensy program for managing the VL53L0X arrays:

After getting everything set up, I started experimenting. The first thing I tried was momentarily disconnecting one or the other of the two I2C bus connections at the Teensy end. This was interesting in that the affected sensor array results became invalid as soon as the I2C connection was pulled, but resumed valid output as soon as the connection was restored – nice!

Next, I tried momentarily disconnecting the +V line to the arrays. All sensor outputs immediately became invalid, and stayed invalid after +V was restored. In addition, the code in loop() designed to detect one or more VL53L0X sensors at the default address immediately triggered – nice – but the re-initialization code failed to restore valid output.

Here’s the output from a run were the +V line was momentarily disconnected and then reconnected:

28 March 2021 Update:

I have been continuing to work on the ‘re-initialize after power interruption’ idea for my VL53L0X sensor array, and while I haven’t come up with a very good solution, I have learned some things:

  • The VL53L0X reverts to it’s default (0x29) I2C address immediately when power is removed, but will actually respond to a 0x29 query even after power has been removed. Apparently, the module can draw enough current from the I2C connections to continue to operate (albeit at the default address).
  • A ‘powered down’ (power disconnected, but I2C leads still connected) will also respond to distance measurement requests, but will return a nonsense number (65535).
  • In order to get a VL53L0X sensor to stop responding, the power lead must be physically grounded – just disconnecting isn’t enough.
  • If I use a digital output to power the array, I can turn the power on and off programmatically. Using this tool:
    • Turning power OFF causes distance measurements to return ‘65535’ (because this is the same as connecting the power lead to GND). However, this isn’t the normal failure mode; the normal failure mode for power disconnections is an open-circuit – not GND
    • Turning power back ON again causes the system to detect that one or more VL53L0X units has appeared at the default I2C address. This probably means I could successfully re-initialize all modules.

So, it looks like I can’t really protect against an arbitrary length power disconnect scenario, as I can’t tell when the power has been restored. All I can do is have the program detect the ‘65535’ distance value, wait for some time (a few seconds?) and then try to re-initialize the sensors. This is, unfortunately, a one-shot deal, as if power hasn’t been restored when the re-init procedure is executed, the initialization code hangs up permanently.

Stay tuned!

Frank

Solving the Teensy VL53L0X Array Controller Reset Problem

Posted 16 November 2020

Back in May of this year, I converted Wall-E2, my autonomous wall-following robot, from using HC-SR04 ultrasonic ‘ping’ sensors to VL53L0X infrared time-of-flight sensors for left & right (and now rear) distance measurement and obstacle detection, as described in this and follow-on posts. Since then, I have been successfully integrating the new sensing capability into Wall-E2’s wall-tracking and obstacle avoidance algorithms, as described in this post among others.

In recent ‘sandbox’ runs, however, I started to notice that the VL53L0X controller (a Teensy 3.5) wasn’t always providing proper distance measurements. Sometimes it would return ‘-1’ for some or all seven measurements. Eventually I figured out that the problem only occurred when I restarted the main controller via the wireless serial connection; when I restarted by cycling the power, VL53L0X measurements were always proper. After looking into this a bit, I realized that the problem occurred because the VL53L0X array controller wasn’t being restarted when the main controller was, except when everything was power cycled.

So, I needed a way to ensure that the VL53L0X array controller got restarted, even with a serial-port reset of the main controller. The Teensy 3.5 actually has a RESET function exposed on a pin pad (although internal to the PCB, not on the periphery) so I added a pin to this pad, and connected it to the wire formerly used as the ‘left ping’ control line. Then I modified the setup code to pull this line LOW for a few 10’s of milliseconds and then back HIGH again, to restart the Teensy.

To test the modification, I modified the main controller code to send a HIGH to an unused digital pin as the first instruction in setup() and set that pin back LOW again as the last instruction. Immediately after setting this pin high, the RESET signal is sent to the Teensy. The Teensy program was modified to set an unused pin HIGH at the start of it’s setup() program, and LOW at the end. By monitoring these two pins with my wondrous Hanmatek DOS1102 DSO (see below) I was able to definitively confirm that the Teensy restarts every time the main controller does – yay!

Yellow trace is main controller setup() timing, blue is Teensy VL53L0X array controller setup() timing

In the above scope photo, the horizontal scale is 1 sec/div. The yellow trace shows the main controller setup() function timing, and the blue is the Teensy VL53L0X array controller setup() function timing. The Teensy gets reset about 500 mSec after the main controller setup() function starts, and it ends about 5.5 Sec later, about 500 mSec before the main controller setup() function ends. The relative timing shown above is the same whether the main controller is restarted via a power switch cycle or a serial port re-open restart.

Stay Tuned,

Frank

Wall Tracking Trials Using Office ‘Sandbox’ Part I

Posted 12 November 2020

Back in October I added a TIMER5 timer interrupt to my autonomous wall-following robot (WAll-E2) code to manage sensor updates. Since then I have made the timer interrupt the sole timing source for all sensor and tracking updates, and upped the update rate from 5Hz to 10Hz. In addition, I’ve been making some improvements to Wall-E2’s obstacle detection/response abilities, and this post describes the results of these enhancements.

Wall-E2’s job is to autonomously track walls forever. This implies the ability not only track walls, but to deal with obstacles as they occur, and recharge its batteries at one or more provided charging stations as needed. Wall-tracking per se has been the subject of several previous posts, and is now reasonably well managed using the ‘find parallel’ technique described here. This post deals with the effort to detect and respond to obstacles as they occur. Here’s a recent run in my office ‘sandbox’

In the above telemetry printout, the first obstacle encounter occurs at 7.65 sec, corresponding to about 4 sec into the video. The obstacle is recognized at 18 cm, well inside the desired offset distance of 30 cm. I believe this occurred because the robot had just started turning back toward the near wall with a target steering value of -WALL_OFFSET_TRACK_SETPOINT_LIMIT (-0.3, the maximum toward-wall steering value) which meant that the normal forward obstacle detection limit of WALL_OFFSET_TGTDIST_CM (30cm in this case) wasn’t in force and the backup limit of MIN_FRONT_OBSTACLE_DIST_CM (20cm in this case) triggered instead. This causes the following code block to execute:

As can be seen in the above code snippet, this causes the robot to make a 90º ‘spin turn’ to the right, and then restart wall tracking.

At about 12.6 sec (about 10 sec into the movie) we see it detect the upcoming wall at about 30 cm (due to a bug in the code, the printed values are incorrect). This causes the following code block to execute:

This code executes a 90º ‘step turn’ (identical to a ‘spin turn’) to the right, and drops back into wall tracking mode.

At about 16 sec into the movie and 20 sec after program start, the robot again detects an upcoming obstacle at about 30cm, and again executes a 90º ‘step turn’ to the right to follow the new wall.

About 1.5 sec later, the robot detects one of the chair legs (I think it was the one nearest the wall in the movie) and tries to get away using another 90º ‘spin turn’, but then exhibits some abnormal behavior. When it attempts to find the parallel orientation to the new (non-existent) wall, it exits RotateToParallelOrientation(Left) with SteeringVal = -79.86, a very strange result. I believe this is because Wall-E2 detected the ‘stuck’ condition while it was attempting to complete the parallel orientation procedure, in this ‘while’ loop

So, it exited abnormally, thus the odd SteeringVal number, and then re-detected it in the main tracking loop because the front distance history array isn’t re-initialized after the first detection. This, apparently, is a ‘feature’, not a bug – who knew! ;-).

After the second ‘stuck’ condition detection, the robot attempts to disengage using the ExecuteStuckRecoveryManeuver(), which, in this case tries to back up and then execute an ‘end-around’ maneuver to get past the chair leg. It finished the backup portion of the maneuver successfully with 23cm remaining rearward, and then executed a 90º ‘spin turn’. Then it went forward 21cm using the front distance sensor (not shown in the video), and halted when I took over manual control.

All in all, this was a very successful ‘sandbox’ run. Lots of good data with clear indications of where things are working well and where things need to be modified/fixed.

  • A bug in the telemetry display code for the ‘Wall Offset Limit’ detection printout (fixed).
  • In the situation at 7.65 sec where the obstacle detection occurred at 18cm vs 30cm, the robot should recognize that it needs to back up to the wall offset target before making the spin turn (done).
  • And, of course, porting all this new stuff to the right-side tracking sections

16 November 2020 Update:

Tonight I got the first cut done at porting the TRACKNG_LEFT algorithms over to the TRACKING_RIGHT case, and made what appears to be a successful right-side sandbox run, as shown in the following short video

And here is the telemetry from the run:

Here’s an Excel plot of the Right side center distance and L/R motor speeds vs time.

Comparing the times from the video and the telemetry, it appears the video time is about 3-3.5 sec lower than the telemetry values. In the video, Wall-E2 detects the first upcoming wall at about 9 sec, and this corresponds with the telemetry at 12.358 where the wall is detected with front distance of 19cm. The reason the wall didn’t get detected earlier is the robot was currently tracking back toward the wall with a steering value of -0.3, and this causes the wall detection value to be reduced to suppress false positives.

The robot then takes 2 sec to back up to 33 cm and turn 90 deg CCW, and then it starts tracking the right-side wall again. It detects the next wall at 17.1 sec (14 sec in video) and 30 cm (the steering value at that point was 0.10, so no reduction in upcoming obstacle detection distance). Because the detection occurred at 30 cm, the robot doesn’t need to back up; it just makes another 90 deg spin turn CCW and starts tracking the right-side wall again. The last segment clearly shows that Wall-E2 is capable of tracking to and capturing the desired offset of 30 cm.

All in all, a very successful right-side sandbox run.

Stay tuned!

Frank

Adding a VL53L0X Rear Distance Sensor to Wall-E2

posted 24 October 2020

After documenting left-side wall-tracking success with Wall-E2, my autonomous wall-tracking robot (see this post and this post), I started thinking about improving Wall-E2’s obstacle avoidance performance.

Wall-E2 can encounter several distinct obstacle situations during wall tracking operations. In the simplest case, Wall-E2 approaches an upcoming corner while tracking a wall, and needs to know how to transition from tracking the current wall to tracking the upcoming wall. A more difficult situation arises when Wall-E2 is ‘stuck’ – prevented from moving forward by an obstacle that isn’t detected by its front LIDAR distance sensor; a shoe, or the curved foot of a coat rack. A third situation arises when Wall-E2 encounters an obstacle that just wasn’t there a second ago; a cat or a human foot or a bag of groceries.

In the simple wall-to-wall transition case, all Wall-E2 has to do is make a right-angle turn away from the current wall and start following the next wall; this was successfully demonstrated several times in the previous posts. This maneuver utilizes a ‘spin-turn’ technique intended to minimize the backward movement of the robot while turning. This is done to prevent Wall-E2 from backing into the currently-tracked wall while attempting to turn toward and track the upcoming wall. Unfortunately, this maneuver is not always successful, whereupon Wall-E2 tries to climb backwards up the current wall, often with disastrous results.

In the ‘stuck’ case, Wall-E2 has to first recognize that it is no longer moving forward (or in any other direction for that matter), and then figure out what to do about it. Detection is accomplished by looking at the variance of front distance measurements over time; the ‘stuck’ condition is declared when the front-distance variance falls below a pre-determined value. A typical ‘stuck’ recovery maneuver is to back up slightly, and then make a right-angle turn away from the wall currently being tracked. This maneuver, while usually successful, has the same problem as the simple wall-to-wall transition; it sometimes results in the same backward-up-the-wall climb, with similar results.

The ‘suddenly appearing obstacle’ case can be handled in a manner similar to ‘stuck’ detection, but bypassing the variance measurement stage. and the resulting avoidance maneuver is similar to the ‘stuck’ case

Wall-E2 currently handles all of the above cases fairly well, except when it backs into something while maneuvering to avoid the detected obstacle. So, my challenge was to find a way to avoid running into something while backup up from something else. The easy answer to this problem was to add a rear-distance sensor to Wall-E2, and then use that information to modify obstacle-avoidance behavior as necessary.

During the changeover from ‘ping’ style distance sensors to left and right 3-element arrays of VL53L0X time-of-flight sensors I learned quite a bit about the care and feeding of the VL53L0X, and also wound up with quite a few spares. So, I took one of the spares and installed it on the rear ‘bumper’ plate on Wall-E2, as shown in the following photo:

GY-530 VL53L0X mounted on rear ‘bumper’

Since the 2nd-deck Teensy 3.5 was already handling both 3-element VL53L0X arrays, I simply added the rear sensor to the left-hand array ‘Wire2’ daisy-chain, and connected its XSHUT pin to Teensy pin 8. Then I modified the Teensy’s program to initialize and poll the rear sensor in the same manner as all the others, and tested it to make sure it was responding properly to rear-aspect obstacles.

The next step is to incorporate rear-aspect distance information into the various obstacle avoidance algorithms in the main program.

‘Stuck’ case:

The ‘stuck’ case by definition occurs when the mathematical variance of the last 3-5 seconds of forward distance measurements fall below a set value, indicating that the robot is no longer moving forward or backward. When this happens while wall tracking, the robot has to decide what to do. The current response is to back up for 1 second at half speed, execute a 90 deg ‘spin turn’ away from the nearest wall and then go back to normal operations.

I think I would like to enhance this algorithm as follows:

  • If the measured front distance is less than MAX_FRONT_DISTANCE_CM (currently set at 400 cm) by at least STUCK_BACKUP_DISTANCE_CM (currently set at 25), then back up by STUCK_BACKUP_DISTANCE_CM using front distance measurements as the primary means of terminating the backup maneuver. If the front distance measurement cannot be used, but the rear distance measurement is valid (less than MAX_REAR_DISTANCE_CM, currently set at 100), then back up using the rear sensor measurement. If neither measurement is available, then revert back to a 1 second half-speed movement. In all cases, use the rear distance measurement to prevent ‘reverse wall climb’ by stopping the motors if the robot gets too close to an obstacle while backing up.
  • Execute a ‘spin turn’ away from the nearest wall – this is the same as the current algorithm.
  • Execute a ‘rolling turn’ back toward the original direction of travel. This should offset the robot further away from the nearest wall, and hopefully allow it to bypass the obstacle.