Issues with QTRX reading a white line

Hello. I have been using the Polulu QTRX-13MD RC(digital) sensor for a line follower robot.

It works fine when using readLineBlack() on a black line on white background.

I am facing issues when I use readLineWhite() on a white line on black background. The sensors under the white line display a low reading upon printing the sensor values(which is expected since value = 1000-value is done during readLineWhite), and the sensors under the black blackground show higher values. But the line position stays between 5000 - 6000 and does not seem to change.

This problem is only occurring on the white line when I use readLineWhite. Everything from calibration to individal sensor readings are okay, I’m not sure why I don’t receive a clear 0-12000 line position reading.

I am using the latest version of the QTRSensor libraries.

Just to confirm, it sounds like you have already verified that each individual sensor behaving as expected after calibrating the sensors. Is that correct?

Could you post your program (the simplest complete program that demonstrates the problem and prints each individual sensor’s readings), and an example output if you position the array with the left-most sensor over the line? Some pictures of your physical setup could be helpful too.

- Patrick

#include <QTRSensors.h>

// This example is designed for use with eight RC QTR sensors. These
// reflectance sensors should be connected to digital pins 3 to 10. The
// sensors' emitter control pin (CTRL or LEDON) can optionally be connected to
// digital pin 2, or you can leave it disconnected and remove the call to
// setEmitterPin().
//
// The setup phase of this example calibrates the sensors for ten seconds and
// turns on the Arduino's LED (usually on pin 13) while calibration is going
// on. During this phase, you should expose each reflectance sensor to the
// lightest and darkest readings they will encounter. For example, if you are
// making a line follower, you should slide the sensors across the line during
// the calibration phase so that each sensor can get a reading of how dark the
// line is and how light the ground is.  Improper calibration will result in
// poor readings.
//
// The main loop of the example reads the calibrated sensor values and uses
// them to estimate the position of a line. You can test this by taping a piece
// of 3/4" black electrical tape to a piece of white paper and sliding the
// sensor across it. It prints the sensor values to the serial monitor as
// numbers from 0 (maximum reflectance) to 1000 (minimum reflectance) followed
// by the estimated location of the line as a number from 0 to 5000. 1000 means
// the line is directly under sensor 1, 2000 means directly under sensor 2,
// etc. 0 means the line is directly under sensor 0 or was last seen by sensor
// 0 before being lost. 5000 means the line is directly under sensor 5 or was
// last seen by sensor 5 before being lost.

QTRSensors qtr;
const uint8_t SensorCount = 13;
uint16_t sensorValues[SensorCount];

void setup()
{
  // configure the sensors
  qtr.setTypeRC();
  qtr.setSensorPins((const uint8_t[]){PB12, PB13, PB14, PB15, PB8, PB9, PB0, PA2, PA1, PA15, PB3, PB4, PB5}, SensorCount);
  
  delay(500);
  pinMode(LED_BUILTIN, OUTPUT);
  digitalWrite(LED_BUILTIN, HIGH); // turn on Arduino's LED to indicate we are in calibration mode

  // 2.5 ms RC read timeout (default) * 10 reads per calibrate() call
  // = ~25 ms per calibrate() call.
  // Call calibrate() 400 times to make calibration take about 10 seconds.
  for (uint16_t i = 0; i < 400; i++)
  {
    qtr.calibrate();
  }
  digitalWrite(LED_BUILTIN, LOW); // turn off Arduino's LED to indicate we are through with calibration

  // print the calibration minimum values measured when emitters were on
  Serial.begin(9600);
  for (uint8_t i = 0; i < SensorCount; i++)
  {
    Serial.print(qtr.calibrationOn.minimum[i]);
    Serial.print(' ');
  }
  Serial.println();

  // print the calibration maximum values measured when emitters were on
  for (uint8_t i = 0; i < SensorCount; i++)
  {
    Serial.print(qtr.calibrationOn.maximum[i]);
    Serial.print(' ');
  }
  Serial.println();
  Serial.println();
  delay(1000);
}

void loop()
{
  // read calibrated sensor values and obtain a measure of the line position
  // from 0 to 5000 (for a white line, use readLineWhite() instead)
  uint16_t position = qtr.readLineWhite(sensorValues);

  // print the sensor values as numbers from 0 to 1000, where 0 means maximum
  // reflectance and 1000 means minimum reflectance, followed by the line
  // position
  for (uint8_t i = 0; i < SensorCount; i++)
  {
    Serial.print(sensorValues[i]);
    Serial.print('\t');
  }
  Serial.println(position);

  delay(250);
}

This is my code. I have uploaded my setup and the reading I am getting. As you can see the sensors are working properly. The leftmost sensor(sensor 13) is seeing lower values, around 17. The rest see higher values of black.


I tried decreasing number of sensors, I tried with the QTRX-13HD-RC version on an Arduino Mega, on a Uno, on a STM32 with Arduino core, on an esp32. readLineWhite() is never working with any of the two sensors that I purchased.

It is a weighted average so having a bunch of black on the lower 12 sensors will outweigh the really strong white signal on the single edge sensor.

That said when I plug the last line of your output into a spreadsheet and perform the same weighted average I see in the code, I get a position of 6577 instead of 4723. If I instead run the readLineBlack algorithm in my spreadsheet, I get a closer value of 4753. Edit: Actually I do get 4723 too if I ignore the last element which is below a value of 50, the noise threshold. It seems like invertReadings parameter isn’t being set to true in your call to QTRSensors::readLinePrivate() somehow. Maybe re-download the code from GitHub - pololu/qtr-sensors-arduino: Arduino library for the Pololu QTR reflectance sensors and make sure that you don’t have an old or otherwise modified version?

I redownloaded the QTRSensor 4.0 library twice. There is still the same issue present. The reading I get is 4500-6500 no matter how I swipe the sensor. This is a big issue because in readLineBlack() and on a black line I get clean values from 0-12000 and it remembers where it last saw the line which are the features that I need. I Serial printed inside the if(invertReadings) and it does get executed. It does do value = 1000- value

This constant value of 4500-6500 is pretty useless for my PID controlled line follower, with readLineWhite() on a white line.

I honestly think this is an issue with the library at this point. Otherwise two of these sensors and lots of microcontrollers can’t be wrong.

Interesting. If I calculate the position based on the last line of your log then I only get the position you have at the end of that log line if the readLineBlack() algorithm was used. The calculated position should be about 2000 higher if the readLineWhite() algorithm was used.

I guess one interesting test would be to modify your code a bit where it alternates between calling readLineBlack() and readLineWhite() to see if the calculated position seems to change much between the two modes. This might help narrow down where to look in the library code for issues. I have looked at that code up on GitHub a few times and I can’t see what would cause the weird behavior that you are seeing.

#include <QTRSensors.h>

QTRSensors qtr;
const uint8_t SensorCount = 13;
uint16_t sensorValues[SensorCount];
bool useWhite = true;

void setup()
{
  // configure the sensors
  qtr.setTypeRC();
  qtr.setSensorPins((const uint8_t[]){PB12, PB13, PB14, PB15, PB8, PB9, PB0, PA2, PA1, PA15, PB3, PB4, PB5}, SensorCount);
  
  delay(500);
  pinMode(LED_BUILTIN, OUTPUT);
  digitalWrite(LED_BUILTIN, HIGH); // turn on Arduino's LED to indicate we are in calibration mode

  // 2.5 ms RC read timeout (default) * 10 reads per calibrate() call
  // = ~25 ms per calibrate() call.
  // Call calibrate() 400 times to make calibration take about 10 seconds.
  for (uint16_t i = 0; i < 400; i++)
  {
    qtr.calibrate();
  }
  digitalWrite(LED_BUILTIN, LOW); // turn off Arduino's LED to indicate we are through with calibration

  // print the calibration minimum values measured when emitters were on
  Serial.begin(9600);
  for (uint8_t i = 0; i < SensorCount; i++)
  {
    Serial.print(qtr.calibrationOn.minimum[i]);
    Serial.print(' ');
  }
  Serial.println();

  // print the calibration maximum values measured when emitters were on
  for (uint8_t i = 0; i < SensorCount; i++)
  {
    Serial.print(qtr.calibrationOn.maximum[i]);
    Serial.print(' ');
  }
  Serial.println();
  Serial.println();
  delay(1000);
}

void loop()
{
  // read calibrated sensor values and obtain a measure of the line position
  // from 0 to 5000 (for a white line, use readLineWhite() instead)
  uint16_t position;
  if (useWhite)
  {
    position = qtr.readLineWhite(sensorValues);
  }
  else
  {
    position = qtr.readLineBlack(sensorValues);
  }


  // print the sensor values as numbers from 0 to 1000, where 0 means maximum
  // reflectance and 1000 means minimum reflectance, followed by the line
  // position
  if (useWhite)
  {
    Serial.print("White\t");
  }
  else
  {
    Serial.print("Black\t");
  }
  
  for (uint8_t i = 0; i < SensorCount; i++)
  {
    Serial.print(sensorValues[i]);
    Serial.print('\t');
  }
  Serial.println(position);

  delay(250);
  useWhite = !useWhite;
}

do you have a sensor at hand which you are using with readLineWhite() ?

So I tested again. readLineWhite() works when I touch the sensor’s surface to the ground, basically when the tip of the IR sensors directly touch the surface.

I tried increasing the timeout, I tried bring the sensor close(like 1mm from the surface, although both my sensors are the QTRX versions). I tried taking readings with emitter control, and I tried to cover the sensor to prevent noise. I even tested it under no external lights. I tested both the sensors and both give the same result.

I did a quick check with the readLineWhite() function with an QTRX-13HD-RC here using an Arduino Mega, and it seems to at least be calculating position values correctly. For me it is a little tricky to try to generate position values outside of a range from approximately 4500 to 8500, but factors like the quality of my quick setup and surfaces might be at play there.

I double checked the Serial Monitor output you posted and reached a similar conclusion to AdamGreen (though not the exact same values). It sounds like you already tried reinstalling the most recent version of the library, so that leaves double checking that you do not accidentally have some other modified version of the library saved somewhere with the same file names. I am attaching a basic spreadsheet I used to check what the readLineWhite() and readLineBlack() functions should return so that you can look at that yourself too; however, please note that it does not account for how the function in our library, readLinePrivate(), will behave if the line is not detected.

qtr_readLineWhite_readLineBlack_check_spreadsheet.ods (16.4 KB)

Could you post a sample output taken with the second program you posted so we can more directly see how the two functions are behaving and compare them to each other?

Also, the distribution of values in your sample output and the observation about it working better if you touch the sensors against the ground make it seem like you might not be getting a good sensor calibration. Can you confirm that when you calibrate your sensors, you are making sure each individual sensor is directed at both a dark surface and a light surface during the calibration process?

- Patrick

So I tried seeing the difference in readings to figure out why readLineWhite() works when I touch the sensor to the ground yesterday. This is what I remember from it.

Using the sensor at a distance of 1cm or higher from ground:
White - Around 0 to 20
Black - Around 400 to 800

Touching the sensor to the ground:
Black - Exactly 1000 on most sensors
White - (I sort of remember being close to exactly 0)

My test surfaces were - white A4 paper with black electric tape, white PVC foam board with black electric tape, black acrylic with white electric tape.

It felt like, if I could somehow just boost the value for black, I could get a correct position reading without touching the sensor to the ground.

Since,
finalValue = 1000 - value for readLineWhite() and if my value was around 400-600 for black at 1cm off the ground, finalValue = 1000 - value would give a larger finalValue for 400-600 range rather than when I touch the sensor to the ground and the value on black is exactly 1000 which gives a finalValue of 0. Hence using readLineWhite() the weighted average would then be calculated using the fact that black now represents lower values, white represents higher values.

I think this could solve it? I’m not sure though.

Interestingly, readLineBlack() gives me weird position readings(much like readLineWhite() is giving me now) when I touch the sensor to the ground but readLineWhite() then works perfectly well. Similarly, when 1cm or higher off the ground, readLineBlack() gives me perfect position readings but readLineWhite() does not.

We generally expect these sensors to work best when the readings they take during calibration are reflective of the readings they will take during actual operation. So, if your sensors are going to operate 1cm off the ground during normal operation, I suggest calibrating them that way.

Can post a sample output of the second program you posted?

- Patrick