PololuQTRSensor trouble

hi Ben,

Well, I probably down loaded it several weeks ago. I’ve been messing with this for quite some tome trying to get it to work, before finally posting on the forum.

Is there a current release version?

I’ll re download and see how it goes.

best
Phil

Hi Ben,

I followed the instructions for installign the new libs:
Removed the old version from arduino-0011\hardware\libraries\PololuQTRSensors and installed the new folder in the same location. The folder did not have a “.o” file. I loaded and compiled my app and during that process a “.o” was created and I assumed linked into the app.

The results are identical to those in my last posts, that is, it does not appear to work.

My code is the same as posted before and these are the header and cpp files I’m using from pololu:

/*
  PololuQTRSensors.h - Library for using Pololu QTR reflectance
	sensors and reflectance sensor arrays: QTR-1A, QTR-8A, QTR-1RC, and 
	QTR-8RC.  The object used will determine the type of the sensor (either
	QTR-xA or QTR-xRC).  Then simply specify in the constructor which 
	Arduino I/O pins are connected to a QTR sensor, and the read() method
	will obtain reflectance measurements for those sensors.  Smaller sensor
	values correspond to higher reflectance (e.g. white) while larger
	sensor values correspond to lower reflectance (e.g. black or a void).
	
	* PololuQTRSensorsRC should be used for QTR-1RC and QTR-8RC sensors.
	* PololuQTRSensorsAnalog should be used for QTR-1A and QTR-8A sensors.
*/
	
/*
 * Written by Ben Schmidel et al., May 28, 2008.
 * Copyright (c) 2008 Pololu Corporation. For more information, see
 *
 *   https://www.pololu.com
 *   https://forum.pololu.com
 *   https://www.pololu.com/docs/0J18/9
 *
 * You may freely modify and share this code, as long as you keep this
 * notice intact (including the two links above).  Licensed under the
 * Creative Commons BY-SA 3.0 license:
 *
 *   http://creativecommons.org/licenses/by-sa/3.0/
 *
 * Disclaimer: To the extent permitted by law, Pololu provides this work
 * without any warranty.  It might be defective, in which case you agree
 * to be responsible for all resulting costs and damages.
 */

#ifndef PololuQTRSensors_h
#define PololuQTRSensors_h

#define QTR_EMITTERS_OFF 0
#define QTR_EMITTERS_ON 1
#define QTR_EMITTERS_ON_AND_OFF 2

// This class cannot be instantiated directly (it has no constructor).
// Instead, you should instantiate one of its two derived classes (either the
// QTR-A or QTR-RC version, depending on the type of your sensor).
class PololuQTRSensors
{
  public:
	
	// Reads the sensor values into an array. There *MUST* be space
	// for as many values as there were sensors specified in the constructor.
	// Example usage:
	// unsigned int sensor_values[8];
	// sensors.read(sensor_values);
	// The values returned are a measure of the reflectance in abstract units,
	// with higher values corresponding to lower reflectance (e.g. a black
	// surface or a void).
	// If measureOffAndOn is true, measures the values with the
	// emitters on AND off and returns on - (timeout - off).  If this
	// value is less than zero, it returns zero.
	// This method will call the appropriate derived class' readPrivate(), as
	// determined by the _type data member.  Making this method virtual
	// leads to compiler warnings, which is why this alternate approach was
	// taken.
	void read(unsigned int *sensor_values, unsigned char readMode = QTR_EMITTERS_ON);
	
	// Turn the IR LEDs off and on.  This is mainly for use by the
	// read method, and calling these functions before or
	// after the reading the sensors will have no effect on the
	// readings, but you may wish to use these for testing purposes.
	void emittersOff();
	void emittersOn();
  
	// Reads the sensors for calibration.  The sensor values are
	// not returned; instead, the maximum and minimum values found
	// over time are stored internally and used for the
	// readCalibrated() method.
	void calibrate(unsigned char readMode = QTR_EMITTERS_ON);

	// Returns values calibrated to a value between 0 and 1000, where
	// 0 corresponds to the minimum value read by calibrate() and 1000
	// corresponds to the maximum value.  Calibration values are
	// stored separately for each sensor, so that differences in the
	// sensors are accounted for automatically.
	void readCalibrated(unsigned int *sensor_values, unsigned char readMode = QTR_EMITTERS_ON);

	// Operates the same as read calibrated, but also returns an
	// estimated position of the robot with respect to a line. The
	// estimate is made using a weighted average of the sensor indices
	// multiplied by 1000, so that a return value of 0 indicates that
	// the line is directly below sensor 0, a return value of 1000
	// indicates that the line is directly below sensor 1, 2000
	// indicates that it's below sensor 2000, etc.  Intermediate
	// values indicate that the line is between two sensors.  The
	// formula is:
	// 
	//    0*value0 + 1000*value1 + 2000*value2 + ...
	//   --------------------------------------------
	//         value0  +  value1  +  value2 + ...
	//
	// By default, this function assumes a dark line (high values)
	// surrounded by white (low values).  If your line is light on
	// black, set the optional second argument white_line to true.  In
	// this case, each sensor value will be replaced by (1000-value)
	// before the averaging.
	int readLine(unsigned int *sensor_values, unsigned char readMode = QTR_EMITTERS_ON, unsigned char white_line = 0);

	// Calibrated minumum and maximum values. These start at 1000 and
	// 0, respectively, so that the very first sensor reading will
	// update both of them.
	//
	// The pointers are unallocated until calibrate() is called, and
	// then allocated to exactly the size required.  Depending on the
	// readMode argument to calibrate, only the On or Off values may
	// be allocated, as required.
	//
	// These variables are made public so that you can use them for
	// your own calculations and do things like saving the values to
	// EEPROM, performing sanity checking, etc.
	unsigned int *calibratedMinimumOn;
	unsigned int *calibratedMaximumOn;
	unsigned int *calibratedMinimumOff;
	unsigned int *calibratedMaximumOff;
	
	~PololuQTRSensors();

  protected:

	PololuQTRSensors()
	{
	
	};

	void init(unsigned char numSensors, unsigned char emitterPin,
		unsigned char type);
	unsigned char _numSensors;

	unsigned char _emitterBitmask;
	// pointer to emitter PORT register
	volatile unsigned char* _emitterPORT;	// needs to be volatile
	// pointer to emitter DDR register
	volatile unsigned char* _emitterDDR;		// needs to be volatile
	
	unsigned int _maxValue; // the maximum value returned by this function

  private:
	
	unsigned char _type;	// the type of the derived class (QTR_RC
							// or QTR_A)

	// Handles the actual calibration. calibratedMinimum and
	// calibratedMaximum are pointers to the requested calibration
	// arrays, which will be allocated if necessary.
	void calibrateOnOrOff(unsigned int **calibratedMinimum,
						  unsigned int **calibratedMaximum,
						  unsigned char readMode);
};



// Object to be used for QTR-1RC and QTR-8RC sensors
class PololuQTRSensorsRC : public PololuQTRSensors
{
	// allows the base PololuQTRSensors class to access this class' 
	// readPrivate()
	friend class PololuQTRSensors;
	
  public:
  
	// if this constructor is used, the user must call init() before using
	// the methods in this class
	PololuQTRSensorsRC() { }
	
	// this constructor just calls init()
	PololuQTRSensorsRC(unsigned char* pins, unsigned char numSensors, 
		  unsigned int timeout = 4000, unsigned char emitterPin = 255);

	// the array 'pins' contains the Arduino pin assignment for each
	// sensor.  For example, if pins is {3, 6, 15}, sensor 1 is on
	// Arduino digital pin 3, sensor 2 is on Arduino digital pin 6,
	// and sensor 3 is on Arduino analog input 1 (digital pin 15).
	// Note that Arduino digital pins 0 - 7 correpsond to port D
	// pins PD0 - PD7, respectively.  Arduino digital pins 8 - 13
	// correspond to port B pins PB0 - PB5.  Arduino analog inputs
	// 0 - 5 are referred to as digital pins 14 - 19 (these are the
	// enumerations you should use for this library) and correspond
	// to port C pins PC0 - PC5.
	
	// 'numSensors' specifies the length of the 'pins' array (i.e. the
	// number of QTR-RC sensors you are using).  numSensors must be 
	// no greater than 8.
	
	// 'timeout' specifies the length of time in timer2 counts beyond
	// which you consider the sensor reading completely black.  That is to say,
	// if the pulse length for a pin exceeds 'timeout', pulse timing will stop
	// and the reading for that pin will be considered full black.
	// It is recommended that you set timeout to be between 1000 and
	// 3000 us, depending on things like the height of your sensors and
	// ambient lighting.  Using timeout allows you to shorten the
	// duration of a sensor-reading cycle while still maintaining
	// useful analog measurements of reflectance.  On a 16 MHz microcontroller,
	// you can convert timer2 counts to microseconds by dividing by 2
	// (i.e. 2000 us = 4000 timer2 counts = 'timeout' of 4000).  On a 20 MHz
	// microcontroller, you can convert timer2 counts to microseconds by
	// dividing by 2.5 or multiplying by 0.4 
	// (i.e. 2000 us = 5000 timer2 counts = 'timeout' of 5000).
	
	// emitterPin is the Arduino digital pin that controls whether the IR LEDs
	// are on or off.  This pin is optional and only exists on the 8A and 8RC
	// QTR sensor arrays.  If a valid pin is specified,
	// the emitters will only be turned on during a reading.  If an invalid
	// pin is specified (e.g. 255), the IR emitters will always be on.
	void init(unsigned char* pins, unsigned char numSensors, 
		  unsigned int timeout = 4000, unsigned char emitterPin = 255);
		  

  
  private:

	// Reads the sensor values into an array. There *MUST* be space
	// for as many values as there were sensors specified in the constructor.
	// Example usage:
	// unsigned int sensor_values[8];
	// sensors.read(sensor_values);
	// The values returned are a measure of the reflectance in timer2 counts,
	// with higher values corresponding to lower reflectance (e.g. a black
	// surface or a void).  Timer2 will be running at the MCU clock / 8, which
	// means 2 MHz for a 16 MHz MCU and 2.5 MHz for a 20 MHz MCU.
	void readPrivate(unsigned int *sensor_values);
 

  private:

	unsigned char _bitmask[8];
	// pointer to PIN registers
	volatile unsigned char* _register[8];	// needs to be volatile
		
	unsigned char _portBMask;
	unsigned char _portCMask;
	unsigned char _portDMask;
};



// Object to be used for QTR-1A and QTR-8A sensors
class PololuQTRSensorsAnalog : public PololuQTRSensors
{
	// allows the base PololuQTRSensors class to access this class' 
	// readPrivate()
	friend class PololuQTRSensors;
	
  public:
  
	// if this constructor is used, the user must call init() before using
	// the methods in this class
	PololuQTRSensorsAnalog() { }
	
	// this constructor just calls init()
	PololuQTRSensorsAnalog(unsigned char* analogPins, 
		unsigned char numSensors, unsigned char numSamplesPerSensor = 4,
		unsigned char emitterPin = 255);

	// the array 'pins' contains the Arduino analog pin assignment for each
	// sensor.  For example, if pins is {0, 1, 7}, sensor 1 is on
	// Arduino analog input 0, sensor 2 is on Arduino analog input 1,
	// and sensor 3 is on Arduino analog input 7.  The ATmega168 has 8
	// total analog input channels (0 - 7) that correspond to port C
	// pins PC0 - PC7.
	
	// 'numSensors' specifies the length of the 'analogPins' array (i.e. the
	// number of QTR-A sensors you are using).  numSensors must be 
	// no greater than 8.
	
	// 'numSamplesPerSensor' indicates the number of 10-bit analog samples
	// to average per channel (i.e. per sensor) for each reading.  The total
	// number of analog-to-digital conversions performed will be equal to
	// numSensors*numSamplesPerSensor.  Note that the amount of time it takes
	// to perform a single analog-to-digital conversion is approximately:
	// 128 * 13 / F_CPU = 1664 / F_CPU
	// If F_CPU is 16 MHz, as on most Arduinos, this becomes:
	// 1664 / 16 MHz = 104 us
	// So if numSamplesPerSensor is 4 and numSensors is, say, 6, it will take
	// 4 * 6 * 104 us = 2.5 ms to perform a full readLine() if F_CPU is 16 MHz.
	// Increasing this parameter increases noise suppression at the cost of
	// sample rate.  Recommended value: 4.
	
	// emitterPin is the Arduino digital pin that controls whether the IR LEDs
	// are on or off.  This pin is optional and only exists on the 8A and 8RC
	// QTR sensor arrays.  If a valid pin is specified, the emitters will only
	// be turned on during a reading.  If an invalid pin is specified 
	// (e.g. 255), the IR emitters will always be on.
	void init(unsigned char* analogPins, unsigned char numSensors, 
		unsigned char numSamplesPerSensor = 4, unsigned char emitterPin = 255);
		  

  
  private:

	// Reads the sensor values into an array. There *MUST* be space
	// for as many values as there were sensors specified in the constructor.
	// Example usage:
	// unsigned int sensor_values[8];
	// sensors.read(sensor_values);
	// The values returned are a measure of the reflectance in terms of a
	// 10-bit ADC average with higher values corresponding to lower 
	// reflectance (e.g. a black surface or a void).
	void readPrivate(unsigned int *sensor_values);
 

  private:

	unsigned char _analogPins[8];
	unsigned char _numSamplesPerSensor;
	unsigned char _portCMask;
};


#endif

// Local Variables: **
// mode: C++ **
// c-basic-offset: 4 **
// tab-width: 4 **
// indent-tabs-mode: t **
// end: **
/*
  PololuQTRSensors.cpp - Library for using Pololu QTR reflectance
	sensors and reflectance sensor arrays: QTR-1A, QTR-8A, QTR-1RC, and 
	QTR-8RC.  The object used will determine the type of the sensor (either
	QTR-xA or QTR-xRC).  Then simply specify in the constructor which 
	Arduino I/O pins are connected to a QTR sensor, and the read() method
	will obtain reflectance measurements for those sensors.  Smaller sensor
	values correspond to higher reflectance (e.g. white) while larger
	sensor values correspond to lower reflectance (e.g. black or a void).
	
	* PololuQTRSensorsRC should be used for QTR-1RC and QTR-8RC sensors.
	* PololuQTRSensorsAnalog should be used for QTR-1A and QTR-8A sensors.
*/
	
/*
 * Written by Ben Schmidel et al., May 28, 2008.
 * Copyright (c) 2008 Pololu Corporation. For more information, see
 *
 *   https://www.pololu.com
 *   https://forum.pololu.com
 *   https://www.pololu.com/docs/0J18/9
 *
 * You may freely modify and share this code, as long as you keep this
 * notice intact (including the two links above).  Licensed under the
 * Creative Commons BY-SA 3.0 license:
 *
 *   http://creativecommons.org/licenses/by-sa/3.0/
 *
 * Disclaimer: To the extent permitted by law, Pololu provides this work
 * without any warranty.  It might be defective, in which case you agree
 * to be responsible for all resulting costs and damages.
 */

#ifndef F_CPU
#define F_CPU 20000000UL
#endif
#include <avr/io.h>
#include <stdlib.h>
#include "PololuQTRSensors.h"

#define QTR_RC		0
#define QTR_A		1

#ifdef LIB_POLOLU

#include "../OrangutanTime/OrangutanTime.h"		// provides access to delay routines
// two options for our sensors

// one pointer to the type in use
static PololuQTRSensors *qtr;

extern "C" void qtr_emitters_on()
{
	qtr->emittersOn();
}

extern "C" void qtr_emitters_off()
{
	qtr->emittersOff();
}

extern "C" char qtr_rc_init(unsigned char* pins, unsigned char numSensors, 
			    unsigned int timeout, unsigned char emitterPin)
{
	PololuQTRSensorsRC *qtr_rc = (PololuQTRSensorsRC *)malloc(sizeof(PololuQTRSensorsRC));
	if(!qtr_rc)
		return 0; // out of memory
	qtr_rc->init(pins, numSensors, timeout, emitterPin);
	qtr = qtr_rc;
	return 1;
}

extern "C" char qtr_analog_init(unsigned char* analogPins, unsigned char numSensors, 
		unsigned char numSamplesPerSensor, unsigned char emitterPin)
{
	PololuQTRSensorsAnalog *qtr_analog = (PololuQTRSensorsAnalog *)malloc(sizeof(PololuQTRSensorsAnalog));
	if(!qtr_analog)
		return 0; // out of memory
	qtr_analog->init(analogPins, numSensors, numSamplesPerSensor, emitterPin);
	qtr = qtr_analog;
	return 1;
}

extern "C" void qtr_read(unsigned int *sensor_values, unsigned char readMode) {
	qtr->read(sensor_values,readMode);
}

extern "C" void qtr_calibrate(unsigned char readMode)
{
	qtr->calibrate(readMode);
}

extern "C" void qtr_read_calibrated(unsigned int *sensor_values, unsigned char readMode)
{
	qtr->readCalibrated(sensor_values, readMode);
}

extern "C" int qtr_read_line(unsigned int *sensor_values, unsigned char readMode)
{
	return qtr->readLine(sensor_values, readMode, false);
}

extern "C" int qtr_read_line_white(unsigned int *sensor_values, unsigned char readMode)
{
	return qtr->readLine(sensor_values, readMode, true);
}

#else
#include "wiring.h"		// provides access to delay() and delayMicroseconds()
#endif

// Base class data member initialization (called by derived class init())
void PololuQTRSensors::init(unsigned char numSensors, 
  unsigned char emitterPin, unsigned char type)
{
	calibratedMinimumOn=0;
	calibratedMaximumOn=0;
	calibratedMinimumOff=0;
	calibratedMaximumOff=0;

	if (numSensors > 8)
		_numSensors = 8;
	else
		_numSensors = numSensors;
		
	_type = type;
		
	if (emitterPin < 8)				// port D
	{
		_emitterBitmask = 1 << emitterPin;
		_emitterPORT = &PORTD;
		_emitterDDR = &DDRD;
	}
	else if (emitterPin < 14)		// port B
	{
		_emitterBitmask = 1 << (emitterPin - 8);
		_emitterPORT = &PORTB;
		_emitterDDR = &DDRB;
	}
	else if (emitterPin < 20)		// port C
	{
		_emitterBitmask = 1 << (emitterPin - 14);
		_emitterPORT = &PORTC;
		_emitterDDR = &DDRC;
	}
	else
	{
		_emitterDDR = 0;
		_emitterPORT = 0;
	}
}


// Reads the sensor values into an array. There *MUST* be space
// for as many values as there were sensors specified in the constructor.
// Example usage:
// unsigned int sensor_values[8];
// sensors.read(sensor_values);
// The values returned are a measure of the reflectance in abstract units,
// with higher values corresponding to lower reflectance (e.g. a black
// surface or a void).
void PololuQTRSensors::read(unsigned int *sensor_values, unsigned char readMode)
{
	unsigned int off_values[8];
	unsigned char i;
	
	if(readMode == QTR_EMITTERS_ON || readMode == QTR_EMITTERS_ON_AND_OFF)
		emittersOn();

	if (_type == QTR_RC)
	{
		((PololuQTRSensorsRC*)this)->readPrivate(sensor_values);
		emittersOff();
		if(readMode == QTR_EMITTERS_ON_AND_OFF)
			((PololuQTRSensorsRC*)this)->readPrivate(off_values);
	}
	else
	{
		((PololuQTRSensorsAnalog*)this)->readPrivate(sensor_values);
		emittersOff();
		if(readMode == QTR_EMITTERS_ON_AND_OFF)
			((PololuQTRSensorsRC*)this)->readPrivate(off_values);
	}

	if(readMode == QTR_EMITTERS_ON_AND_OFF)
	{
		for(i=0;i<_numSensors;i++)
		{
			sensor_values[i] += _maxValue - off_values[i];
		}
	}
}


// Turn the IR LEDs off and on.  This is mainly for use by the
// read method, and calling these functions before or
// after the reading the sensors will have no effect on the
// readings, but you may wish to use these for testing purposes.
void PololuQTRSensors::emittersOff()
{
	if (_emitterDDR == 0)
		return;
	*_emitterDDR |= _emitterBitmask;
	*_emitterPORT &= ~_emitterBitmask;
}

void PololuQTRSensors::emittersOn()
{
  if (_emitterDDR == 0)
		return;
	*_emitterDDR |= _emitterBitmask;
	*_emitterPORT |= _emitterBitmask;
}


// Reads the sensors 10 times and uses the results for
// calibration.  The sensor values are not returned; instead, the
// maximum and minimum values found over time are stored internally
// and used for the readCalibrated() method.
void PololuQTRSensors::calibrate(unsigned char readMode)
{
	if(readMode == QTR_EMITTERS_ON_AND_OFF || readMode == QTR_EMITTERS_ON)
	{
		calibrateOnOrOff(&calibratedMinimumOn,
						 &calibratedMaximumOn,
						 QTR_EMITTERS_ON);
	}


	if(readMode == QTR_EMITTERS_ON_AND_OFF || readMode == QTR_EMITTERS_OFF)
	{
		calibrateOnOrOff(&calibratedMinimumOff,
						 &calibratedMaximumOff,
						 QTR_EMITTERS_OFF);
	}
}

void PololuQTRSensors::calibrateOnOrOff(unsigned int **calibratedMinimum,
										unsigned int **calibratedMaximum,
										unsigned char readMode)
{
	int i;
	unsigned int sensor_values[8];
	unsigned int max_sensor_values[8];
	unsigned int min_sensor_values[8];

	// Allocate the arrays if necessary.
	if(*calibratedMaximum == 0)
	{
		*calibratedMaximum = (unsigned int*)malloc(sizeof(unsigned int)*_numSensors);

		// If the malloc failed, don't continue.
		if(*calibratedMaximum == 0)
			return;

		// Initialize the max and min calibrated values to values that
		// will cause the first reading to update them.

		for(i=0;i<_numSensors;i++)
			(*calibratedMaximum)[i] = 0;
	}
	if(*calibratedMinimum == 0)
	{
		*calibratedMinimum = (unsigned int*)malloc(sizeof(unsigned int)*_numSensors);

		// If the malloc failed, don't continue.
		if(*calibratedMinimum == 0)
			return;

		for(i=0;i<_numSensors;i++)
			(*calibratedMinimum)[i] = _maxValue;
	}

	int j;
	for(j=0;j<10;j++)
	{
		read(sensor_values,readMode);
		for(i=0;i<_numSensors;i++)
		{
			// set the max we found THIS time
			if(j == 0 || max_sensor_values[i] < sensor_values[i])
				max_sensor_values[i] = sensor_values[i];

			// set the min we found THIS time
			if(j == 0 || min_sensor_values[i] > sensor_values[i])
				min_sensor_values[i] = sensor_values[i];
		}
	}

	// record the min and max calibration values
	for(i=0;i<_numSensors;i++)
	{
		if(min_sensor_values[i] > (*calibratedMaximum)[i])
			(*calibratedMaximum)[i] = min_sensor_values[i];
		if(max_sensor_values[i] < (*calibratedMinimum)[i])
			(*calibratedMinimum)[i] = max_sensor_values[i];
	}
}


// Returns values calibrated to a value between 0 and 1000, where
// 0 corresponds to the minimum value read by calibrate() and 1000
// corresponds to the maximum value.  Calibration values are
// stored separately for each sensor, so that differences in the
// sensors are accounted for automatically.
void PololuQTRSensors::readCalibrated(unsigned int *sensor_values, unsigned char readMode)
{
	int i;

	// if not calibrated, do nothing
	if(readMode == QTR_EMITTERS_ON_AND_OFF || readMode == QTR_EMITTERS_OFF)
		if(!calibratedMinimumOff || !calibratedMaximumOff)
			return;
	if(readMode == QTR_EMITTERS_ON_AND_OFF || readMode == QTR_EMITTERS_ON)
		if(!calibratedMinimumOn || !calibratedMaximumOn)
			return;

	// read the needed values
	read(sensor_values,readMode);

	for(i=0;i<_numSensors;i++)
	{
		unsigned int calmin,calmax;
		unsigned int denominator;

		// find the correct calibration
		if(readMode == QTR_EMITTERS_ON)
		{
			calmax = calibratedMaximumOn[i];
		    calmin = calibratedMinimumOn[i];
		}
		else if(readMode == QTR_EMITTERS_OFF)
		{
			calmax = calibratedMaximumOff[i];
		    calmin = calibratedMinimumOff[i];
		}
		else // QTR_EMITTERS_ON_AND_OFF
		{
			
			if(calibratedMinimumOff[i] < calibratedMinimumOn[i]) // no meaningful signal
				calmin = _maxValue;
			else
				calmin = calibratedMinimumOn[i] + _maxValue - calibratedMinimumOff[i]; // this won't go past _maxValue

			if(calibratedMaximumOff[i] < calibratedMaximumOn[i]) // no meaningful signal
				calmax = _maxValue;
			else
				calmax = calibratedMaximumOn[i] + _maxValue - calibratedMaximumOff[i]; // this won't go past _maxValue
		}

		denominator = calmax - calmin;

		signed int x = 0;
		if(denominator != 0)
			x = (((signed long)sensor_values[i]) - calmin)
				* 1000 / denominator;
		if(x < 0)
			x = 0;
		else if(x > 1000)
			x = 1000;
		sensor_values[i] = x;
	}

}


// Operates the same as read calibrated, but also returns an
// estimated position of the robot with respect to a line. The
// estimate is made using a weighted average of the sensor indices
// multiplied by 1000, so that a return value of 0 indicates that
// the line is directly below sensor 0, a return value of 1000
// indicates that the line is directly below sensor 1, 2000
// indicates that it's below sensor 2000, etc.  Intermediate
// values indicate that the line is between two sensors.  The
// formula is:
// 
//    0*value0 + 1000*value1 + 2000*value2 + ...
//   --------------------------------------------
//         value0  +  value1  +  value2 + ...
//
// By default, this function assumes a dark line (high values)
// surrounded by white (low values).  If your line is light on
// black, set the optional second argument white_line to true.  In
// this case, each sensor value will be replaced by (1000-value)
// before the averaging.
int PololuQTRSensors::readLine(unsigned int *sensor_values,
	unsigned char readMode, unsigned char white_line)
{
	unsigned char i, on_line = 0;
	unsigned long avg; // this is for the weighted total, which is long
	                   // before division
	unsigned int sum; // this is for the denominator which is <= 64000
	static int last_value=0; // assume initially that the line is left.

	readCalibrated(sensor_values, readMode);

	avg = 0;
	sum = 0;
  
	for(i=0;i<_numSensors;i++) {
		int value = sensor_values[i];
		if(white_line)
			value = 1000-value;

		// keep track of whether we see the line at all
		if(value > 200) {
			on_line = 1;
		}
		
		// only average in values that are above a noise threshold
		if(value > 50) {
			avg += (long)(value) * (i * 1000);
			sum += value;
		}
	}

	if(!on_line)
	{
		// If it last read to the left of center, return 0.
		if(last_value < (_numSensors-1)*1000/2)
			return 0;
		
		// If it last read to the right of center, return the max.
		else
			return (_numSensors-1)*1000;

	}

	last_value = avg/sum;

	return last_value;
}



// Derived RC class constructor
PololuQTRSensorsRC::PololuQTRSensorsRC(unsigned char* pins,
  unsigned char numSensors, unsigned int timeout, unsigned char emitterPin)
{
	init(pins, numSensors, timeout, emitterPin);
}


// the array 'pins' contains the Arduino pin assignment for each
// sensor.  For example, if pins is {3, 6, 15}, sensor 1 is on
// Arduino digital pin 3, sensor 2 is on Arduino digital pin 6,
// and sensor 3 is on Arduino analog input 1 (digital pin 15).
// Note that Arduino digital pins 0 - 7 correpsond to port D
// pins PD0 - PD7, respectively.  Arduino digital pins 8 - 13
// correspond to port B pins PB0 - PB5.  Arduino analog inputs
// 0 - 5 are referred to as digital pins 14 - 19 (these are the
// enumerations you should use for this library) and correspond
// to port C pins PC0 - PC5.

// 'numSensors' specifies the length of the 'pins' array (i.e. the
// number of QTR-RC sensors you are using).  numSensors must be 
// no greater than 8.

// 'timeout' specifies the length of time in timer2 counts beyond
// which you consider the sensor reading completely black.  That is to say,
// if the pulse length for a pin exceeds 'timeout', pulse timing will stop
// and the reading for that pin will be considered full black.
// It is recommended that you set timeout to be between 1000 and
// 3000 us, depending on things like the height of your sensors and
// ambient lighting.  Using timeout allows you to shorten the
// duration of a sensor-reading cycle while still maintaining
// useful analog measurements of reflectance.  On a 16 MHz microcontroller,
// you can convert timer2 counts to microseconds by dividing by 2
// (i.e. 2000 us = 4000 timer2 counts = 'timeout' of 4000).  On a 20 MHz
// microcontroller, you can convert timer2 counts to microseconds by
// dividing by 2.5 or multiplying by 0.4 
// (i.e. 2000 us = 5000 timer2 counts = 'timeout' of 5000).
	
// 'emitterPin' is the Arduino pin that controls the IR LEDs on the 8RC
// modules.  If you are using a 1RC (i.e. if there is no emitter pin),
// use an invalid Arduino pin value (20 or greater).
void PololuQTRSensorsRC::init(unsigned char* pins,
	unsigned char numSensors, unsigned int timeout, unsigned char emitterPin)
{
	PololuQTRSensors::init(numSensors, emitterPin, QTR_RC);
	
	unsigned char i;
	_portBMask = 0;
	_portCMask = 0;
	_portDMask = 0;
	
	_maxValue = timeout;
	for (i = 0; i < _numSensors; i++)
	{
		if (pins[i] < 8)			// port D
		{
			_bitmask[i] = 1 << pins[i];
			_portDMask |= _bitmask[i];
			_register[i] = &PIND;
		}
		else if (pins[i] < 14)		// port B
		{
			_bitmask[i] = 1 << (pins[i] - 8);
			_portBMask |= _bitmask[i];
			_register[i] = &PINB;
		}
		else if (pins[i] < 20)		// port C
		{
			_bitmask[i] = 1 << (pins[i] - 14);
			_portCMask |= _bitmask[i];
			_register[i] = &PINC;
		}
	}
}


// Reads the sensor values into an array. There *MUST* be space
// for as many values as there were sensors specified in the constructor.
// Example usage:
// unsigned int sensor_values[8];
// sensors.read(sensor_values);
// ...
// The values returned are in microseconds and range from 0 to
// timeout_us (as specified in the constructor).
void PololuQTRSensorsRC::readPrivate(unsigned int *sensor_values)
{
	unsigned char i;
	unsigned char start_time;
	unsigned char delta_time;
	unsigned int time = 0;

	unsigned char last_b = _portBMask;
	unsigned char last_c = _portCMask;
	unsigned char last_d = _portDMask;
	
	// reset the values
	for(i = 0; i < _numSensors; i++)
		sensor_values[i] = 0;
	
	// set all sensor pins to outputs
	DDRB |= _portBMask;
	DDRC |= _portCMask;
	DDRD |= _portDMask;
	
	// drive high for 10 us
	PORTB |= _portBMask;
	PORTC |= _portCMask;
	PORTD |= _portDMask;
	
	delayMicroseconds(10);
	
	// set all ports to inputs
	DDRB &= ~_portBMask;
	DDRC &= ~_portCMask;
	DDRD &= ~_portDMask;
	
	// turn off pull ups
	PORTB &= ~_portBMask;
	PORTC &= ~_portCMask;
	PORTD &= ~_portDMask;

	unsigned char prevTCCR2A = TCCR2A;
	unsigned char prevTCCR2B = TCCR2B;
	TCCR2A |= 0x03;
	TCCR2B = 0x02;		// run timer2 in normal mode at 2.5 MHz
						// this is compatible with OrangutanMotors


	start_time = TCNT2;
	while (time < _maxValue)
	{
		// Keep track of the total time.
		// This explicitly casts the difference to unsigned char, so
		// we don't add negative values.
		delta_time = TCNT2 - start_time;
		time += delta_time;
		start_time += delta_time;

		// continue immediately if there is no change
		if (PINB == last_b && PINC == last_c && PIND == last_d)
			continue;

		// save the last observed values
		last_b = PINB;
		last_c = PINC;
		last_d = PIND;

		// figure out which pins changed
		for (i = 0; i < _numSensors; i++)
		{
			if (sensor_values[i] == 0 && !(*_register[i] & _bitmask[i]))
				sensor_values[i] = time;
		}
	}

	TCCR2A = prevTCCR2A;
	TCCR2B = prevTCCR2B;
	for(i = 0; i < _numSensors; i++)
		if (!sensor_values[i])
			sensor_values[i] = _maxValue;
}



// Derived Analog class constructor
PololuQTRSensorsAnalog::PololuQTRSensorsAnalog(unsigned char* analogPins,
  unsigned char numSensors, unsigned char numSamplesPerSensor,
  unsigned char emitterPin)
{
	init(analogPins, numSensors, numSamplesPerSensor, emitterPin);
}


// the array 'pins' contains the Arduino analog pin assignment for each
// sensor.  For example, if pins is {0, 1, 7}, sensor 1 is on
// Arduino analog input 0, sensor 2 is on Arduino analog input 1,
// and sensor 3 is on Arduino analog input 7.  The ATmega168 has 8
// total analog input channels (0 - 7) that correspond to port C
// pins PC0 - PC7.

// 'numSensors' specifies the length of the 'analogPins' array (i.e. the
// number of QTR-A sensors you are using).  numSensors must be 
// no greater than 8.

// 'numSamplesPerSensor' indicates the number of 10-bit analog samples
// to average per channel (i.e. per sensor) for each reading.  The total
// number of analog-to-digital conversions performed will be equal to
// numSensors*numSamplesPerSensor.  Note that the amount of time it takes
// to perform a single analog-to-digital conversion is approximately:
// 128 * 13 / F_CPU = 1664 / F_CPU
// If F_CPU is 16 MHz, as on most Arduinos, this becomes:
// 1664 / 16 MHz = 104 us
// So if numSamplesPerSensor is 4 and numSensors is, say, 6, it will take
// 4 * 6 * 104 us = 2.5 ms to perform a full readLine() if F_CPU is 16 MHz.
// Increasing this parameter increases noise suppression at the cost of
// sample rate.  Recommended value: 4.

// emitterPin is the Arduino digital pin that controls whether the IR LEDs
// are on or off.  This pin is optional and only exists on the 8A and 8RC
// QTR sensor arrays.  If a valid pin is specified, the emitters will only
// be turned on during a reading.  If an invalid pin is specified 
// (e.g. 255), the IR emitters will always be on.
void PololuQTRSensorsAnalog::init(unsigned char* analogPins,
	unsigned char numSensors, unsigned char numSamplesPerSensor,
	unsigned char emitterPin)
{
	unsigned char i;
	
	PololuQTRSensors::init(numSensors, emitterPin, QTR_A);
	
	_numSamplesPerSensor = numSamplesPerSensor;
	_portCMask = 0;
	for (i = 0; i < _numSensors; i++)
	{
		_analogPins[i] = analogPins[i];
		if (analogPins[i] <= 5)	// no need to mask for dedicated analog inputs
			_portCMask |= (1 << analogPins[i]);
	}

	_maxValue = 1023; // this is the maximum returned by the A/D conversion
}


// Reads the sensor values into an array. There *MUST* be space
// for as many values as there were sensors specified in the constructor.
// Example usage:
// unsigned int sensor_values[8];
// sensors.read(sensor_values);
// The values returned are a measure of the reflectance in terms of a
// 10-bit ADC average with higher values corresponding to lower 
// reflectance (e.g. a black surface or a void).
void PololuQTRSensorsAnalog::readPrivate(unsigned int *sensor_values)
{
	unsigned char i, j;
	
	// store current state of various registers
	unsigned char admux = ADMUX;
	unsigned char adcsra = ADCSRA;
	unsigned char ddrc = DDRC;
	unsigned char portc = PORTC;

	// wait for any current conversion to finish
	while (ADCSRA & (1 << ADSC));
	
	// reset the values
	for(i = 0; i < _numSensors; i++)
		sensor_values[i] = 0;

	// set all sensor pins to high-Z inputs
	DDRC &= ~_portCMask;
	PORTC &= ~_portCMask;
	
	ADCSRA = 0x87;	// configure the ADC
	for (j = 0; j < _numSamplesPerSensor; j++)
	{
		for (i = 0; i < _numSensors; i++)
		{
			ADMUX = _analogPins[i];			// set analog input channel
			ADCSRA |= 1 << ADSC;			// start the conversion
			while (ADCSRA & (1 << ADSC));	// wait for conversion to finish
			sensor_values[i] += ADC;		// add in the conversion result
		}
	}
	
	// get the rounded average of the readings for each sensor
	for (i = 0; i < _numSensors; i++)
		sensor_values[i] = (sensor_values[i] + (_numSamplesPerSensor >> 1)) /
			_numSamplesPerSensor;

	ADMUX = admux;
	ADCSRA = adcsra;
	PORTC = portc;
	DDRC = ddrc;
}

// the destructor frees up allocated memory
PololuQTRSensors::~PololuQTRSensors()
{
	if(calibratedMaximumOn)
		free(calibratedMaximumOn);
	if(calibratedMaximumOff)
		free(calibratedMaximumOff);
	if(calibratedMinimumOn)
		free(calibratedMinimumOn);
	if(calibratedMinimumOff)
		free(calibratedMinimumOff);
}


// Local Variables: **
// mode: C++ **
// c-basic-offset: 4 **
// tab-width: 4 **
// indent-tabs-mode: t **
// end: **

I am in the process of investigating the problem further. The test I conducted on Friday was to connect the output of a potentiometer to an analog input and then to initialize the sensor library to use that pin. When I read uncalibrated sensor values, I was able to get expected readings from the input with the potentiometer on it. If you feel so inclined, you could conduct a similar test to make sure at least that works for you. Also, could you try reading uncalibrated sensor values with the sensor’s LEDON pin disconnected. This should ensure that the IR emitters are on. You can verify this if you have a digital camera without an IR filter (many cell phone cameras qualify); just point it at the sensor array and you should be able to see the IR LEDs glowing on the camera’s display if they are on.

- Ben

Hi Ben,

As you suggested, I tried looking at the sensors with my cell phone using the code below.

This is what I saw.

During the calibration phase, the emitters were on. Once the "i to 250’ loop is completed, the emitters never came back on.

Phil

#include <PololuQTRSensors.h>  

#define NUMSENSORS 6
#define SAMPLES 3
#define EMITTERPIN 9

unsigned int sensors[8]; 
long  cnt = 0;
unsigned int line = 0;

PololuQTRSensorsAnalog qtra((unsigned char[]) {0, 1, 2, 3, 4, 5}, NUMSENSORS, SAMPLES, EMITTERPIN);  

void setup()
{  
  int i;  
  Serial.begin(9600);
  
  Serial.println("Starting to Calibrate");
  for (i = 0; i < 250; i++) {   // make the calibration take about 5 seconds  
    qtra.calibrate(QTR_EMITTERS_ON);
    Serial.print(".");  
    delay(20);  
} 
  Serial.println();
  Serial.println("Finished calibrating");
  
  delay(100);  
  
  unsigned int *pArry;
  
  pArry = qtra.calibratedMinimumOn;
  Serial.print("calibratedMinimumOn    ");
  for (i=0; i<NUMSENSORS; i++) {
    Serial.print("\t");
    Serial.print(pArry[0]);
  }
  Serial.println();
  
  pArry = qtra.calibratedMaximumOn;
  Serial.print("calibratedMaximumOn    ");
  for (i=0; i<NUMSENSORS; i++) {
    Serial.print("\t");
    Serial.print(pArry[0]);
  }
  Serial.println();
  
  pArry = qtra.calibratedMinimumOff;
  Serial.print("calibratedMinimumOff    ");
  for (i=0; i<NUMSENSORS; i++) {
    Serial.print("\t");
    Serial.print(pArry[0]);
  }
  Serial.println();
  
  pArry = qtra.calibratedMaximumOff;
  Serial.print("calibratedMaximumOff    ");
  for (i=0; i<NUMSENSORS; i++) {
    Serial.print("\t");
    Serial.print(pArry[0]);
  }
  Serial.println();
  
  delay(10000);
}

void loop() 
{
  int i;
  Serial.println(cnt++);
  
  qtra.readCalibrated(sensors, QTR_EMITTERS_OFF);
  Serial.print("  EMITTERS_OFF  ");
  for (i=0; i<NUMSENSORS; i++) {
    Serial.print("\t");
    Serial.print(sensors[i]);
  }
  Serial.println();
  
  delay(1000);                  // stop the program for some time
  
  qtra.readCalibrated(sensors, QTR_EMITTERS_ON);
  Serial.print("  EMITTERS_ON  ");
  for (i=0; i<NUMSENSORS; i++) {
    Serial.print("\t");
    Serial.print(sensors[i]);
  }
  Serial.println();
  
  delay(1000);                  // stop the program for some time
  
  qtra.readCalibrated(sensors, QTR_EMITTERS_ON_AND_OFF);
  Serial.print("  EMITTERS_ON_OFF  ");
  for (i=0; i<NUMSENSORS; i++) {
    Serial.print("\t");
    Serial.print(sensors[i]);
  }
  Serial.println();
  
  delay(1000);                  // stop the program for some time
  
  line = qtra.readLine(sensors);
  Serial.print("    line = ");
  Serial.print(line);
  Serial.println();

  delay(1000);                  // stop the program for some time
}

Can you do the same test with the emitter pin (labeled LEDON on the sensor array) disconnected?

- Ben

Hi again Ben.

You may not believe this, but I’ve tested pretty much every combination you or I can think of. I guess I’m wondering if anyone else is using this software and if so, I would like to hear from them.

These are the results from using the following bit of test code (which I’ve posted before).

With the first test, the LEDON pin is contected. As you can see from looking at the code, it turns the LEDON pin off and on, delaying one second in between. Watching the ir emitters with my phone, they do indeed turn on and off each second.

With the second test, I disconnected the LEDON pin and as you would expect the ir emitters remained on at all times while the program ran.

Simple test code:

/*
 * AnalogInput
 * by DojoDave <http://www.0j0.org>
 *
 * Turns on and off a light emitting diode(LED) connected to digital  
 * pin 13. The amount of time the LED will be on and off depends on
 * the value obtained by analogRead(). In the easiest case we connect
 * a potentiometer to analog pin 2.
 *
 * http://www.arduino.cc/en/Tutorial/AnalogInput
 */

int ledPin = 13;   // select the pin for the LED
int val0 = 0;       //
int val1 = 0;       //
int val2 = 0;       //
int val3 = 0;       //
int val4 = 0;       //
int val5 = 0;       //
long cnt = 0;

void setup() {
  pinMode(9, OUTPUT);  // declare the ledPin as an OUTPUT
  
  
  Serial.begin(9600);
}

void loop() {
  cnt++;
  digitalWrite(9, (cnt%2));   // sets 9 
  
  val0 = analogRead(0);    // 
  val1 = analogRead(1);    // 
  val2 = analogRead(2);    // 
  val3 = analogRead(3);    // 
  val4 = analogRead(4);    // 
  val5 = analogRead(5);    // 
  Serial.print(val0);
  Serial.print("\t");
  Serial.print(val1);
  Serial.print("\t");
  Serial.print(val2);
  Serial.print("\t");
  Serial.print(val3);
  Serial.print("\t");
  Serial.print(val4);
  Serial.print("\t");
  Serial.print(val5);
  Serial.print("\t");
  Serial.println();
  delay(1000);                  // stop the program for some time
}

The next test involves the Pololu Qtr Sensor class.

First with the LEDON pin connected. Looking with my phone again, the emitters are on during the (i = 0; i < 250; i++) loop in the setup phase, but turn off after that and do not come on again.

Next, with the LEDON pin disconnected. Viewing with the phone, the emitters are on continuously, even during the ‘loop’ phase.

The results from both of these test are identical and are included below, however, they show similar results to those from my previous tests, that is, it does not work.

I doubt very much if this code has been tested with an Arduino.

Qtr class code:

#include <PololuQTRSensors.h>  

#define NUMSENSORS 6
#define SAMPLES 3
#define EMITTERPIN 9

unsigned int sensors[8]; 
long  cnt = 0;
unsigned int line = 0;

PololuQTRSensorsAnalog qtra((unsigned char[]) {0, 1, 2, 3, 4, 5}, NUMSENSORS, SAMPLES, EMITTERPIN);  

void setup()
{  
  int i;  
  Serial.begin(9600);
  
  Serial.println("Starting to Calibrate");
  for (i = 0; i < 250; i++) {   // make the calibration take about 5 seconds  
    qtra.calibrate(QTR_EMITTERS_ON);
    Serial.print(".");  
    delay(20);  
  } 
  Serial.println();
  Serial.println("Finished calibrating");
  
  delay(100);  

  unsigned int *pArry;
  
  pArry = qtra.calibratedMinimumOn;
  Serial.print("calibratedMinimumOn    ");
  for (i=0; i<NUMSENSORS; i++) {
    Serial.print("\t");
    Serial.print(pArry[0]);
  }
  Serial.println();
  
  pArry = qtra.calibratedMaximumOn;
  Serial.print("calibratedMaximumOn    ");
  for (i=0; i<NUMSENSORS; i++) {
    Serial.print("\t");
    Serial.print(pArry[0]);
  }
  Serial.println();
  
  pArry = qtra.calibratedMinimumOff;
  Serial.print("calibratedMinimumOff    ");
  for (i=0; i<NUMSENSORS; i++) {
    Serial.print("\t");
    Serial.print(pArry[0]);
  }
  Serial.println();
  
  pArry = qtra.calibratedMaximumOff;
  Serial.print("calibratedMaximumOff    ");
  for (i=0; i<NUMSENSORS; i++) {
    Serial.print("\t");
    Serial.print(pArry[0]);
  }
  Serial.println();
  
  delay(10000);
}

void loop() 
{
  int i;
  Serial.println(cnt++);
 
  qtra.readCalibrated(sensors, QTR_EMITTERS_OFF);
  Serial.print("  EMITTERS_OFF  ");
  for (i=0; i<NUMSENSORS; i++) {
    Serial.print("\t");
    Serial.print(sensors[i]);
  }
  Serial.println();
  delay(1000);                  // stop the program for some time



  qtra.readCalibrated(sensors, QTR_EMITTERS_ON);
  Serial.print("  EMITTERS_ON  ");
  for (i=0; i<NUMSENSORS; i++) {
    Serial.print("\t");
    Serial.print(sensors[i]);
  }
  Serial.println();
  
  /*
  delay(1000);                  // stop the program for some time
  
  qtra.readCalibrated(sensors, QTR_EMITTERS_ON_AND_OFF);
  Serial.print("  EMITTERS_ON_OFF  ");
  for (i=0; i<NUMSENSORS; i++) {
    Serial.print("\t");
    Serial.print(sensors[i]);
  }
  Serial.println();
  
  delay(1000);                  // stop the program for some time
  
  line = qtra.readLine(sensors);
  Serial.print("    line = ");
  Serial.print(line);
  Serial.println();
*/
  delay(1000);                  // stop the program for some time
}

These are the results from the Qtr class code:

Starting to Calibrate
..........................................................................................................................................................................................................................................................
Finished calibrating

calibratedMinimumOn    	1023	1023	1023	1023	1023	1023
calibratedMaximumOn    	1023	1023	1023	1023	1023	1023
calibratedMinimumOff    	128	128	128	128	128	128
calibratedMaximumOff    	128	128	128	128	128	128

0
  EMITTERS_OFF  	0	0	0	0	0	0
  EMITTERS_ON  	0	0	0	0	0	0

1
  EMITTERS_OFF  	0	0	0	0	0	0
  EMITTERS_ON  	0	0	0	0	0	0

2
  EMITTERS_OFF  	0	0	0	0	0	0

Hi Ben,

How are we doing with this. Do you want to ask the developer if i can talk to him personally and if so you can email me his address? That might make things go a little quicker?

Best
Phil

You’re right, this library was never tested on a real Arduino, but it was tested on a mega168 microcontroller programmed using the Arduino environment, so the performance should match that of an Arduino. Unfortunately I haven’t had time to fully get to the bottom of this, but it’s the next task on my to-do list. I’ll be working on it tonight and I’ll post tomorrow to let you know what I’ve figured out. I apologize for the delay.

- Ben

Well, I’ve fairly extensively tested the QTR library and it works fine for me. Note that the modification date of the QTR library I’m using is 8/26/08 and it comes as part of the Pololu AVR library package that you can download here.

I wrote the following two programs using the Arduino IDE and programmed them onto a mega168 that has pin 0 (PD0) connected to the sensor’s LEDON (emitter) pin and analog inputs 0 - 3 (PC0 - PC3) connected to sensor outputs 1 - 4 as labeled on the array’s PCB:

Test of raw sensor output:

#include <OrangutanLCD.h>
#include <PololuQTRSensors.h>  

#define NUMSENSORS 4
#define SAMPLES 3
#define EMITTERPIN 0

unsigned int sensors[8]; 
long  cnt = 0;
unsigned int line = 0;
OrangutanLCD lcd;

PololuQTRSensorsAnalog qtra((unsigned char[]) {0, 1, 2, 3}, NUMSENSORS, SAMPLES, EMITTERPIN);  

void setup()
{  
}

void loop() 
{
  int i;
  
  qtra.read(sensors, QTR_EMITTERS_ON);
  lcd.gotoXY(0, 0);
  for (i = 0; i < 4; i++)
  {
    lcd.print(sensors[i] / 103);
    lcd.print(' ');
  }
  
  lcd.gotoXY(0, 1);    
  qtra.read(sensors, QTR_EMITTERS_OFF);
  for (i = 0; i < 4; i++)
  {
    lcd.print(sensors[i] / 103);
    lcd.print(' ');
  }

  delay(100);                  // stop the program for some time
}

Test of calibrated sensor output:

#include <OrangutanLCD.h>
#include <PololuQTRSensors.h>  

#define NUMSENSORS 4
#define SAMPLES 3
#define EMITTERPIN 0

unsigned int sensors[8]; 
long  cnt = 0;
unsigned int line = 0;
OrangutanLCD lcd;

PololuQTRSensorsAnalog qtra((unsigned char[]) {0, 1, 2, 3}, NUMSENSORS, SAMPLES, EMITTERPIN);  

void setup()
{  
  int i;
  lcd.clear();
  lcd.print("...");
  delay(3000);
  lcd.clear();
  lcd.print("calib.");
  for (i = 0; i < 250; i++)
  {
    qtra.calibrate();
    delay(20); 
  }
}

void loop() 
{
  int i;
  
  int position = qtra.readLine(sensors, QTR_EMITTERS_ON);
  lcd.clear();
  lcd.print("pos=");
  lcd.print(position);
  lcd.gotoXY(0, 1);
  for (i = 0; i < 4; i++)
  {
    lcd.print(sensors[i] / 101);
    lcd.print(' ');
  }

  delay(200);                  // stop the program for some time
}

You should be able to make this code work on your end by replacing the lcd methods with serial output calls. I think you either still have an old version of the library or something very strange is going on, because every aspect of these programs works as expected for me.

- Ben

Hello Ben,

I started working with QTR-8RC on Arduino and experienced the same problem.
I do calibration (moving the sensor back and forth close over a white sheet with
a black line), but the values in the array sensor stay zero.
when I try using qtrrc.readLine(sensor); the same with the return value.

However, once I do qtrrc.read(sensor) there are non-zeros in this
array.

Next time you call qtrrc.readLine(sensor) you get the same values.
They change only when you call qtrrc.read(sensor).
It looks like the values are done only locally and not returned.

I have downloaded and installed the
library from Pololu in October, the file PololuQTRSensor.cpp ist of 26.Aug.08 and
the file PololuQTRSensor.h as well. Currently I have employed only
the first five sensors. Here is my full Arduino program:

–Hannes


/*
 Pololu QTR-8RC Reflectance Sensor Array testing
  Hannes Hassler Oct 2008

*/


#include <PololuQTRSensors.h>

#define ledActivatePin 2

#define  no_of_sensors 5

byte sensorPin[] = {3, 4, 5, 6, 7};



unsigned int sensor[no_of_sensors];

// create an object for six QTR-xRC sensors on digital pins 2 to 7    
PololuQTRSensorsRC qtrrc((unsigned char[]) {3, 4, 5, 6, 7}, no_of_sensors);  


void setup()  {
  // define pin modes for tx, rx, led pins:
  
  pinMode(ledActivatePin, OUTPUT);
  digitalWrite(ledActivatePin, HIGH);
  
  for (int i=0;i<no_of_sensors;i++) {
    pinMode(sensorPin[i], INPUT);
  }
  
  
  Serial.begin(9600);  
  
  calibrateSensorPlusComment(qtrrc); 
 
  
}



void calibrateSensor(PololuQTRSensorsRC qtr) {
  // during calibration phase move the sensors over both  
 // reflectance extremes they will encounter in your application:   
   for (int i = 0; i < 250; i++)  {// make the calibration take about 5 seconds     
     qtr.calibrate();  
     delay(20);  
   }  
}



void calibrateSensorPlusComment(PololuQTRSensorsRC qtr) {
  Serial.println("calibration (5 secs)");
  calibrateSensor(qtr);     
  Serial.println("calibration finished"); 
}


int readPosition(PololuQTRSensorsRC qtr) {
  return qtr.readLine(sensor); 
}

void rawRead(PololuQTRSensorsRC qtr) {
  qtr.read(sensor); 
}

void loop() {
  
  
  static int v = 0;  
  static char ch;
  
 
  if (Serial.available()) {    
    
      ch = Serial.read();
    

    switch(ch) {
      case '0'...'9':
        v = v * 10 + ch - '0';
        break;
      case 's':
       Serial.print("sensor:");
       Serial.println(v);
       v = 0;
       break;
       case 'c':       
       calibrateSensorPlusComment(qtrrc); 
       break;
       case 'L':
        digitalWrite(ledActivatePin, LOW);
       break;
       case 'H':
        digitalWrite(ledActivatePin, HIGH);
       break;
       case 'r':
       rawRead(qtrrc);        
       showSensorVals();
       break; 
       case 'l':
       //rawRead(qtrrc);
       int position = qtrrc.readLine(sensor);   
       showPos(position);      
       showSensorVals();
       break; 
       
    } 
  }  
       

}


void showPos(int position) {  
  Serial.print("position:");
  Serial.println(position);
}

void showSensorVals() {
  
  Serial.print("sensor: ");
  for (int i=0;i<no_of_sensors;i++) { 
         Serial.print("\t");    
         Serial.print(i);
         Serial.print("=");
         Serial.print(sensor[i]);
       }
   Serial.println(" ");
  
}

Hi Hannes,

I gave up on it, but if you guys get it working, I might come back and take a look :slight_smile:

Phil

Hello,
Can you try putting in explicit values for the white_line and readMode parameters to both readLine and calibrate? I am worried that somehow these parameters are getting switched in your version of the code. Hopefully we can track down this problem!

Thanks,
-Paul

I have modified my output so that you can see the code how it is called
(in Arduino environment) in the quote window below.
The call-parts I have marked with ::
After the call part you can see the values you get in the sensor array, respectively.

#define  no_of_sensors 8

unsigned int sensor[no_of_sensors];

// create an object for six QTR-xRC sensors on digital pins 3 to 10
PololuQTRSensorsRC qtrrc((unsigned char[]) {3, 4, 5, 6, 7, 8, 9, 10}, no_of_sensors);  

It is the same variable used both for the call
qtrrc.readLine(sensor); and for
qtrrc.read(sensor);

But the contents in it are quite different after these calls.
After the first call of qtrrc.readLine(sensor) you got all values
zero. After the first qtrrc.read(sensor); you get values.
After the second call of qtrrc.readLine(sensor) you get some values too,
but obviously they are just the same ones.
They change only after another call of qtrrc.read(sensor);

Finally I made a call of qtrrc.read(sensor) and put the sensor on the
black line. You notice the high value at sensor 5.

Let me add, for my purposes I am completely content
with the .read(sensor) method and do not need readLine().
I also really like this sensor-array,
because I have build my own with normal
LEDs and fototransistors. I never got so good black-white results
as with Pololu QTR-8RC

Well, if you want to debug this further, please try it with calibrate(QTR_EMITTERS_ON) and readLine(sensors, QTR_EMITTERS_ON, 0) to see if those parameters are causing you trouble. It would also be nice to know if your IR emitters go on when you are running calibrate() or readLine() repeatedly in a loop.

I’m having a similar problem to the others described in this thread.

The sensor this time is a QTR-1A. Here’s the code I’m using:

#include <PololuQTRSensors.h>

int aPin = 0;
int ledPin = 13; 
PololuQTRSensorsAnalog qtr1((unsigned char[]) {0}, 1, 3, 0);

void setup()
{
  Serial.begin(9600);
  pinMode(ledPin, OUTPUT);
  digitalWrite(ledPin, HIGH);
}

void loop()
{
  unsigned int sensors[3];
  int val = 0;
  
  qtr1.read(sensors, QTR_EMITTERS_ON);
  val = analogRead(aPin);
  
  Serial.print("s:");
  Serial.print(sensors[0]);
  Serial.print(":");
  Serial.println(val);
  delay(500);
}

Here’s some console output:

s:1023:328
s:1023:329
s:1023:334
s:1023:328
s:1023:998
s:1023:985
s:1023:794
s:1023:468
s:1023:17
s:1023:19
s:1023:18
s:1023:17
s:1023:247
s:1023:242

The low (<20) values are the sensor over white paper, and the high readings are over a black line. This tells me that the sensor is hooked up correctly. Inspection with a cellphone camera reveals that the IR LED is on constantly, which would also make sense, given that we’re dealing with a QTR-1A.

I’m planning on using a QTR-8RC so will eventually want to move up to using readLine. I figured I’d start with these analog sensors and get them to work first.

I’m running this on an Arduino NG, if that’s relevant. I’m also using arduino-012 software. Is there a chance that the Pololu libraries are not compatible with this version? I’m downloading 011 now, and will post my results with that.

EDIT: Same behavior with arduino-011.

EDIT2: I fired up my QTR-8RC today, and was able to get the read, readCalibrated and readLine methods to work as expected. So, I can make the PololuQTRSensorsRC object work, but not the PololuQTRSensorsAnalog. Good enough for my immediate application, but now that I’ve found this weirdness, I’ve gotta track it down!

Thanks for any help or insight anyone might be able to provide!

Hello.

I’m very glad to hear that you got the RC sensors working under the Arduino environment. I don’t have an Arduino to test on, but I have used the Arduino environment to program the QTR sensor libraries onto mega168s and both the analog and RC libraries have functioned as expected. If you manage to figure out why the analog version isn’t working on your Arduino, please let us know!

- Ben

Had the same problem. Fast and easy way to get things going is to change sources of the library, replacing function PololuQTRSensorsAnalog::readPrivate with following:

void PololuQTRSensorsAnalog::readPrivate(unsigned int *sensor_values)
{
	unsigned char i, j;
	for (j = 0; j < _numSamplesPerSensor; j++)
	{
		for (i = 0; i < _numSensors; i++)
		{
			sensor_values[i] += analogRead(_analogPins[i]);
		}
	}
	
	for (i = 0; i < _numSensors; i++)
		sensor_values[i] = (sensor_values[i] + (_numSamplesPerSensor >> 1)) /
			_numSamplesPerSensor;


}

After that it will work, but only on arduino =)

Hello All,

I am new to this forum and to this area of work (sensors, robotics). I want to use the QTR8RC sensors for a personal project. I am using a PSOC Microcontroller in which pins are limited.

Anyway, I want to be able to hook up the output of the sensors to a hardware shift register so I could have 8 parallel inputs and one output to my microcontroller.

However, I am looking at the instructiions for use and I am a little confused.
The directions are:

  1. Make the I/O an ouput
  2. Delay 10us to let charge
  3. Make the I/O an input
  4. Read Values
  5. and loop this for continuous read.

However, my problem arises in that the hardware shift register has 8 parellel inputs and one output. I am not sure if I will be able to change the Output/Input on the sensors.

Am I reading this correct or will this work without problems? I was under the assumption that I could just power the sensors and create a loop to delay before reading the sensors. Is this not correct? I thought that when the sensor saw black or white would determine if the state of the pin is high/low and then this value would be read and could be shifted through the hardware shift register. Because the shift register is 8bit, it would take 8 counts to shift values through and then this cycle would loop.

Any ideas?

Thanks all and please help me work through this.

Hello,

I don’t think your approach will work. You really need your pins to first charge the capacitor and then time the discharge; that timing won’t really be doable with your setup, either. You could maybe make something happen with the analog (not RC) version of the sensor, but if you just connect to a digital input, you won’t have any say over the thresholds and you won’t get to calibrate for individual sensor variation.

- Jan

A post was split to a new topic: QTR sensor array center point