A port of the pololu header from arduino to mbed

Dependencies:   PololuQTRSensors

source for original arduino library: https://github.com/pololu/zumo-shield/tree/master/ZumoReflectanceSensorArray

Committer:
I_failed_Cpp
Date:
Wed Oct 18 15:45:07 2017 +0000
Revision:
3:e3afbfd0a71c
Parent:
2:4aa1484fa679
Down to one error left to fix:; ; Error: No instance of overloaded function "ZumoReflectanceSensorArray::init" matches the argument list in "main.cpp", Line: 29, Col: 25;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
I_failed_Cpp 0:4c5986aedbfc 1 /*! \file ZumoReflectanceSensorArray.h
I_failed_Cpp 0:4c5986aedbfc 2 *
I_failed_Cpp 0:4c5986aedbfc 3 * See the ZumoReflectanceSensorArray class reference for more information about
I_failed_Cpp 0:4c5986aedbfc 4 * this library.
I_failed_Cpp 0:4c5986aedbfc 5 *
I_failed_Cpp 0:4c5986aedbfc 6 * \class ZumoReflectanceSensorArray ZumoReflectanceSensorArray.h
I_failed_Cpp 0:4c5986aedbfc 7 * \brief Read from reflectance sensor array
I_failed_Cpp 0:4c5986aedbfc 8 *
I_failed_Cpp 0:4c5986aedbfc 9 * The ZumoReflectanceSensorArray library provides an interface for using a
I_failed_Cpp 0:4c5986aedbfc 10 * [Zumo Reflectance Sensor Array](http://www.pololu.com/product/1419) connected
I_failed_Cpp 0:4c5986aedbfc 11 * to a Zumo robot. The library provides access to the raw sensor values as well
I_failed_Cpp 0:4c5986aedbfc 12 * as to high level functions including calibration and line-tracking.
I_failed_Cpp 0:4c5986aedbfc 13 *
I_failed_Cpp 0:4c5986aedbfc 14 * For calibration, memory is allocated using the `malloc()` function. This
I_failed_Cpp 0:4c5986aedbfc 15 * conserves RAM: if all six sensors are calibrated with the emitters both on
I_failed_Cpp 0:4c5986aedbfc 16 * and off, a total of 48 bytes is dedicated to storing calibration values.
I_failed_Cpp 0:4c5986aedbfc 17 * However, for an application where only two sensors are used, and the
I_failed_Cpp 0:4c5986aedbfc 18 * emitters are always on during reads, only 4 bytes are required.
I_failed_Cpp 0:4c5986aedbfc 19 *
I_failed_Cpp 0:4c5986aedbfc 20 * Internally, this library uses all standard Arduino functions such as
I_failed_Cpp 0:4c5986aedbfc 21 * `micros()` for timing and `digitalRead()` for getting the sensor values, so
I_failed_Cpp 0:4c5986aedbfc 22 * it should work on all Arduinos without conflicting with other libraries.
I_failed_Cpp 0:4c5986aedbfc 23 *
I_failed_Cpp 0:4c5986aedbfc 24 * ### Calibration ###
I_failed_Cpp 0:4c5986aedbfc 25 *
I_failed_Cpp 0:4c5986aedbfc 26 * This library allows you to use the `calibrate()` method to easily calibrate
I_failed_Cpp 0:4c5986aedbfc 27 * your sensors for the particular conditions it will encounter. Calibrating
I_failed_Cpp 0:4c5986aedbfc 28 * your sensors can lead to substantially more reliable sensor readings, which
I_failed_Cpp 0:4c5986aedbfc 29 * in turn can help simplify your code. As such, we recommend you build a
I_failed_Cpp 0:4c5986aedbfc 30 * calibration phase into your Zumo's initialization routine. This can be as
I_failed_Cpp 0:4c5986aedbfc 31 * simple as a fixed duration over which you repeatedly call the `calibrate()`
I_failed_Cpp 0:4c5986aedbfc 32 * method.
I_failed_Cpp 0:4c5986aedbfc 33 *
I_failed_Cpp 0:4c5986aedbfc 34 * During this calibration phase, you will need to expose each of your
I_failed_Cpp 0:4c5986aedbfc 35 * reflectance sensors to the lightest and darkest readings they will encounter.
I_failed_Cpp 0:4c5986aedbfc 36 * For example, if your Zumo is programmed to be a line follower, you will want
I_failed_Cpp 0:4c5986aedbfc 37 * to slide it across the line during the calibration phase so the each sensor
I_failed_Cpp 0:4c5986aedbfc 38 * can get a reading of how dark the line is and how light the ground is (or you
I_failed_Cpp 0:4c5986aedbfc 39 * can program it to automatically turn back and forth to pass all of the
I_failed_Cpp 0:4c5986aedbfc 40 * sensors over the line). The **SensorCalibration** example included with this
I_failed_Cpp 0:4c5986aedbfc 41 * library demonstrates a calibration routine.
I_failed_Cpp 0:4c5986aedbfc 42 *
I_failed_Cpp 0:4c5986aedbfc 43 * ### Reading the sensors
I_failed_Cpp 0:4c5986aedbfc 44 *
I_failed_Cpp 0:4c5986aedbfc 45 *
I_failed_Cpp 0:4c5986aedbfc 46 * This library gives you a number of different ways to read the sensors.
I_failed_Cpp 0:4c5986aedbfc 47 *
I_failed_Cpp 0:4c5986aedbfc 48 * - You can request raw sensor values using the `read()` method.
I_failed_Cpp 0:4c5986aedbfc 49 *
I_failed_Cpp 0:4c5986aedbfc 50 * - You can request calibrated sensor values using the `readCalibrated()`
I_failed_Cpp 0:4c5986aedbfc 51 * method. Calibrated sensor values will always range from 0 to 1000, with the
I_failed_Cpp 0:4c5986aedbfc 52 * extreme values corresponding to the most and least reflective surfaces
I_failed_Cpp 0:4c5986aedbfc 53 * encountered during calibration.
I_failed_Cpp 0:4c5986aedbfc 54 *
I_failed_Cpp 0:4c5986aedbfc 55 * - For line-detection applications, you can request the line location using
I_failed_Cpp 0:4c5986aedbfc 56 * the `readLine()` method. This function provides calibrated values
I_failed_Cpp 0:4c5986aedbfc 57 * for each sensor and returns an integer that tells you where it thinks the
I_failed_Cpp 0:4c5986aedbfc 58 * line is.
I_failed_Cpp 0:4c5986aedbfc 59 *
I_failed_Cpp 0:4c5986aedbfc 60 * ### Class Inheritance ###
I_failed_Cpp 0:4c5986aedbfc 61 *
I_failed_Cpp 0:4c5986aedbfc 62 * The ZumoReflectanceSensorArray class is derived from the QTRSensorsRC class,
I_failed_Cpp 0:4c5986aedbfc 63 * which is in turn derived from the QTRSensors base class. The QTRSensorsRC and
I_failed_Cpp 0:4c5986aedbfc 64 * QTRSensors classes are part of the \ref QTRSensors.h "QTRSensors" library,
I_failed_Cpp 0:4c5986aedbfc 65 * which provides more general functionality for working with reflectance
I_failed_Cpp 0:4c5986aedbfc 66 * sensors and is included in the Zumo Shield libraries as a dependency for this
I_failed_Cpp 0:4c5986aedbfc 67 * library.
I_failed_Cpp 0:4c5986aedbfc 68 *
I_failed_Cpp 0:4c5986aedbfc 69 * We recommend using the ZumoReflectanceSensorArray library instead of
I_failed_Cpp 0:4c5986aedbfc 70 * the \ref QTRSensors.h "QTRSensors" library when programming an Arduino on a
I_failed_Cpp 0:4c5986aedbfc 71 * Zumo. For documentation specific to the %QTRSensors library, please see its
I_failed_Cpp 0:4c5986aedbfc 72 * [user's guide](http://www.pololu.com/docs/0J19) on Pololu's website.
I_failed_Cpp 0:4c5986aedbfc 73 */
I_failed_Cpp 0:4c5986aedbfc 74
I_failed_Cpp 0:4c5986aedbfc 75 #ifndef ZumoReflectanceSensorArray_h
I_failed_Cpp 0:4c5986aedbfc 76 #define ZumoReflectanceSensorArray_h
I_failed_Cpp 0:4c5986aedbfc 77
I_failed_Cpp 0:4c5986aedbfc 78 #include "QTRSensors.h"
I_failed_Cpp 0:4c5986aedbfc 79 #include <mbed.h>
I_failed_Cpp 0:4c5986aedbfc 80
I_failed_Cpp 0:4c5986aedbfc 81 /*
I_failed_Cpp 0:4c5986aedbfc 82 #if defined(__NUCLEO__) //need to check actual board/processor name
I_failed_Cpp 0:4c5986aedbfc 83 // Nucleo Board
I_failed_Cpp 0:4c5986aedbfc 84 #define ZUMO_SENSOR_ARRAY_DEFAULT_EMITTER_PIN PA4 //need to check actual pin number/name
I_failed_Cpp 0:4c5986aedbfc 85 */
I_failed_Cpp 0:4c5986aedbfc 86 #if defined(__AVR_ATmega32U4__)
I_failed_Cpp 0:4c5986aedbfc 87 // Arduino Leonardo
I_failed_Cpp 0:4c5986aedbfc 88 #define ZUMO_SENSOR_ARRAY_DEFAULT_EMITTER_PIN A4
I_failed_Cpp 0:4c5986aedbfc 89 #elif defined(TARGET_NUCLEO_F103RB)
I_failed_Cpp 0:4c5986aedbfc 90 // Nucleo F103RB
I_failed_Cpp 0:4c5986aedbfc 91 #define ZUMO_SENSOR_ARRAY_DEFAULT_EMITTER_PIN PC_1 //or PA_10???
I_failed_Cpp 0:4c5986aedbfc 92 #else
I_failed_Cpp 0:4c5986aedbfc 93 // Arduino UNO and other ATmega328P/168 Arduinos
I_failed_Cpp 0:4c5986aedbfc 94 #define ZUMO_SENSOR_ARRAY_DEFAULT_EMITTER_PIN 2
I_failed_Cpp 0:4c5986aedbfc 95 #endif
I_failed_Cpp 0:4c5986aedbfc 96
I_failed_Cpp 0:4c5986aedbfc 97 class ZumoReflectanceSensorArray : public QTRSensorsRC
I_failed_Cpp 0:4c5986aedbfc 98 {
I_failed_Cpp 0:4c5986aedbfc 99 public:
I_failed_Cpp 0:4c5986aedbfc 100
I_failed_Cpp 0:4c5986aedbfc 101 /*! \brief Minimal constructor.
I_failed_Cpp 0:4c5986aedbfc 102 *
I_failed_Cpp 0:4c5986aedbfc 103 * This version of the constructor performs no initialization. If it is used,
I_failed_Cpp 0:4c5986aedbfc 104 * the user must call init() before using the methods in this class.
I_failed_Cpp 0:4c5986aedbfc 105 */
I_failed_Cpp 0:4c5986aedbfc 106 ZumoReflectanceSensorArray() {}
I_failed_Cpp 0:4c5986aedbfc 107
I_failed_Cpp 0:4c5986aedbfc 108 /*! \brief Constructor; initializes with given emitter pin and defaults for
I_failed_Cpp 0:4c5986aedbfc 109 * other settings.
I_failed_Cpp 0:4c5986aedbfc 110 *
I_failed_Cpp 0:4c5986aedbfc 111 * \param emitterPin Pin that turns IR emitters on or off.
I_failed_Cpp 0:4c5986aedbfc 112 *
I_failed_Cpp 2:4aa1484fa679 113 * This constructor calls `init(PinName emitterPin)` with the specified
I_failed_Cpp 0:4c5986aedbfc 114 * emitter pin and default values for other settings.
I_failed_Cpp 0:4c5986aedbfc 115 */
I_failed_Cpp 2:4aa1484fa679 116 ZumoReflectanceSensorArray(PinName emitterPin){
I_failed_Cpp 0:4c5986aedbfc 117 init(emitterPin);
I_failed_Cpp 0:4c5986aedbfc 118 }
I_failed_Cpp 0:4c5986aedbfc 119
I_failed_Cpp 0:4c5986aedbfc 120 /*! \brief Constructor; initializes with all settings as given.
I_failed_Cpp 0:4c5986aedbfc 121 *
I_failed_Cpp 0:4c5986aedbfc 122 * \param pins Array of pin numbers for sensors.
I_failed_Cpp 0:4c5986aedbfc 123 * \param numSensors Number of sensors.
I_failed_Cpp 0:4c5986aedbfc 124 * \param timeout Maximum duration of reflectance reading in microseconds.
I_failed_Cpp 0:4c5986aedbfc 125 * \param emitterPin Pin that turns IR emitters on or off.
I_failed_Cpp 0:4c5986aedbfc 126 *
I_failed_Cpp 3:e3afbfd0a71c 127 * This constructor calls `init(PinName * pins, unsigned char
I_failed_Cpp 3:e3afbfd0a71c 128 * numSensors, unsigned int timeout, PinName emitterPin)` with all
I_failed_Cpp 0:4c5986aedbfc 129 * settings as given.
I_failed_Cpp 0:4c5986aedbfc 130 */
I_failed_Cpp 0:4c5986aedbfc 131 ZumoReflectanceSensorArray(PinName *pins, unsigned char numSensors, unsigned int timeout = 2000, PinName emitterPin = ZUMO_SENSOR_ARRAY_DEFAULT_EMITTER_PIN){
I_failed_Cpp 0:4c5986aedbfc 132 QTRSensorsRC::init(pins, numSensors, timeout, emitterPin);
I_failed_Cpp 0:4c5986aedbfc 133 }
I_failed_Cpp 0:4c5986aedbfc 134
I_failed_Cpp 0:4c5986aedbfc 135 /*! \brief Initializes with given emitter pin and and defaults for other
I_failed_Cpp 0:4c5986aedbfc 136 * settings.
I_failed_Cpp 0:4c5986aedbfc 137 *
I_failed_Cpp 0:4c5986aedbfc 138 * \param emitterPin Pin that turns IR emitters on or off.
I_failed_Cpp 0:4c5986aedbfc 139 *
I_failed_Cpp 0:4c5986aedbfc 140 * This function initializes the ZumoReflectanceSensorArray object with the
I_failed_Cpp 0:4c5986aedbfc 141 * specified emitter pin. The other settings are set to default values: all
I_failed_Cpp 0:4c5986aedbfc 142 * six sensors on the array are active, and a timeout of 2000 microseconds is
I_failed_Cpp 0:4c5986aedbfc 143 * used.
I_failed_Cpp 0:4c5986aedbfc 144 *
I_failed_Cpp 0:4c5986aedbfc 145 * \a emitterPin is the Arduino digital pin that controls whether the IR LEDs
I_failed_Cpp 0:4c5986aedbfc 146 * are on or off. This pin is optional; if a valid pin is specified, the
I_failed_Cpp 0:4c5986aedbfc 147 * emitters will only be turned on during a reading. If \a emitterPin is not
I_failed_Cpp 0:4c5986aedbfc 148 * specified, the emitters will be controlled with pin 2 on the Uno (and other
I_failed_Cpp 0:4c5986aedbfc 149 * ATmega328/168 boards) or pin A4 on the Leonardo (and other ATmega32U4
I_failed_Cpp 0:4c5986aedbfc 150 * boards). (The "LED ON" jumper on the Zumo Reflectance Sensor Array must be
I_failed_Cpp 0:4c5986aedbfc 151 * configured correctly for this to work.) If the value `QTR_NO_EMITTER_PIN`
I_failed_Cpp 0:4c5986aedbfc 152 * (255) is used, you can leave the emitter pin disconnected and the IR
I_failed_Cpp 0:4c5986aedbfc 153 * emitters will always be on.
I_failed_Cpp 0:4c5986aedbfc 154 */
I_failed_Cpp 0:4c5986aedbfc 155 void init(PinName emitterPin = ZUMO_SENSOR_ARRAY_DEFAULT_EMITTER_PIN){
I_failed_Cpp 3:e3afbfd0a71c 156 PinName sensorPins[]={ D4, A3, D11, A0, A2, D5 }; // sensorPins[] = { D4, A3, D11, A0, A2, D5 };
I_failed_Cpp 0:4c5986aedbfc 157 QTRSensorsRC::init(sensorPins, sizeof(sensorPins), 2000, emitterPin);
I_failed_Cpp 0:4c5986aedbfc 158 }
I_failed_Cpp 0:4c5986aedbfc 159
I_failed_Cpp 0:4c5986aedbfc 160 /*! \brief Initializes with all settings as given.
I_failed_Cpp 0:4c5986aedbfc 161 *
I_failed_Cpp 0:4c5986aedbfc 162 * \param pins Array of pin numbers for sensors.
I_failed_Cpp 0:4c5986aedbfc 163 * \param numSensors Number of sensors.
I_failed_Cpp 0:4c5986aedbfc 164 * \param timeout Maximum duration of reflectance reading in microseconds.
I_failed_Cpp 0:4c5986aedbfc 165 * \param emitterPin Pin that turns IR emitters on or off.
I_failed_Cpp 0:4c5986aedbfc 166 *
I_failed_Cpp 0:4c5986aedbfc 167 * This function initializes the ZumoReflectanceSensorArray object with all
I_failed_Cpp 0:4c5986aedbfc 168 * settings as given.
I_failed_Cpp 0:4c5986aedbfc 169 *
I_failed_Cpp 0:4c5986aedbfc 170 * The array \a pins should contain the Arduino digital pin numbers for each
I_failed_Cpp 0:4c5986aedbfc 171 * sensor.
I_failed_Cpp 0:4c5986aedbfc 172 *
I_failed_Cpp 0:4c5986aedbfc 173 * \a numSensors specifies the length of the \a pins array (the number of
I_failed_Cpp 0:4c5986aedbfc 174 * reflectance sensors you are using).
I_failed_Cpp 0:4c5986aedbfc 175 *
I_failed_Cpp 0:4c5986aedbfc 176 * \a timeout specifies the length of time in microseconds beyond which you
I_failed_Cpp 0:4c5986aedbfc 177 * consider the sensor reading completely black. That is to say, if the pulse
I_failed_Cpp 0:4c5986aedbfc 178 * length for a pin exceeds \a timeout, pulse timing will stop and the reading
I_failed_Cpp 0:4c5986aedbfc 179 * for that pin will be considered full black. It is recommended that you set
I_failed_Cpp 0:4c5986aedbfc 180 * \a timeout to be between 1000 and 3000 us, depending on factors like the
I_failed_Cpp 0:4c5986aedbfc 181 * height of your sensors and ambient lighting. This allows you to shorten the
I_failed_Cpp 0:4c5986aedbfc 182 * duration of a sensor-reading cycle while maintaining useful measurements of
I_failed_Cpp 0:4c5986aedbfc 183 * reflectance. If \a timeout is not specified, it defaults to 2000 us. (See
I_failed_Cpp 0:4c5986aedbfc 184 * the [product page](http://www.pololu.com/product/1419) for the Zumo
I_failed_Cpp 0:4c5986aedbfc 185 * Reflectance Sensor Array on Pololu's website for an overview of the
I_failed_Cpp 0:4c5986aedbfc 186 * sensors' principle of operation.)
I_failed_Cpp 0:4c5986aedbfc 187 *
I_failed_Cpp 0:4c5986aedbfc 188 * \a emitterPin is the Arduino digital pin that controls whether the IR LEDs
I_failed_Cpp 0:4c5986aedbfc 189 * are on or off. This pin is optional; if a valid pin is specified, the
I_failed_Cpp 0:4c5986aedbfc 190 * emitters will only be turned on during a reading. If \a emitterPin is not
I_failed_Cpp 0:4c5986aedbfc 191 * specified, the emitters will be controlled with pin 2 on the Uno (and other
I_failed_Cpp 0:4c5986aedbfc 192 * ATmega328/168 boards) or pin A4 on the Leonardo (and other ATmega32U4
I_failed_Cpp 0:4c5986aedbfc 193 * boards). (The corresponding connection should be made with the "LED ON"
I_failed_Cpp 0:4c5986aedbfc 194 * jumper on the Zumo Reflectance Sensor Array.) If the value
I_failed_Cpp 0:4c5986aedbfc 195 * `QTR_NO_EMITTER_PIN` (255) is used, you can leave the emitter pin
I_failed_Cpp 0:4c5986aedbfc 196 * disconnected and the IR emitters will always be on.
I_failed_Cpp 0:4c5986aedbfc 197 *
I_failed_Cpp 0:4c5986aedbfc 198 * This version of `%init()` can be useful if you only want to use a subset
I_failed_Cpp 0:4c5986aedbfc 199 * of the six reflectance sensors on the array. For example, using the
I_failed_Cpp 0:4c5986aedbfc 200 * outermost two sensors (on pins 4 and 5 by default) is usually enough for
I_failed_Cpp 0:4c5986aedbfc 201 * detecting the ring border in sumo competitions:
I_failed_Cpp 0:4c5986aedbfc 202 *
I_failed_Cpp 0:4c5986aedbfc 203 * ~~~{.ino}
I_failed_Cpp 0:4c5986aedbfc 204 * ZumoReflectanceSensorArray reflectanceSensors;
I_failed_Cpp 0:4c5986aedbfc 205 *
I_failed_Cpp 0:4c5986aedbfc 206 * ...
I_failed_Cpp 0:4c5986aedbfc 207 *
I_failed_Cpp 0:4c5986aedbfc 208 * reflectanceSensors.init((unsigned char[]) {4, 5}, 2);
I_failed_Cpp 0:4c5986aedbfc 209 * ~~~
I_failed_Cpp 0:4c5986aedbfc 210 *
I_failed_Cpp 0:4c5986aedbfc 211 * Alternatively, you can use \ref ZumoReflectanceSensorArray(unsigned char * pins, unsigned char numSensors, unsigned int timeout, unsigned char emitterPin)
I_failed_Cpp 0:4c5986aedbfc 212 * "a different constructor" to declare and initialize the object at the same
I_failed_Cpp 0:4c5986aedbfc 213 * time:
I_failed_Cpp 0:4c5986aedbfc 214 *
I_failed_Cpp 0:4c5986aedbfc 215 * ~~~{.ino}
I_failed_Cpp 0:4c5986aedbfc 216 *
I_failed_Cpp 0:4c5986aedbfc 217 * ZumoReflectanceSensorArray reflectanceSensors((unsigned char[]) {4, 5}, 2);
I_failed_Cpp 0:4c5986aedbfc 218 * ~~~
I_failed_Cpp 0:4c5986aedbfc 219 *
I_failed_Cpp 0:4c5986aedbfc 220 */
I_failed_Cpp 0:4c5986aedbfc 221 void init(PinName *pins, unsigned char numSensors, unsigned int timeout = 2000, PinName emitterPin = ZUMO_SENSOR_ARRAY_DEFAULT_EMITTER_PIN){
I_failed_Cpp 0:4c5986aedbfc 222 QTRSensorsRC::init(pins, numSensors, timeout, emitterPin);
I_failed_Cpp 0:4c5986aedbfc 223 }
I_failed_Cpp 0:4c5986aedbfc 224 };
I_failed_Cpp 0:4c5986aedbfc 225
I_failed_Cpp 0:4c5986aedbfc 226 // documentation for inherited functions
I_failed_Cpp 0:4c5986aedbfc 227
I_failed_Cpp 0:4c5986aedbfc 228 /*! \fn void QTRSensors::read(unsigned int *sensor_values, unsigned char readMode = QTR_EMITTERS_ON)
I_failed_Cpp 0:4c5986aedbfc 229 \memberof ZumoReflectanceSensorArray
I_failed_Cpp 0:4c5986aedbfc 230 * \brief Reads the raw sensor values into an array.
I_failed_Cpp 0:4c5986aedbfc 231 *
I_failed_Cpp 0:4c5986aedbfc 232 * \param sensorValues Array to populate with sensor readings.
I_failed_Cpp 0:4c5986aedbfc 233 * \param readMode Read mode (`QTR_EMITTERS_OFF`, `QTR_EMITTERS_ON`, or
I_failed_Cpp 0:4c5986aedbfc 234 * `QTR_EMITTERS_ON_AND_OFF`).
I_failed_Cpp 0:4c5986aedbfc 235 *
I_failed_Cpp 0:4c5986aedbfc 236 * There **must** be space in the \a sensorValues array for as many values as
I_failed_Cpp 0:4c5986aedbfc 237 * there were sensors specified in the constructor. The values returned are
I_failed_Cpp 0:4c5986aedbfc 238 * measures of the reflectance in units of microseconds. They will be raw
I_failed_Cpp 0:4c5986aedbfc 239 * readings between 0 and the \a timeout argument (in units of microseconds)
I_failed_Cpp 0:4c5986aedbfc 240 * provided in the constructor (which defaults to 2000).
I_failed_Cpp 0:4c5986aedbfc 241 *
I_failed_Cpp 0:4c5986aedbfc 242 * The \a readMode argument specifies the kind of read that will be performed.
I_failed_Cpp 0:4c5986aedbfc 243 * Several options are defined:
I_failed_Cpp 0:4c5986aedbfc 244 *
I_failed_Cpp 0:4c5986aedbfc 245 * - `QTR_EMITTERS_OFF` specifies that the reading should be made without
I_failed_Cpp 0:4c5986aedbfc 246 * turning on the infrared (IR) emitters, in which case the reading represents
I_failed_Cpp 0:4c5986aedbfc 247 * ambient light levels near the sensor.
I_failed_Cpp 0:4c5986aedbfc 248 * - `QTR_EMITTERS_ON` specifies that the emitters should be turned on for the
I_failed_Cpp 0:4c5986aedbfc 249 * reading, which results in a measure of reflectance.
I_failed_Cpp 0:4c5986aedbfc 250 * - `QTR_EMITTERS_ON_AND_OFF` specifies that a reading should be made in both
I_failed_Cpp 0:4c5986aedbfc 251 * the on and off states. The values returned when this option is used are
I_failed_Cpp 0:4c5986aedbfc 252 * given by the formula **on + max &minus; off**, where **on** is the reading
I_failed_Cpp 0:4c5986aedbfc 253 * with the emitters on, **off** is the reading with the emitters off, and
I_failed_Cpp 0:4c5986aedbfc 254 * **max** is the maximum sensor reading. This option can reduce the amount of
I_failed_Cpp 0:4c5986aedbfc 255 * interference from uneven ambient lighting.
I_failed_Cpp 0:4c5986aedbfc 256 *
I_failed_Cpp 0:4c5986aedbfc 257 * Note that emitter control will only work if you specify a valid emitter pin
I_failed_Cpp 0:4c5986aedbfc 258 * in the constructor and make the corresponding connection (with the "LED ON"
I_failed_Cpp 0:4c5986aedbfc 259 * jumper or otherwise).
I_failed_Cpp 0:4c5986aedbfc 260 *
I_failed_Cpp 0:4c5986aedbfc 261 * The ZumoReflectanceSensorArray class inherits this function from the
I_failed_Cpp 0:4c5986aedbfc 262 * QTRSensors class.
I_failed_Cpp 0:4c5986aedbfc 263 */
I_failed_Cpp 0:4c5986aedbfc 264
I_failed_Cpp 0:4c5986aedbfc 265 /*! \fn void QTRSensors::emittersOff()
I_failed_Cpp 0:4c5986aedbfc 266 * \brief Turns the IR LEDs off.
I_failed_Cpp 0:4c5986aedbfc 267 *
I_failed_Cpp 0:4c5986aedbfc 268 * This is mainly for use by the `read()` method, and calling this function
I_failed_Cpp 0:4c5986aedbfc 269 * before or after reading the sensors will have no effect on the readings, but
I_failed_Cpp 0:4c5986aedbfc 270 * you might wish to use it for testing purposes. This method will only do
I_failed_Cpp 0:4c5986aedbfc 271 * something if the emitter pin specified in the constructor is valid (i.e. not
I_failed_Cpp 0:4c5986aedbfc 272 * `QTR_NO_EMITTER_PIN`) and the corresponding connection is made.
I_failed_Cpp 0:4c5986aedbfc 273 *
I_failed_Cpp 0:4c5986aedbfc 274 * The ZumoReflectanceSensorArray class inherits this function from the
I_failed_Cpp 0:4c5986aedbfc 275 * QTRSensors class.
I_failed_Cpp 0:4c5986aedbfc 276 */
I_failed_Cpp 0:4c5986aedbfc 277
I_failed_Cpp 0:4c5986aedbfc 278 /*! \fn void QTRSensors::emittersOn()
I_failed_Cpp 0:4c5986aedbfc 279 * \brief Turns the IR LEDs on.
I_failed_Cpp 0:4c5986aedbfc 280 * \copydetails emittersOff
I_failed_Cpp 0:4c5986aedbfc 281 */
I_failed_Cpp 0:4c5986aedbfc 282
I_failed_Cpp 0:4c5986aedbfc 283 /*! \fn void QTRSensors::calibrate(unsigned char readMode = QTR_EMITTERS_ON)
I_failed_Cpp 0:4c5986aedbfc 284 * \brief Reads the sensors for calibration.
I_failed_Cpp 0:4c5986aedbfc 285 *
I_failed_Cpp 0:4c5986aedbfc 286 * \param readMode Read mode (`QTR_EMITTERS_OFF`, `QTR_EMITTERS_ON`, or
I_failed_Cpp 0:4c5986aedbfc 287 * `QTR_EMITTERS_ON_AND_OFF`).
I_failed_Cpp 0:4c5986aedbfc 288 *
I_failed_Cpp 0:4c5986aedbfc 289 * The sensor values read by this function are not returned; instead, the
I_failed_Cpp 0:4c5986aedbfc 290 * maximum and minimum values found over time are stored internally and used for
I_failed_Cpp 0:4c5986aedbfc 291 * the `readCalibrated()` method. You can access the calibration (i.e raw max
I_failed_Cpp 0:4c5986aedbfc 292 * and min sensor readings) through the public member pointers
I_failed_Cpp 0:4c5986aedbfc 293 * `calibratedMinimumOn`, `calibratedMaximumOn`, `calibratedMinimumOff`, and
I_failed_Cpp 0:4c5986aedbfc 294 * `calibratedMaximumOff`. Note that these pointers will point to arrays of
I_failed_Cpp 0:4c5986aedbfc 295 * length \a numSensors, as specified in the constructor, and they will only be
I_failed_Cpp 0:4c5986aedbfc 296 * allocated **after** `calibrate()` has been called. If you only calibrate with
I_failed_Cpp 0:4c5986aedbfc 297 * the emitters on, the calibration arrays that hold the off values will not be
I_failed_Cpp 0:4c5986aedbfc 298 * allocated.
I_failed_Cpp 0:4c5986aedbfc 299 *
I_failed_Cpp 0:4c5986aedbfc 300 * The ZumoReflectanceSensorArray class inherits this function from the
I_failed_Cpp 0:4c5986aedbfc 301 * QTRSensors class.
I_failed_Cpp 0:4c5986aedbfc 302 */
I_failed_Cpp 0:4c5986aedbfc 303
I_failed_Cpp 0:4c5986aedbfc 304 /*! \fn void QTRSensors::resetCalibration()
I_failed_Cpp 0:4c5986aedbfc 305 * \brief Resets all calibration that has been done.
I_failed_Cpp 0:4c5986aedbfc 306 *
I_failed_Cpp 0:4c5986aedbfc 307 * This function discards the calibration values that have been previously
I_failed_Cpp 0:4c5986aedbfc 308 * recorded, resetting the min and max values.
I_failed_Cpp 0:4c5986aedbfc 309 *
I_failed_Cpp 0:4c5986aedbfc 310 * The ZumoReflectanceSensorArray class inherits this function from the
I_failed_Cpp 0:4c5986aedbfc 311 * QTRSensors class.
I_failed_Cpp 0:4c5986aedbfc 312 */
I_failed_Cpp 0:4c5986aedbfc 313
I_failed_Cpp 0:4c5986aedbfc 314 /*! \fn void QTRSensors::readCalibrated(unsigned int *sensor_values, unsigned char readMode = QTR_EMITTERS_ON)
I_failed_Cpp 0:4c5986aedbfc 315 * \brief Returns sensor readings normalized to values between 0 and 1000.
I_failed_Cpp 0:4c5986aedbfc 316 *
I_failed_Cpp 0:4c5986aedbfc 317 * \param sensorValues Array to populate with sensor readings.
I_failed_Cpp 0:4c5986aedbfc 318 * \param readMode Read mode (`QTR_EMITTERS_OFF`, `QTR_EMITTERS_ON`, or
I_failed_Cpp 0:4c5986aedbfc 319 * `QTR_EMITTERS_ON_AND_OFF`).
I_failed_Cpp 0:4c5986aedbfc 320 *
I_failed_Cpp 0:4c5986aedbfc 321 * 0 corresponds to a reading that is less than or equal to the minimum value
I_failed_Cpp 0:4c5986aedbfc 322 * read by `calibrate()` and 1000 corresponds to a reading that is greater than
I_failed_Cpp 0:4c5986aedbfc 323 * or equal to the maximum value. Calibration values are stored separately for
I_failed_Cpp 0:4c5986aedbfc 324 * each sensor, so that differences in the sensors are accounted for
I_failed_Cpp 0:4c5986aedbfc 325 * automatically.
I_failed_Cpp 0:4c5986aedbfc 326 *
I_failed_Cpp 0:4c5986aedbfc 327 * The ZumoReflectanceSensorArray class inherits this function from the
I_failed_Cpp 0:4c5986aedbfc 328 * QTRSensors class.
I_failed_Cpp 0:4c5986aedbfc 329 */
I_failed_Cpp 0:4c5986aedbfc 330
I_failed_Cpp 0:4c5986aedbfc 331 /*! \fn int QTRSensors::readLine(unsigned int *sensor_values, unsigned char readMode = QTR_EMITTERS_ON, unsigned char whiteLine = 0)
I_failed_Cpp 0:4c5986aedbfc 332 * \brief Returns an estimated position of a line under the sensor array.
I_failed_Cpp 0:4c5986aedbfc 333 *
I_failed_Cpp 0:4c5986aedbfc 334 * \param sensorValues Array to populate with sensor readings.
I_failed_Cpp 0:4c5986aedbfc 335 * \param readMode Read mode (`QTR_EMITTERS_OFF`, `QTR_EMITTERS_ON`, or
I_failed_Cpp 0:4c5986aedbfc 336 * `QTR_EMITTERS_ON_AND_OFF`).
I_failed_Cpp 0:4c5986aedbfc 337 * \param whiteLine 0 to detect a dark line on a light surface; 1 to detect
I_failed_Cpp 0:4c5986aedbfc 338 * a light line on a dark surface.
I_failed_Cpp 0:4c5986aedbfc 339 * \return An estimated line position.
I_failed_Cpp 0:4c5986aedbfc 340 *
I_failed_Cpp 0:4c5986aedbfc 341 * This function operates the same as `readCalibrated()`, but with a feature
I_failed_Cpp 0:4c5986aedbfc 342 * designed for line following: it returns an estimated position of the line.
I_failed_Cpp 0:4c5986aedbfc 343 * The estimate is made using a weighted average of the sensor indices
I_failed_Cpp 0:4c5986aedbfc 344 * multiplied by 1000, so that a return value of 0 indicates that the line is
I_failed_Cpp 0:4c5986aedbfc 345 * directly below sensor 0 (or was last seen by sensor 0 before being lost), a
I_failed_Cpp 0:4c5986aedbfc 346 * return value of 1000 indicates that the line is directly below sensor 1, 2000
I_failed_Cpp 0:4c5986aedbfc 347 * indicates that it's below sensor 2, etc. Intermediate values indicate that
I_failed_Cpp 0:4c5986aedbfc 348 * the line is between two sensors. The formula is:
I_failed_Cpp 0:4c5986aedbfc 349 *
I_failed_Cpp 0:4c5986aedbfc 350 * \f[
I_failed_Cpp 0:4c5986aedbfc 351 * \newcommand{sv}[1]{\mathtt{sensorValues[#1]}}
I_failed_Cpp 0:4c5986aedbfc 352 * \text{return value} =
I_failed_Cpp 0:4c5986aedbfc 353 * \frac{(0 \times \sv{0}) + (1000 \times \sv{1}) + (2000 \times \sv{2}) + \ldots}
I_failed_Cpp 0:4c5986aedbfc 354 * {\sv{0} + \sv{1} + \sv{2} + \ldots}
I_failed_Cpp 0:4c5986aedbfc 355 * \f]
I_failed_Cpp 0:4c5986aedbfc 356 *
I_failed_Cpp 0:4c5986aedbfc 357 * As long as your sensors aren't spaced too far apart relative to the line,
I_failed_Cpp 0:4c5986aedbfc 358 * this returned value is designed to be monotonic, which makes it great for use
I_failed_Cpp 0:4c5986aedbfc 359 * in closed-loop PID control. Additionally, this method remembers where it last
I_failed_Cpp 0:4c5986aedbfc 360 * saw the line, so if you ever lose the line to the left or the right, its line
I_failed_Cpp 0:4c5986aedbfc 361 * position will continue to indicate the direction you need to go to reacquire
I_failed_Cpp 0:4c5986aedbfc 362 * the line. For example, if sensor 5 is your rightmost sensor and you end up
I_failed_Cpp 0:4c5986aedbfc 363 * completely off the line to the left, this function will continue to return
I_failed_Cpp 0:4c5986aedbfc 364 * 5000.
I_failed_Cpp 0:4c5986aedbfc 365 *
I_failed_Cpp 0:4c5986aedbfc 366 * By default, this function assumes a dark line (high values) on a light
I_failed_Cpp 0:4c5986aedbfc 367 * background (low values). If your line is light on dark, set the optional
I_failed_Cpp 0:4c5986aedbfc 368 * second argument \a whiteLine to true. In this case, each sensor value will be
I_failed_Cpp 0:4c5986aedbfc 369 * replaced by the maximum possible value minus its actual value before the
I_failed_Cpp 0:4c5986aedbfc 370 * averaging.
I_failed_Cpp 0:4c5986aedbfc 371 *
I_failed_Cpp 0:4c5986aedbfc 372 * The ZumoReflectanceSensorArray class inherits this function from the
I_failed_Cpp 0:4c5986aedbfc 373 * QTRSensors class.
I_failed_Cpp 0:4c5986aedbfc 374 */
I_failed_Cpp 0:4c5986aedbfc 375
I_failed_Cpp 0:4c5986aedbfc 376
I_failed_Cpp 0:4c5986aedbfc 377 // documentation for inherited member variables
I_failed_Cpp 0:4c5986aedbfc 378
I_failed_Cpp 0:4c5986aedbfc 379 /*!
I_failed_Cpp 0:4c5986aedbfc 380 * \property unsigned int * QTRSensors::calibratedMinimumOn
I_failed_Cpp 0:4c5986aedbfc 381 * \brief The calibrated minimum values measured for each sensor, with emitters
I_failed_Cpp 0:4c5986aedbfc 382 * on.
I_failed_Cpp 0:4c5986aedbfc 383 *
I_failed_Cpp 0:4c5986aedbfc 384 * This pointer is unallocated and set to 0 until `calibrate()` is called, and
I_failed_Cpp 0:4c5986aedbfc 385 * then allocated to exactly the size required. Depending on the \a readMode
I_failed_Cpp 0:4c5986aedbfc 386 * argument to `calibrate()`, only the On or Off values might be allocated, as
I_failed_Cpp 0:4c5986aedbfc 387 * required. This variable is made public so that you can use the calibration
I_failed_Cpp 0:4c5986aedbfc 388 * values for your own calculations and do things like saving them to EEPROM,
I_failed_Cpp 0:4c5986aedbfc 389 * performing sanity checking, etc.
I_failed_Cpp 0:4c5986aedbfc 390 *
I_failed_Cpp 0:4c5986aedbfc 391 * The ZumoReflectanceSensorArray class inherits this variable from the
I_failed_Cpp 0:4c5986aedbfc 392 * QTRSensors class.
I_failed_Cpp 0:4c5986aedbfc 393 *
I_failed_Cpp 0:4c5986aedbfc 394 * \property unsigned int * QTRSensors::calibratedMaximumOn
I_failed_Cpp 0:4c5986aedbfc 395 * \brief The calibrated maximum values measured for each sensor, with emitters
I_failed_Cpp 0:4c5986aedbfc 396 * on.
I_failed_Cpp 0:4c5986aedbfc 397 * \copydetails QTRSensors::calibratedMinimumOn
I_failed_Cpp 0:4c5986aedbfc 398 *
I_failed_Cpp 0:4c5986aedbfc 399 * \property unsigned int * QTRSensors::calibratedMinimumOff
I_failed_Cpp 0:4c5986aedbfc 400 * \brief The calibrated minimum values measured for each sensor, with emitters
I_failed_Cpp 0:4c5986aedbfc 401 * off.
I_failed_Cpp 0:4c5986aedbfc 402 * \copydetails QTRSensors::calibratedMinimumOn
I_failed_Cpp 0:4c5986aedbfc 403 *
I_failed_Cpp 0:4c5986aedbfc 404 * \property unsigned int * QTRSensors::calibratedMaximumOff
I_failed_Cpp 0:4c5986aedbfc 405 * \brief The calibrated maximum values measured for each sensor, with emitters
I_failed_Cpp 0:4c5986aedbfc 406 * off.
I_failed_Cpp 0:4c5986aedbfc 407 * \copydetails QTRSensors::calibratedMinimumOn
I_failed_Cpp 0:4c5986aedbfc 408 */
I_failed_Cpp 0:4c5986aedbfc 409
I_failed_Cpp 0:4c5986aedbfc 410 #endif