new
This commit is contained in:
parent
eeb02bdd4f
commit
7a8c6154a9
7 changed files with 1171 additions and 0 deletions
575
arduino/libraries/QTRSensors/QTRSensors.cpp
Executable file
575
arduino/libraries/QTRSensors/QTRSensors.cpp
Executable file
|
@ -0,0 +1,575 @@
|
|||
/*
|
||||
QTRSensors.cpp - Arduino 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).
|
||||
|
||||
* QTRSensorsRC should be used for QTR-1RC and QTR-8RC sensors.
|
||||
* QTRSensorsAnalog should be used for QTR-1A and QTR-8A sensors.
|
||||
*/
|
||||
|
||||
/*
|
||||
* Written by Ben Schmidel et al., October 4, 2010.
|
||||
* Copyright (c) 2008-2012 Pololu Corporation. For more information, see
|
||||
*
|
||||
* http://www.pololu.com
|
||||
* http://forum.pololu.com
|
||||
* http://www.pololu.com/docs/0J19
|
||||
*
|
||||
* 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.
|
||||
*/
|
||||
|
||||
#include <stdlib.h>
|
||||
#include "QTRSensors.h"
|
||||
#include <Arduino.h>
|
||||
|
||||
#define QTR_RC 0
|
||||
#define QTR_A 1
|
||||
|
||||
|
||||
|
||||
// Base class data member initialization (called by derived class init())
|
||||
void QTRSensors::init(unsigned char *pins, unsigned char numSensors,
|
||||
unsigned char emitterPin, unsigned char type)
|
||||
{
|
||||
calibratedMinimumOn=0;
|
||||
calibratedMaximumOn=0;
|
||||
calibratedMinimumOff=0;
|
||||
calibratedMaximumOff=0;
|
||||
|
||||
if (numSensors > QTR_MAX_SENSORS)
|
||||
_numSensors = QTR_MAX_SENSORS;
|
||||
else
|
||||
_numSensors = numSensors;
|
||||
|
||||
if (_pins == 0)
|
||||
{
|
||||
_pins = (unsigned char*)malloc(sizeof(unsigned char)*_numSensors);
|
||||
if (_pins == 0)
|
||||
return;
|
||||
}
|
||||
|
||||
unsigned char i;
|
||||
for (i = 0; i < _numSensors; i++)
|
||||
{
|
||||
_pins[i] = pins[i];
|
||||
}
|
||||
|
||||
_emitterPin = emitterPin;
|
||||
_type = type;
|
||||
}
|
||||
|
||||
|
||||
// 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 QTRSensors::read(unsigned int *sensor_values, unsigned char readMode)
|
||||
{
|
||||
unsigned int off_values[QTR_MAX_SENSORS];
|
||||
unsigned char i;
|
||||
|
||||
if(readMode == QTR_EMITTERS_ON || readMode == QTR_EMITTERS_ON_AND_OFF)
|
||||
emittersOn();
|
||||
|
||||
if (_type == QTR_RC)
|
||||
{
|
||||
((QTRSensorsRC*)this)->readPrivate(sensor_values);
|
||||
emittersOff();
|
||||
if(readMode == QTR_EMITTERS_ON_AND_OFF)
|
||||
((QTRSensorsRC*)this)->readPrivate(off_values);
|
||||
}
|
||||
else
|
||||
{
|
||||
((QTRSensorsAnalog*)this)->readPrivate(sensor_values);
|
||||
emittersOff();
|
||||
if(readMode == QTR_EMITTERS_ON_AND_OFF)
|
||||
((QTRSensorsAnalog*)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 QTRSensors::emittersOff()
|
||||
{
|
||||
if (_emitterPin == QTR_NO_EMITTER_PIN)
|
||||
return;
|
||||
pinMode(_emitterPin, OUTPUT);
|
||||
digitalWrite(_emitterPin, LOW);
|
||||
delayMicroseconds(200);
|
||||
}
|
||||
|
||||
void QTRSensors::emittersOn()
|
||||
{
|
||||
if (_emitterPin == QTR_NO_EMITTER_PIN)
|
||||
return;
|
||||
pinMode(_emitterPin, OUTPUT);
|
||||
digitalWrite(_emitterPin, HIGH);
|
||||
delayMicroseconds(200);
|
||||
}
|
||||
|
||||
// Resets the calibration.
|
||||
void QTRSensors::resetCalibration()
|
||||
{
|
||||
unsigned char i;
|
||||
for(i=0;i<_numSensors;i++)
|
||||
{
|
||||
if(calibratedMinimumOn)
|
||||
calibratedMinimumOn[i] = _maxValue;
|
||||
if(calibratedMinimumOff)
|
||||
calibratedMinimumOff[i] = _maxValue;
|
||||
if(calibratedMaximumOn)
|
||||
calibratedMaximumOn[i] = 0;
|
||||
if(calibratedMaximumOff)
|
||||
calibratedMaximumOff[i] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
// 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 QTRSensors::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 QTRSensors::calibrateOnOrOff(unsigned int **calibratedMinimum,
|
||||
unsigned int **calibratedMaximum,
|
||||
unsigned char readMode)
|
||||
{
|
||||
int i;
|
||||
unsigned int sensor_values[16];
|
||||
unsigned int max_sensor_values[16];
|
||||
unsigned int min_sensor_values[16];
|
||||
|
||||
// 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 QTRSensors::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 QTRSensors::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 constructors
|
||||
QTRSensorsRC::QTRSensorsRC()
|
||||
{
|
||||
calibratedMinimumOn = 0;
|
||||
calibratedMaximumOn = 0;
|
||||
calibratedMinimumOff = 0;
|
||||
calibratedMaximumOff = 0;
|
||||
_pins = 0;
|
||||
}
|
||||
|
||||
QTRSensorsRC::QTRSensorsRC(unsigned char* pins,
|
||||
unsigned char numSensors, unsigned int timeout, unsigned char emitterPin)
|
||||
{
|
||||
calibratedMinimumOn = 0;
|
||||
calibratedMaximumOn = 0;
|
||||
calibratedMinimumOff = 0;
|
||||
calibratedMaximumOff = 0;
|
||||
_pins = 0;
|
||||
|
||||
init(pins, numSensors, timeout, emitterPin);
|
||||
}
|
||||
|
||||
|
||||
// The array 'pins' contains the Arduino pin number for each sensor.
|
||||
|
||||
// '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 16.
|
||||
|
||||
// 'timeout' specifies the length of time in microseconds 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
|
||||
|
||||
// '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),
|
||||
// or if you just want the emitters on all the time and don't want to
|
||||
// use an I/O pin to control it, use a value of 255 (QTR_NO_EMITTER_PIN).
|
||||
void QTRSensorsRC::init(unsigned char* pins,
|
||||
unsigned char numSensors, unsigned int timeout, unsigned char emitterPin)
|
||||
{
|
||||
QTRSensors::init(pins, numSensors, emitterPin, QTR_RC);
|
||||
|
||||
_maxValue = timeout;
|
||||
}
|
||||
|
||||
|
||||
// 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 (as specified in the constructor).
|
||||
void QTRSensorsRC::readPrivate(unsigned int *sensor_values)
|
||||
{
|
||||
unsigned char i;
|
||||
|
||||
if (_pins == 0)
|
||||
return;
|
||||
|
||||
for(i = 0; i < _numSensors; i++)
|
||||
{
|
||||
sensor_values[i] = _maxValue;
|
||||
digitalWrite(_pins[i], HIGH); // make sensor line an output
|
||||
pinMode(_pins[i], OUTPUT); // drive sensor line high
|
||||
}
|
||||
|
||||
delayMicroseconds(10); // charge lines for 10 us
|
||||
|
||||
for(i = 0; i < _numSensors; i++)
|
||||
{
|
||||
pinMode(_pins[i], INPUT); // make sensor line an input
|
||||
digitalWrite(_pins[i], LOW); // important: disable internal pull-up!
|
||||
}
|
||||
|
||||
unsigned long startTime = micros();
|
||||
while (micros() - startTime < _maxValue)
|
||||
{
|
||||
unsigned int time = micros() - startTime;
|
||||
for (i = 0; i < _numSensors; i++)
|
||||
{
|
||||
if (digitalRead(_pins[i]) == LOW && time < sensor_values[i])
|
||||
sensor_values[i] = time;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
// Derived Analog class constructors
|
||||
QTRSensorsAnalog::QTRSensorsAnalog()
|
||||
{
|
||||
calibratedMinimumOn = 0;
|
||||
calibratedMaximumOn = 0;
|
||||
calibratedMinimumOff = 0;
|
||||
calibratedMaximumOff = 0;
|
||||
_pins = 0;
|
||||
}
|
||||
|
||||
QTRSensorsAnalog::QTRSensorsAnalog(unsigned char* pins,
|
||||
unsigned char numSensors, unsigned char numSamplesPerSensor,
|
||||
unsigned char emitterPin)
|
||||
{
|
||||
calibratedMinimumOn = 0;
|
||||
calibratedMaximumOn = 0;
|
||||
calibratedMinimumOff = 0;
|
||||
calibratedMaximumOff = 0;
|
||||
_pins = 0;
|
||||
|
||||
init(pins, 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.
|
||||
|
||||
// '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 16.
|
||||
|
||||
// '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 it takes about 100 us to
|
||||
// perform a single analog-to-digital conversion, so:
|
||||
// if numSamplesPerSensor is 4 and numSensors is 6, it will take
|
||||
// 4 * 6 * 100 us = ~2.5 ms to perform a full readLine().
|
||||
// Increasing this parameter increases noise suppression at the cost of
|
||||
// sample rate. The recommended value is 4.
|
||||
|
||||
// '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),
|
||||
// or if you just want the emitters on all the time and don't want to
|
||||
// use an I/O pin to control it, use a value of 255 (QTR_NO_EMITTER_PIN).
|
||||
void QTRSensorsAnalog::init(unsigned char* pins,
|
||||
unsigned char numSensors, unsigned char numSamplesPerSensor,
|
||||
unsigned char emitterPin)
|
||||
{
|
||||
QTRSensors::init(pins, numSensors, emitterPin, QTR_A);
|
||||
|
||||
_numSamplesPerSensor = numSamplesPerSensor;
|
||||
_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 QTRSensorsAnalog::readPrivate(unsigned int *sensor_values)
|
||||
{
|
||||
unsigned char i, j;
|
||||
|
||||
if (_pins == 0)
|
||||
return;
|
||||
|
||||
// reset the values
|
||||
for(i = 0; i < _numSensors; i++)
|
||||
sensor_values[i] = 0;
|
||||
|
||||
for (j = 0; j < _numSamplesPerSensor; j++)
|
||||
{
|
||||
for (i = 0; i < _numSensors; i++)
|
||||
{
|
||||
sensor_values[i] += analogRead(_pins[i]); // add 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;
|
||||
}
|
||||
|
||||
// the destructor frees up allocated memory
|
||||
QTRSensors::~QTRSensors()
|
||||
{
|
||||
if (_pins)
|
||||
free(_pins);
|
||||
if(calibratedMaximumOn)
|
||||
free(calibratedMaximumOn);
|
||||
if(calibratedMaximumOff)
|
||||
free(calibratedMaximumOff);
|
||||
if(calibratedMinimumOn)
|
||||
free(calibratedMinimumOn);
|
||||
if(calibratedMinimumOff)
|
||||
free(calibratedMinimumOff);
|
||||
}
|
282
arduino/libraries/QTRSensors/QTRSensors.h
Executable file
282
arduino/libraries/QTRSensors/QTRSensors.h
Executable file
|
@ -0,0 +1,282 @@
|
|||
/*
|
||||
QTRSensors.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).
|
||||
|
||||
* QTRSensorsRC should be used for QTR-1RC and QTR-8RC sensors.
|
||||
* QTRSensorsAnalog should be used for QTR-1A and QTR-8A sensors.
|
||||
*/
|
||||
|
||||
/*
|
||||
* Written by Ben Schmidel et al., October 4, 2010
|
||||
* Copyright (c) 2008-2012 Pololu Corporation. For more information, see
|
||||
*
|
||||
* http://www.pololu.com
|
||||
* http://forum.pololu.com
|
||||
* http://www.pololu.com/docs/0J19
|
||||
*
|
||||
* 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 QTRSensors_h
|
||||
#define QTRSensors_h
|
||||
|
||||
#define QTR_EMITTERS_OFF 0
|
||||
#define QTR_EMITTERS_ON 1
|
||||
#define QTR_EMITTERS_ON_AND_OFF 2
|
||||
|
||||
#define QTR_NO_EMITTER_PIN 255
|
||||
|
||||
#define QTR_MAX_SENSORS 16
|
||||
|
||||
// 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 QTRSensors
|
||||
{
|
||||
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);
|
||||
|
||||
// Resets all calibration that has been done.
|
||||
void resetCalibration();
|
||||
|
||||
// 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;
|
||||
|
||||
~QTRSensors();
|
||||
|
||||
protected:
|
||||
|
||||
QTRSensors()
|
||||
{
|
||||
|
||||
};
|
||||
|
||||
void init(unsigned char *pins, unsigned char numSensors, unsigned char emitterPin,
|
||||
unsigned char type);
|
||||
|
||||
unsigned char *_pins;
|
||||
unsigned char _numSensors;
|
||||
unsigned char _emitterPin;
|
||||
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 QTRSensorsRC : public QTRSensors
|
||||
{
|
||||
// allows the base QTRSensors class to access this class'
|
||||
// readPrivate()
|
||||
friend class QTRSensors;
|
||||
|
||||
public:
|
||||
|
||||
// if this constructor is used, the user must call init() before using
|
||||
// the methods in this class
|
||||
QTRSensorsRC();
|
||||
|
||||
// this constructor just calls init()
|
||||
QTRSensorsRC(unsigned char* pins, unsigned char numSensors,
|
||||
unsigned int timeout = 4000, unsigned char emitterPin = 255);
|
||||
|
||||
// The array 'pins' contains the Arduino pin number for each sensor.
|
||||
|
||||
// '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 16.
|
||||
|
||||
// 'timeout' specifies the length of time in microseconds 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
|
||||
|
||||
// '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),
|
||||
// or if you just want the emitters on all the time and don't want to
|
||||
// use an I/O pin to control it, use a value of 255 (QTR_NO_EMITTER_PIN).
|
||||
void init(unsigned char* pins, unsigned char numSensors,
|
||||
unsigned int timeout = 2000, unsigned char emitterPin = QTR_NO_EMITTER_PIN);
|
||||
|
||||
|
||||
|
||||
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 microseconds.
|
||||
void readPrivate(unsigned int *sensor_values);
|
||||
};
|
||||
|
||||
|
||||
|
||||
// Object to be used for QTR-1A and QTR-8A sensors
|
||||
class QTRSensorsAnalog : public QTRSensors
|
||||
{
|
||||
// allows the base QTRSensors class to access this class
|
||||
// readPrivate()
|
||||
friend class QTRSensors;
|
||||
|
||||
public:
|
||||
|
||||
// if this constructor is used, the user must call init() before using
|
||||
// the methods in this class
|
||||
QTRSensorsAnalog();
|
||||
|
||||
// this constructor just calls init()
|
||||
QTRSensorsAnalog(unsigned char* pins,
|
||||
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.
|
||||
|
||||
// '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 16.
|
||||
|
||||
// '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 it takes about 100 us to
|
||||
// perform a single analog-to-digital conversion, so:
|
||||
// if numSamplesPerSensor is 4 and numSensors is 6, it will take
|
||||
// 4 * 6 * 100 us = ~2.5 ms to perform a full readLine().
|
||||
// Increasing this parameter increases noise suppression at the cost of
|
||||
// sample rate. The recommended value is 4.
|
||||
|
||||
// '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),
|
||||
// or if you just want the emitters on all the time and don't want to
|
||||
// use an I/O pin to control it, use a value of 255 (QTR_NO_EMITTER_PIN).
|
||||
void init(unsigned char* analogPins, unsigned char numSensors,
|
||||
unsigned char numSamplesPerSensor = 4, unsigned char emitterPin = QTR_NO_EMITTER_PIN);
|
||||
|
||||
|
||||
|
||||
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 _numSamplesPerSensor;
|
||||
};
|
||||
|
||||
|
||||
#endif
|
91
arduino/libraries/QTRSensors/examples/QTRAExample/QTRAExample.ino
Executable file
91
arduino/libraries/QTRSensors/examples/QTRAExample/QTRAExample.ino
Executable file
|
@ -0,0 +1,91 @@
|
|||
#include <QTRSensors.h>
|
||||
|
||||
// This example is designed for use with six QTR-1A sensors or the first six sensors of a
|
||||
// QTR-8A module. These reflectance sensors should be connected to analog inputs 0 to 5.
|
||||
// The QTR-8A's emitter control pin (LEDON) can optionally be connected to digital pin 2,
|
||||
// or you can leave it disconnected and change the EMITTER_PIN #define below from 2 to
|
||||
// QTR_NO_EMITTER_PIN.
|
||||
|
||||
// The setup phase of this example calibrates the sensor for ten seconds and turns on
|
||||
// the LED built in to the Arduino 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.
|
||||
// If you want to skip the calibration phase, you can get the raw sensor readings
|
||||
// (analog voltage readings from 0 to 1023) by calling qtra.read(sensorValues) instead of
|
||||
// qtra.readLine(sensorValues).
|
||||
|
||||
// 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.
|
||||
|
||||
|
||||
#define NUM_SENSORS 6 // number of sensors used
|
||||
#define NUM_SAMPLES_PER_SENSOR 4 // average 4 analog samples per sensor reading
|
||||
#define EMITTER_PIN 2 // emitter is controlled by digital pin 2
|
||||
|
||||
// sensors 0 through 5 are connected to analog inputs 0 through 5, respectively
|
||||
QTRSensorsAnalog qtra((unsigned char[]) {0, 1, 2, 3, 4, 5},
|
||||
NUM_SENSORS, NUM_SAMPLES_PER_SENSOR, EMITTER_PIN);
|
||||
unsigned int sensorValues[NUM_SENSORS];
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
delay(500);
|
||||
pinMode(13, OUTPUT);
|
||||
digitalWrite(13, HIGH); // turn on Arduino's LED to indicate we are in calibration mode
|
||||
for (int i = 0; i < 400; i++) // make the calibration take about 10 seconds
|
||||
{
|
||||
qtra.calibrate(); // reads all sensors 10 times at 2.5 ms per six sensors (i.e. ~25 ms per call)
|
||||
}
|
||||
digitalWrite(13, 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 (int i = 0; i < NUM_SENSORS; i++)
|
||||
{
|
||||
Serial.print(qtra.calibratedMinimumOn[i]);
|
||||
Serial.print(' ');
|
||||
}
|
||||
Serial.println();
|
||||
|
||||
// print the calibration maximum values measured when emitters were on
|
||||
for (int i = 0; i < NUM_SENSORS; i++)
|
||||
{
|
||||
Serial.print(qtra.calibratedMaximumOn[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
|
||||
// To get raw sensor values, call:
|
||||
// qtra.read(sensorValues); instead of unsigned int position = qtra.readLine(sensorValues);
|
||||
unsigned int position = qtra.readLine(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 (unsigned char i = 0; i < NUM_SENSORS; i++)
|
||||
{
|
||||
Serial.print(sensorValues[i]);
|
||||
Serial.print('\t');
|
||||
}
|
||||
//Serial.println(); // uncomment this line if you are using raw values
|
||||
Serial.println(position); // comment this line out if you are using raw values
|
||||
|
||||
delay(250);
|
||||
}
|
|
@ -0,0 +1,48 @@
|
|||
#include <QTRSensors.h>
|
||||
|
||||
// This example is designed for use with six QTR-1A sensors or the first six sensors of a
|
||||
// QTR-8A module. These reflectance sensors should be connected to analog inputs 0 to 5.
|
||||
// The QTR-8A's emitter control pin (LEDON) can optionally be connected to digital pin 2,
|
||||
// or you can leave it disconnected and change the EMITTER_PIN #define below from 2 to
|
||||
// QTR_NO_EMITTER_PIN.
|
||||
|
||||
// The main loop of the example reads the raw sensor values (uncalibrated).
|
||||
// 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 1023 (minimum reflectance).
|
||||
|
||||
|
||||
#define NUM_SENSORS 6 // number of sensors used
|
||||
#define NUM_SAMPLES_PER_SENSOR 4 // average 4 analog samples per sensor reading
|
||||
#define EMITTER_PIN 2 // emitter is controlled by digital pin 2
|
||||
|
||||
// sensors 0 through 5 are connected to analog inputs 0 through 5, respectively
|
||||
QTRSensorsAnalog qtra((unsigned char[]) {0, 1, 2, 3, 4, 5},
|
||||
NUM_SENSORS, NUM_SAMPLES_PER_SENSOR, EMITTER_PIN);
|
||||
unsigned int sensorValues[NUM_SENSORS];
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
delay(500);
|
||||
Serial.begin(9600); // set the data rate in bits per second for serial data transmission
|
||||
delay(1000);
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
// read raw sensor values
|
||||
qtra.read(sensorValues);
|
||||
|
||||
// print the sensor values as numbers from 0 to 1023, where 0 means maximum reflectance and
|
||||
// 1023 means minimum reflectance
|
||||
for (unsigned char i = 0; i < NUM_SENSORS; i++)
|
||||
{
|
||||
Serial.print(sensorValues[i]);
|
||||
Serial.print('\t'); // tab to format the raw data into columns in the Serial monitor
|
||||
}
|
||||
Serial.println();
|
||||
|
||||
delay(250);
|
||||
}
|
91
arduino/libraries/QTRSensors/examples/QTRRCExample/QTRRCExample.ino
Executable file
91
arduino/libraries/QTRSensors/examples/QTRRCExample/QTRRCExample.ino
Executable file
|
@ -0,0 +1,91 @@
|
|||
#include <QTRSensors.h>
|
||||
|
||||
// This example is designed for use with eight QTR-1RC sensors or the eight sensors of a
|
||||
// QTR-8RC module. These reflectance sensors should be connected to digital inputs 3 to 10.
|
||||
// The QTR-8RC's emitter control pin (LEDON) can optionally be connected to digital pin 2,
|
||||
// or you can leave it disconnected and change the EMITTER_PIN #define below from 2 to
|
||||
// QTR_NO_EMITTER_PIN.
|
||||
|
||||
// The setup phase of this example calibrates the sensor for ten seconds and turns on
|
||||
// the LED built in to the Arduino 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.
|
||||
// If you want to skip the calibration phase, you can get the raw sensor readings
|
||||
// (pulse times from 0 to 2500 us) by calling qtrrc.read(sensorValues) instead of
|
||||
// qtrrc.readLine(sensorValues).
|
||||
|
||||
// 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.
|
||||
|
||||
|
||||
#define NUM_SENSORS 8 // number of sensors used
|
||||
#define TIMEOUT 2500 // waits for 2500 microseconds for sensor outputs to go low
|
||||
#define EMITTER_PIN 2 // emitter is controlled by digital pin 2
|
||||
|
||||
// sensors 0 through 7 are connected to digital pins 3 through 10, respectively
|
||||
QTRSensorsRC qtrrc((unsigned char[]) {3, 4, 5, 6, 7, 8, 9, 10},
|
||||
NUM_SENSORS, TIMEOUT, EMITTER_PIN);
|
||||
unsigned int sensorValues[NUM_SENSORS];
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
delay(500);
|
||||
pinMode(13, OUTPUT);
|
||||
digitalWrite(13, HIGH); // turn on Arduino's LED to indicate we are in calibration mode
|
||||
for (int i = 0; i < 400; i++) // make the calibration take about 10 seconds
|
||||
{
|
||||
qtrrc.calibrate(); // reads all sensors 10 times at 2500 us per read (i.e. ~25 ms per call)
|
||||
}
|
||||
digitalWrite(13, 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 (int i = 0; i < NUM_SENSORS; i++)
|
||||
{
|
||||
Serial.print(qtrrc.calibratedMinimumOn[i]);
|
||||
Serial.print(' ');
|
||||
}
|
||||
Serial.println();
|
||||
|
||||
// print the calibration maximum values measured when emitters were on
|
||||
for (int i = 0; i < NUM_SENSORS; i++)
|
||||
{
|
||||
Serial.print(qtrrc.calibratedMaximumOn[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
|
||||
// To get raw sensor values, call:
|
||||
// qtrrc.read(sensorValues); instead of unsigned int position = qtrrc.readLine(sensorValues);
|
||||
unsigned int position = qtrrc.readLine(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 (unsigned char i = 0; i < NUM_SENSORS; i++)
|
||||
{
|
||||
Serial.print(sensorValues[i]);
|
||||
Serial.print('\t');
|
||||
}
|
||||
//Serial.println(); // uncomment this line if you are using raw values
|
||||
Serial.println(position); // comment this line out if you are using raw values
|
||||
|
||||
delay(250);
|
||||
}
|
|
@ -0,0 +1,48 @@
|
|||
#include <QTRSensors.h>
|
||||
|
||||
// This example is designed for use with eight QTR-1RC sensors or the eight sensors of a
|
||||
// QTR-8RC module. These reflectance sensors should be connected to digital inputs 3 to 10.
|
||||
// The QTR-8RC's emitter control pin (LEDON) can optionally be connected to digital pin 2,
|
||||
// or you can leave it disconnected and change the EMITTER_PIN #define below from 2 to
|
||||
// QTR_NO_EMITTER_PIN.
|
||||
|
||||
// The main loop of the example reads the raw sensor values (uncalibrated).
|
||||
// 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 2500 (minimum reflectance).
|
||||
|
||||
|
||||
#define NUM_SENSORS 8 // number of sensors used
|
||||
#define TIMEOUT 2500 // waits for 2500 microseconds for sensor outputs to go low
|
||||
#define EMITTER_PIN 2 // emitter is controlled by digital pin 2
|
||||
|
||||
// sensors 0 through 7 are connected to digital pins 3 through 10, respectively
|
||||
QTRSensorsRC qtrrc((unsigned char[]) {3, 4, 5, 6, 7, 8, 9, 10},
|
||||
NUM_SENSORS, TIMEOUT, EMITTER_PIN);
|
||||
unsigned int sensorValues[NUM_SENSORS];
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
delay(500);
|
||||
Serial.begin(9600); // set the data rate in bits per second for serial data transmission
|
||||
delay(1000);
|
||||
}
|
||||
|
||||
|
||||
void loop()
|
||||
{
|
||||
// read raw sensor values
|
||||
qtrrc.read(sensorValues);
|
||||
|
||||
// print the sensor values as numbers from 0 to 2500, where 0 means maximum reflectance and
|
||||
// 1023 means minimum reflectance
|
||||
for (unsigned char i = 0; i < NUM_SENSORS; i++)
|
||||
{
|
||||
Serial.print(sensorValues[i]);
|
||||
Serial.print('\t'); // tab to format the raw data into columns in the Serial monitor
|
||||
}
|
||||
Serial.println();
|
||||
|
||||
delay(250);
|
||||
}
|
36
arduino/libraries/QTRSensors/keywords.txt
Executable file
36
arduino/libraries/QTRSensors/keywords.txt
Executable file
|
@ -0,0 +1,36 @@
|
|||
#######################################
|
||||
# Syntax Coloring Map QTRSensors
|
||||
#######################################
|
||||
|
||||
#######################################
|
||||
# Datatypes (KEYWORD1)
|
||||
#######################################
|
||||
|
||||
QTRSensorsAnalog KEYWORD1
|
||||
QTRSensorsRC KEYWORD1
|
||||
QTRSensors KEYWORD1
|
||||
|
||||
#######################################
|
||||
# Methods and Functions (KEYWORD2)
|
||||
#######################################
|
||||
|
||||
read KEYWORD2
|
||||
emittersOff KEYWORD2
|
||||
emittersOn KEYWORD2
|
||||
calibrate KEYWORD2
|
||||
readCalibrated KEYWORD2
|
||||
readLine KEYWORD2
|
||||
calibratedMinimumOn KEYWORD2
|
||||
calibratedMaximumOn KEYWORD2
|
||||
calibratedMinimumOff KEYWORD2
|
||||
calibratedMaximumOff KEYWORD2
|
||||
init KEYWORD2
|
||||
|
||||
#######################################
|
||||
# Constants (LITERAL1)
|
||||
#######################################
|
||||
|
||||
QTR_EMITTERS_OFF LITERAL1
|
||||
QTR_EMITTERS_ON LITERAL1
|
||||
QTR_EMITTERS_ON_AND_OFF LITERAL1
|
||||
QTR_NO_EMITTER_PIN LITERAL1
|
Loading…
Add table
Reference in a new issue