mirror of
https://github.com/KevinMidboe/Arduino.git
synced 2025-10-29 17:40:11 +00:00
Init commit with many years of arduino sketches and projects. I dont know if the esp8266 includes much, but there are also libraries. I hope they dont have crazy automatic versioning through the Arduino IDE.
This commit is contained in:
126
libraries/Zumo/PLab_ZumoMotors.cpp
Executable file
126
libraries/Zumo/PLab_ZumoMotors.cpp
Executable file
@@ -0,0 +1,126 @@
|
||||
#include "Arduino.h"
|
||||
#include "PLab_ZumoMotors.h"
|
||||
#include <ZumoMotors.h>
|
||||
|
||||
|
||||
#define ADMUX_VCCWRT1V1 (_BV(MUX3) | _BV(MUX2) | _BV(MUX1)) // DS AREF..
|
||||
|
||||
float Read_Zumo_Volts_AREF()
|
||||
{
|
||||
int oldADMUX = ADMUX;
|
||||
// Read 1.1V reference against AVcc
|
||||
// set the reference to Vcc and the measurement to the internal 1.1V reference
|
||||
if (ADMUX != ADMUX_VCCWRT1V1)
|
||||
{
|
||||
ADMUX = ADMUX_VCCWRT1V1;
|
||||
// Bandgap reference start-up time: max 70us
|
||||
// Wait for Vref to settle.
|
||||
delayMicroseconds(350);
|
||||
}
|
||||
// Start conversion and wait for it to finish.
|
||||
ADCSRA |= _BV(ADSC);
|
||||
while (bit_is_set(ADCSRA,ADSC)) {};
|
||||
|
||||
// Result is now stored in ADC.
|
||||
// Calculate Vcc (in V)
|
||||
float vcc = 1.1*1023.0 / ADC;
|
||||
|
||||
// Apply compensation
|
||||
vcc = vcc * 1.77; // Zumo divider factor;
|
||||
|
||||
ADMUX = oldADMUX;
|
||||
return vcc;
|
||||
}
|
||||
|
||||
float calc_time(int _speed, float _length) {
|
||||
double a = 24069*pow(_speed,-1.238);
|
||||
double b = 5.7824*log(_speed) - 19.99;
|
||||
double _time = _length * a + b;
|
||||
float correction;
|
||||
if (_speed > 100) {
|
||||
correction = -0.0007*_speed + 1.154;
|
||||
} else if (_speed > 50) {
|
||||
correction = 0.0017*_speed + 0.9167;
|
||||
} else {
|
||||
correction = 0.0187*_speed + 0.0667;
|
||||
};
|
||||
_time = _time / correction;
|
||||
float battery_voltage = Read_Zumo_Volts_AREF();
|
||||
_time = _time * 5.2 / battery_voltage;
|
||||
return _time;
|
||||
}
|
||||
|
||||
float calc_turn_length(int __speed) {
|
||||
float _speed = __speed;
|
||||
float y = 3.3375e-6*_speed*_speed*_speed - 0.00327*_speed*_speed + 1.0536*_speed - 28.595;
|
||||
float _length = 10.0 * 90.0 / y;
|
||||
return _length;
|
||||
}
|
||||
|
||||
PLab_ZumoMotors::PLab_ZumoMotors()
|
||||
{
|
||||
}
|
||||
|
||||
void PLab_ZumoMotors::forward(int _speed, int _length)
|
||||
{
|
||||
motors.setSpeeds(0, 0);
|
||||
float _time = calc_time(_speed,_length);
|
||||
motors.setSpeeds(_speed, _speed);
|
||||
delay(_time);
|
||||
motors.setSpeeds(0, 0);
|
||||
}
|
||||
|
||||
void PLab_ZumoMotors::backward(int _speed, int _length)
|
||||
{
|
||||
motors.setSpeeds(0, 0);
|
||||
float _time = calc_time(_speed,_length);
|
||||
motors.setSpeeds(- _speed, - _speed);
|
||||
delay(_time);
|
||||
motors.setSpeeds(0, 0);
|
||||
}
|
||||
|
||||
void PLab_ZumoMotors::turnRight(int _speed, int degrees)
|
||||
{
|
||||
motors.setSpeeds(0, 0);
|
||||
float _length = calc_turn_length(_speed);
|
||||
_length = _length * degrees / 90.0;
|
||||
float _time = calc_time(_speed,_length);
|
||||
motors.setSpeeds(_speed, - _speed);
|
||||
delay(_time);
|
||||
motors.setSpeeds(0, 0);
|
||||
}
|
||||
|
||||
void PLab_ZumoMotors::turnLeft(int _speed, int degrees)
|
||||
{
|
||||
motors.setSpeeds(0, 0);
|
||||
float _length = calc_turn_length(_speed);
|
||||
_length = _length * degrees / 90.0;
|
||||
float _time = calc_time(_speed,_length);
|
||||
motors.setSpeeds(- _speed, _speed);
|
||||
delay(_time);
|
||||
motors.setSpeeds(0, 0);
|
||||
}
|
||||
|
||||
// enable/disable flipping of motors
|
||||
void PLab_ZumoMotors::flipLeftMotor(boolean flip) {
|
||||
motors.flipLeftMotor(flip);
|
||||
}
|
||||
|
||||
|
||||
void PLab_ZumoMotors::flipRightMotor(boolean flip) {
|
||||
motors.flipRightMotor(flip);
|
||||
}
|
||||
|
||||
// set speed for left, right, or both motors
|
||||
|
||||
void PLab_ZumoMotors::setLeftSpeed(int speed){
|
||||
motors.setLeftSpeed(speed);
|
||||
}
|
||||
|
||||
void PLab_ZumoMotors::setRightSpeed(int speed){
|
||||
motors.setRightSpeed(speed);
|
||||
}
|
||||
|
||||
void PLab_ZumoMotors::setSpeeds(int leftSpeed, int rightSpeed){
|
||||
motors.setSpeeds(leftSpeed, rightSpeed);
|
||||
}
|
||||
35
libraries/Zumo/PLab_ZumoMotors.h
Executable file
35
libraries/Zumo/PLab_ZumoMotors.h
Executable file
@@ -0,0 +1,35 @@
|
||||
/*
|
||||
PLab_ZumoMotors.h - Library for Zumo.
|
||||
Created by Dag Svanæs, 2015.
|
||||
Released into the public domain.
|
||||
*/
|
||||
|
||||
#ifndef PLab_ZumoMotors_h
|
||||
#define PLab_ZumoMotors_h
|
||||
|
||||
#include "Arduino.h"
|
||||
#include <ZumoMotors.h>
|
||||
|
||||
class PLab_ZumoMotors
|
||||
{
|
||||
public:
|
||||
PLab_ZumoMotors();
|
||||
void forward(int _speed, int length);
|
||||
void backward(int _speed, int _length);
|
||||
void turnRight(int _speed, int degrees);
|
||||
void turnLeft(int _speed, int degrees);
|
||||
|
||||
// enable/disable flipping of motors
|
||||
void flipLeftMotor(boolean flip);
|
||||
void flipRightMotor(boolean flip);
|
||||
|
||||
// set speed for left, right, or both motors
|
||||
void setLeftSpeed(int speed);
|
||||
void setRightSpeed(int speed);
|
||||
void setSpeeds(int leftSpeed, int rightSpeed);
|
||||
|
||||
private:
|
||||
ZumoMotors motors;
|
||||
};
|
||||
|
||||
#endif
|
||||
173
libraries/Zumo/Pushbutton.cpp
Executable file
173
libraries/Zumo/Pushbutton.cpp
Executable file
@@ -0,0 +1,173 @@
|
||||
#include "Pushbutton.h"
|
||||
|
||||
// constructor; takes arguments specifying whether to enable internal pull-up
|
||||
// and the default state of the pin that the button is connected to
|
||||
Pushbutton::Pushbutton(unsigned char pin, unsigned char pullUp, unsigned char defaultState)
|
||||
{
|
||||
_pin = pin;
|
||||
_pullUp = pullUp;
|
||||
_defaultState = defaultState;
|
||||
gsdpState = 0;
|
||||
gsdrState = 0;
|
||||
gsdpPrevTimeMillis = 0;
|
||||
gsdrPrevTimeMillis = 0;
|
||||
initialized = false;
|
||||
}
|
||||
|
||||
// wait for button to be pressed
|
||||
void Pushbutton::waitForPress()
|
||||
{
|
||||
init(); // initialize if necessary
|
||||
|
||||
do
|
||||
{
|
||||
while (!_isPressed()); // wait for button to be pressed
|
||||
delay(10); // debounce the button press
|
||||
}
|
||||
while (!_isPressed()); // if button isn't still pressed, loop
|
||||
}
|
||||
|
||||
// wait for button to be released
|
||||
void Pushbutton::waitForRelease()
|
||||
{
|
||||
init(); // initialize if necessary
|
||||
|
||||
do
|
||||
{
|
||||
while (_isPressed()); // wait for button to be released
|
||||
delay(10); // debounce the button release
|
||||
}
|
||||
while (_isPressed()); // if button isn't still released, loop
|
||||
}
|
||||
|
||||
// wait for button to be pressed, then released
|
||||
void Pushbutton::waitForButton()
|
||||
{
|
||||
waitForPress();
|
||||
waitForRelease();
|
||||
}
|
||||
|
||||
// indicates whether button is pressed
|
||||
boolean Pushbutton::isPressed()
|
||||
{
|
||||
init(); // initialize if necessary
|
||||
|
||||
return _isPressed();
|
||||
}
|
||||
|
||||
// Uses a finite state machine to detect a single button press and returns
|
||||
// true to indicate the press (false otherwise). It requires the button to be
|
||||
// released for at least 15 ms and then pressed for at least 15 ms before
|
||||
// reporting the press. This function handles all necessary debouncing and
|
||||
// should be called repeatedly in a loop.
|
||||
boolean Pushbutton::getSingleDebouncedPress()
|
||||
{
|
||||
unsigned long timeMillis = millis();
|
||||
|
||||
init(); // initialize if necessary
|
||||
|
||||
switch (gsdpState)
|
||||
{
|
||||
case 0:
|
||||
if (!_isPressed()) // if button is released
|
||||
{
|
||||
gsdpPrevTimeMillis = timeMillis;
|
||||
gsdpState = 1; // proceed to next state
|
||||
}
|
||||
break;
|
||||
|
||||
case 1:
|
||||
if ((timeMillis - gsdpPrevTimeMillis >= 15) && !_isPressed()) // if 15 ms or longer has elapsed and button is still released
|
||||
gsdpState = 2; // proceed to next state
|
||||
else if (_isPressed())
|
||||
gsdpState = 0; // button is pressed or bouncing, so go back to previous (initial) state
|
||||
break;
|
||||
|
||||
case 2:
|
||||
if (_isPressed()) // if button is now pressed
|
||||
{
|
||||
gsdpPrevTimeMillis = timeMillis;
|
||||
gsdpState = 3; // proceed to next state
|
||||
}
|
||||
break;
|
||||
|
||||
case 3:
|
||||
if ((timeMillis - gsdpPrevTimeMillis >= 15) && _isPressed()) // if 15 ms or longer has elapsed and button is still pressed
|
||||
{
|
||||
gsdpState = 0; // next state becomes initial state
|
||||
return true; // report button press
|
||||
}
|
||||
else if (!_isPressed())
|
||||
gsdpState = 2; // button is released or bouncing, so go back to previous state
|
||||
break;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
// Uses a finite state machine to detect a single button release and returns
|
||||
// true to indicate the release (false otherwise). It requires the button to be
|
||||
// pressed for at least 15 ms and then released for at least 15 ms before
|
||||
// reporting the release. This function handles all necessary debouncing and
|
||||
// should be called repeatedly in a loop.
|
||||
boolean Pushbutton::getSingleDebouncedRelease()
|
||||
{
|
||||
unsigned int timeMillis = millis();
|
||||
|
||||
init(); // initialize if necessary
|
||||
|
||||
switch (gsdrState)
|
||||
{
|
||||
case 0:
|
||||
if (_isPressed()) // if button is pressed
|
||||
{
|
||||
gsdrPrevTimeMillis = timeMillis;
|
||||
gsdrState = 1; // proceed to next state
|
||||
}
|
||||
break;
|
||||
|
||||
case 1:
|
||||
if ((timeMillis - gsdrPrevTimeMillis >= 15) && _isPressed()) // if 15 ms or longer has elapsed and button is still pressed
|
||||
gsdrState = 2; // proceed to next state
|
||||
else if (!_isPressed())
|
||||
gsdrState = 0; // button is released or bouncing, so go back to previous (initial) state
|
||||
break;
|
||||
|
||||
case 2:
|
||||
if (!_isPressed()) // if button is now released
|
||||
{
|
||||
gsdrPrevTimeMillis = timeMillis;
|
||||
gsdrState = 3; // proceed to next state
|
||||
}
|
||||
break;
|
||||
|
||||
case 3:
|
||||
if ((timeMillis - gsdrPrevTimeMillis >= 15) && !_isPressed()) // if 15 ms or longer has elapsed and button is still released
|
||||
{
|
||||
gsdrState = 0; // next state becomes initial state
|
||||
return true; // report button release
|
||||
}
|
||||
else if (_isPressed())
|
||||
gsdrState = 2; // button is pressed or bouncing, so go back to previous state
|
||||
break;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
// initializes I/O pin for use as button inputs
|
||||
void Pushbutton::init2()
|
||||
{
|
||||
if (_pullUp == PULL_UP_ENABLED)
|
||||
pinMode(_pin, INPUT_PULLUP);
|
||||
else
|
||||
pinMode(_pin, INPUT); // high impedance
|
||||
|
||||
delayMicroseconds(5); // give pull-up time to stabilize
|
||||
}
|
||||
|
||||
// button is pressed if pin state differs from default state
|
||||
inline boolean Pushbutton::_isPressed()
|
||||
{
|
||||
return (digitalRead(_pin) == LOW) ^ (_defaultState == DEFAULT_STATE_LOW);
|
||||
}
|
||||
70
libraries/Zumo/Pushbutton.h
Executable file
70
libraries/Zumo/Pushbutton.h
Executable file
@@ -0,0 +1,70 @@
|
||||
/*! \file Pushbutton.h
|
||||
*
|
||||
* See the Pushbutton class reference for more information about this library.
|
||||
*
|
||||
* \class Pushbutton Pushbutton.h
|
||||
* \brief Read button presses and releases with debouncing
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef Pushbutton_h
|
||||
#define Pushbutton_h
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
#define ZUMO_BUTTON 12
|
||||
|
||||
#define PULL_UP_DISABLED 0
|
||||
#define PULL_UP_ENABLED 1
|
||||
|
||||
#define DEFAULT_STATE_LOW 0
|
||||
#define DEFAULT_STATE_HIGH 1
|
||||
|
||||
class Pushbutton
|
||||
{
|
||||
public:
|
||||
|
||||
// constructor; takes arguments specifying whether to enable internal pull-up
|
||||
// and the default state of the pin that the button is connected to
|
||||
Pushbutton(unsigned char pin, unsigned char pullUp = PULL_UP_ENABLED, unsigned char defaultState = DEFAULT_STATE_HIGH);
|
||||
|
||||
// wait for button to be pressed, released, or pressed and released
|
||||
void waitForPress();
|
||||
void waitForRelease();
|
||||
void waitForButton();
|
||||
|
||||
// indicates whether button is currently pressed
|
||||
boolean isPressed();
|
||||
|
||||
// more complex functions that return true once for each button transition
|
||||
// from released to pressed or pressed to released
|
||||
boolean getSingleDebouncedPress();
|
||||
boolean getSingleDebouncedRelease();
|
||||
|
||||
private:
|
||||
|
||||
unsigned char _pin;
|
||||
unsigned char _pullUp;
|
||||
unsigned char _defaultState;
|
||||
unsigned char gsdpState;
|
||||
unsigned char gsdrState;
|
||||
unsigned int gsdpPrevTimeMillis;
|
||||
unsigned int gsdrPrevTimeMillis;
|
||||
boolean initialized;
|
||||
|
||||
inline void init()
|
||||
{
|
||||
if (!initialized)
|
||||
{
|
||||
initialized = true;
|
||||
init2();
|
||||
}
|
||||
}
|
||||
|
||||
// initializes I/O pin for use as button input
|
||||
void init2();
|
||||
|
||||
boolean _isPressed();
|
||||
};
|
||||
|
||||
#endif
|
||||
563
libraries/Zumo/QTRSensors.cpp
Executable file
563
libraries/Zumo/QTRSensors.cpp
Executable file
@@ -0,0 +1,563 @@
|
||||
/*
|
||||
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>
|
||||
|
||||
|
||||
|
||||
// Base class data member initialization (called by derived class init())
|
||||
void QTRSensors::init(unsigned char *pins, unsigned char numSensors,
|
||||
unsigned char emitterPin)
|
||||
{
|
||||
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;
|
||||
}
|
||||
|
||||
|
||||
// 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();
|
||||
else
|
||||
emittersOff();
|
||||
|
||||
readPrivate(sensor_values);
|
||||
emittersOff();
|
||||
|
||||
if(readMode == QTR_EMITTERS_ON_AND_OFF)
|
||||
{
|
||||
readPrivate(off_values);
|
||||
|
||||
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);
|
||||
|
||||
_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);
|
||||
|
||||
_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);
|
||||
}
|
||||
31
libraries/Zumo/QTRSensors.dox
Executable file
31
libraries/Zumo/QTRSensors.dox
Executable file
@@ -0,0 +1,31 @@
|
||||
/*! \file QTRSensors.h
|
||||
*
|
||||
* This library is included in the Zumo Shield libraries as a dependency for the
|
||||
* ZumoReflectanceSensorArray library. If you are programming an Arduino on a
|
||||
* Zumo, you should generally use the ZumoReflectanceSensorArray library instead
|
||||
* of using the %QTRSensors library directly.
|
||||
*
|
||||
* For documentation specific to the %QTRSensors library, please see the [user's
|
||||
* guide](http://www.pololu.com/docs/0J19) on Pololu's website.
|
||||
*
|
||||
*
|
||||
* \class QTRSensors QTRSensors.h
|
||||
* \brief <em>(%ZumoReflectanceSensorArray dependency)</em>
|
||||
*
|
||||
* This class is part of the \ref QTRSensors.h "QTRSensors" library, which is
|
||||
* included in the Zumo Shield libraries as a dependency for the
|
||||
* ZumoReflectanceSensorArray library. If you are programming an Arduino on a
|
||||
* Zumo, you should generally use the ZumoReflectanceSensorArray library instead
|
||||
* of using the %QTRSensors library directly.
|
||||
*
|
||||
* For documentation specific to the %QTRSensors library, please see the [user's
|
||||
* guide](http://www.pololu.com/docs/0J19) on Pololu's website.
|
||||
*
|
||||
*
|
||||
* \class QTRSensorsRC QTRSensors.h
|
||||
* \copydoc QTRSensors
|
||||
*
|
||||
*
|
||||
* \class QTRSensorsAnalog QTRSensors.h
|
||||
* \copydoc QTRSensors
|
||||
*/
|
||||
268
libraries/Zumo/QTRSensors.h
Executable file
268
libraries/Zumo/QTRSensors.h
Executable file
@@ -0,0 +1,268 @@
|
||||
/*
|
||||
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's readPrivate(),
|
||||
// which is defined as a virtual function in the base class and
|
||||
// overridden by each derived class's own implementation.
|
||||
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 *_pins;
|
||||
unsigned char _numSensors;
|
||||
unsigned char _emitterPin;
|
||||
unsigned int _maxValue; // the maximum value returned by this function
|
||||
|
||||
private:
|
||||
|
||||
virtual void readPrivate(unsigned int *sensor_values) = 0;
|
||||
|
||||
// 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
|
||||
{
|
||||
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
|
||||
{
|
||||
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);
|
||||
|
||||
unsigned char _numSamplesPerSensor;
|
||||
};
|
||||
|
||||
|
||||
#endif
|
||||
742
libraries/Zumo/ZumoBuzzer.cpp
Executable file
742
libraries/Zumo/ZumoBuzzer.cpp
Executable file
@@ -0,0 +1,742 @@
|
||||
#ifndef F_CPU
|
||||
#define F_CPU 16000000UL // Standard Arduinos run at 16 MHz
|
||||
#endif //!F_CPU
|
||||
|
||||
#include <avr/interrupt.h>
|
||||
#include <avr/pgmspace.h>
|
||||
#include "ZumoBuzzer.h"
|
||||
|
||||
#ifdef __AVR_ATmega32U4__
|
||||
|
||||
// PD7 (OC4D)
|
||||
#define BUZZER_DDR DDRD
|
||||
#define BUZZER (1 << PORTD7)
|
||||
|
||||
#define TIMER4_CLK_8 0x4 // 2 MHz
|
||||
|
||||
#define ENABLE_TIMER_INTERRUPT() TIMSK4 = (1 << TOIE4)
|
||||
#define DISABLE_TIMER_INTERRUPT() TIMSK4 = 0
|
||||
|
||||
#else // 168P or 328P
|
||||
|
||||
// PD3 (OC2B)
|
||||
#define BUZZER_DDR DDRD
|
||||
#define BUZZER (1 << PORTD3)
|
||||
|
||||
#define TIMER2_CLK_32 0x3 // 500 kHz
|
||||
|
||||
static const unsigned int cs2_divider[] = {0, 1, 8, 32, 64, 128, 256, 1024};
|
||||
|
||||
#define ENABLE_TIMER_INTERRUPT() TIMSK2 = (1 << TOIE2)
|
||||
#define DISABLE_TIMER_INTERRUPT() TIMSK2 = 0
|
||||
|
||||
#endif
|
||||
|
||||
unsigned char buzzerInitialized = 0;
|
||||
volatile unsigned char buzzerFinished = 1; // flag: 0 while playing
|
||||
const char *buzzerSequence = 0;
|
||||
|
||||
// declaring these globals as static means they won't conflict
|
||||
// with globals in other .cpp files that share the same name
|
||||
static volatile unsigned int buzzerTimeout = 0; // tracks buzzer time limit
|
||||
static char play_mode_setting = PLAY_AUTOMATIC;
|
||||
|
||||
extern volatile unsigned char buzzerFinished; // flag: 0 while playing
|
||||
extern const char *buzzerSequence;
|
||||
|
||||
|
||||
static unsigned char use_program_space; // boolean: true if we should
|
||||
// use program space
|
||||
|
||||
// music settings and defaults
|
||||
static unsigned char octave = 4; // the current octave
|
||||
static unsigned int whole_note_duration = 2000; // the duration of a whole note
|
||||
static unsigned int note_type = 4; // 4 for quarter, etc
|
||||
static unsigned int duration = 500; // the duration of a note in ms
|
||||
static unsigned int volume = 15; // the note volume
|
||||
static unsigned char staccato = 0; // true if playing staccato
|
||||
|
||||
// staccato handling
|
||||
static unsigned char staccato_rest_duration; // duration of a staccato
|
||||
// rest, or zero if it is time
|
||||
// to play a note
|
||||
|
||||
static void nextNote();
|
||||
|
||||
#ifdef __AVR_ATmega32U4__
|
||||
|
||||
// Timer4 overflow interrupt
|
||||
ISR (TIMER4_OVF_vect)
|
||||
{
|
||||
if (buzzerTimeout-- == 0)
|
||||
{
|
||||
DISABLE_TIMER_INTERRUPT();
|
||||
sei(); // re-enable global interrupts (nextNote() is very slow)
|
||||
TCCR4B = (TCCR4B & 0xF0) | TIMER4_CLK_8; // select IO clock
|
||||
unsigned int top = (F_CPU/16) / 1000; // set TOP for freq = 1 kHz:
|
||||
TC4H = top >> 8; // top 2 bits... (TC4H temporarily stores top 2 bits of 10-bit accesses)
|
||||
OCR4C = top; // and bottom 8 bits
|
||||
TC4H = 0; // 0% duty cycle: top 2 bits...
|
||||
OCR4D = 0; // and bottom 8 bits
|
||||
buzzerFinished = 1;
|
||||
if (buzzerSequence && (play_mode_setting == PLAY_AUTOMATIC))
|
||||
nextNote();
|
||||
}
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
// Timer2 overflow interrupt
|
||||
ISR (TIMER2_OVF_vect)
|
||||
{
|
||||
if (buzzerTimeout-- == 0)
|
||||
{
|
||||
DISABLE_TIMER_INTERRUPT();
|
||||
sei(); // re-enable global interrupts (nextNote() is very slow)
|
||||
TCCR2B = (TCCR2B & 0xF8) | TIMER2_CLK_32; // select IO clock
|
||||
OCR2A = (F_CPU/64) / 1000; // set TOP for freq = 1 kHz
|
||||
OCR2B = 0; // 0% duty cycle
|
||||
buzzerFinished = 1;
|
||||
if (buzzerSequence && (play_mode_setting == PLAY_AUTOMATIC))
|
||||
nextNote();
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
// constructor
|
||||
|
||||
ZumoBuzzer::ZumoBuzzer()
|
||||
{
|
||||
}
|
||||
|
||||
// this is called by playFrequency()
|
||||
inline void ZumoBuzzer::init()
|
||||
{
|
||||
if (!buzzerInitialized)
|
||||
{
|
||||
buzzerInitialized = 1;
|
||||
init2();
|
||||
}
|
||||
}
|
||||
|
||||
// initializes timer4 (32U4) or timer2 (328P) for buzzer control
|
||||
void ZumoBuzzer::init2()
|
||||
{
|
||||
DISABLE_TIMER_INTERRUPT();
|
||||
|
||||
#ifdef __AVR_ATmega32U4__
|
||||
TCCR4A = 0x00; // bits 7 and 6 clear: normal port op., OC4A disconnected
|
||||
// bits 5 and 4 clear: normal port op., OC4B disconnected
|
||||
// bit 3 clear: no force output compare for channel A
|
||||
// bit 2 clear: no force output compare for channel B
|
||||
// bit 1 clear: disable PWM for channel A
|
||||
// bit 0 clear: disable PWM for channel B
|
||||
|
||||
TCCR4B = 0x04; // bit 7 clear: disable PWM inversion
|
||||
// bit 6 clear: no prescaler reset
|
||||
// bits 5 and 4 clear: dead time prescaler 1
|
||||
// bit 3 clear, 2 set, 1-0 clear: timer clock = CK/8
|
||||
|
||||
TCCR4C = 0x09; // bits 7 and 6 clear: normal port op., OC4A disconnected
|
||||
// bits 5 and 4 clear: normal port op., OC4B disconnected
|
||||
// bit 3 set, 2 clear: clear OC4D on comp match when upcounting,
|
||||
// set OC4D on comp match when downcounting
|
||||
// bit 1 clear: no force output compare for channel D
|
||||
// bit 0 set: enable PWM for channel 4
|
||||
|
||||
TCCR4D = 0x01; // bit 7 clear: disable fault protection interrupt
|
||||
// bit 6 clear: disable fault protection mode
|
||||
// bit 5 clear: disable fault protection noise canceler
|
||||
// bit 4 clear: falling edge triggers fault
|
||||
// bit 3 clear: disable fault protection analog comparator
|
||||
// bit 2 clear: fault protection interrupt flag
|
||||
// bit 1 clear, 0 set: select waveform generation mode,
|
||||
// phase- and frequency-correct PWM, TOP = OCR4C,
|
||||
// OCR4D set at BOTTOM, TOV4 flag set at BOTTOM
|
||||
|
||||
// This sets timer 4 to run in phase- and frequency-correct PWM mode,
|
||||
// where TOP = OCR4C, OCR4D is updated at BOTTOM, TOV1 Flag is set on BOTTOM.
|
||||
// OC4D is cleared on compare match when upcounting, set on compare
|
||||
// match when downcounting; OC4A and OC4B are disconnected.
|
||||
|
||||
unsigned int top = (F_CPU/16) / 1000; // set TOP for freq = 1 kHz:
|
||||
TC4H = top >> 8; // top 2 bits...
|
||||
OCR4C = top; // and bottom 8 bits
|
||||
TC4H = 0; // 0% duty cycle: top 2 bits...
|
||||
OCR4D = 0; // and bottom 8 bits
|
||||
#else
|
||||
TCCR2A = 0x21; // bits 7 and 6 clear: normal port op., OC4A disconnected
|
||||
// bit 5 set, 4 clear: clear OC2B on comp match when upcounting,
|
||||
// set OC2B on comp match when downcounting
|
||||
// bits 3 and 2: not used
|
||||
// bit 1 clear, 0 set: combine with bit 3 of TCCR2B...
|
||||
|
||||
TCCR2B = 0x0B; // bit 7 clear: no force output compare for channel A
|
||||
// bit 6 clear: no force output compare for channel B
|
||||
// bits 5 and 4: not used
|
||||
// bit 3 set: combine with bits 1 and 0 of TCCR2A to
|
||||
// select waveform generation mode 5, phase-correct PWM,
|
||||
// TOP = OCR2A, OCR2B set at TOP, TOV2 flag set at BOTTOM
|
||||
// bit 2 clear, 1-0 set: timer clock = clkT2S/32
|
||||
|
||||
// This sets timer 2 to run in phase-correct PWM mode, where TOP = OCR2A,
|
||||
// OCR2B is updated at TOP, TOV2 Flag is set on BOTTOM. OC2B is cleared
|
||||
// on compare match when upcounting, set on compare match when downcounting;
|
||||
// OC2A is disconnected.
|
||||
// Note: if the PWM frequency and duty cycle are changed, the first
|
||||
// cycle of the new frequency will be at the old duty cycle, since
|
||||
// the duty cycle (OCR2B) is not updated until TOP.
|
||||
|
||||
|
||||
OCR2A = (F_CPU/64) / 1000; // set TOP for freq = 1 kHz
|
||||
OCR2B = 0; // 0% duty cycle
|
||||
#endif
|
||||
|
||||
BUZZER_DDR |= BUZZER; // buzzer pin set as an output
|
||||
sei();
|
||||
}
|
||||
|
||||
|
||||
// Set up timer 1 to play the desired frequency (in Hz or .1 Hz) for the
|
||||
// the desired duration (in ms). Allowed frequencies are 40 Hz to 10 kHz.
|
||||
// volume controls buzzer volume, with 15 being loudest and 0 being quietest.
|
||||
// Note: frequency*duration/1000 must be less than 0xFFFF (65535). This
|
||||
// means that you can't use a max duration of 65535 ms for frequencies
|
||||
// greater than 1 kHz. For example, the max duration you can use for a
|
||||
// frequency of 10 kHz is 6553 ms. If you use a duration longer than this,
|
||||
// you will cause an integer overflow that produces unexpected behavior.
|
||||
void ZumoBuzzer::playFrequency(unsigned int freq, unsigned int dur,
|
||||
unsigned char volume)
|
||||
{
|
||||
init(); // initializes the buzzer if necessary
|
||||
buzzerFinished = 0;
|
||||
|
||||
unsigned int timeout;
|
||||
unsigned char multiplier = 1;
|
||||
|
||||
if (freq & DIV_BY_10) // if frequency's DIV_BY_10 bit is set
|
||||
{ // then the true frequency is freq/10
|
||||
multiplier = 10; // (gives higher resolution for small freqs)
|
||||
freq &= ~DIV_BY_10; // clear DIV_BY_10 bit
|
||||
}
|
||||
|
||||
unsigned char min = 40 * multiplier;
|
||||
if (freq < min) // min frequency allowed is 40 Hz
|
||||
freq = min;
|
||||
if (multiplier == 1 && freq > 10000)
|
||||
freq = 10000; // max frequency allowed is 10kHz
|
||||
|
||||
#ifdef __AVR_ATmega32U4__
|
||||
unsigned long top;
|
||||
unsigned char dividerExponent = 0;
|
||||
|
||||
// calculate necessary clock source and counter top value to get freq
|
||||
top = (unsigned int)(((F_CPU/2 * multiplier) + (freq >> 1))/ freq);
|
||||
|
||||
while (top > 1023)
|
||||
{
|
||||
dividerExponent++;
|
||||
top = (unsigned int)((((F_CPU/2 >> (dividerExponent)) * multiplier) + (freq >> 1))/ freq);
|
||||
}
|
||||
#else
|
||||
unsigned int top;
|
||||
unsigned char newCS2 = 2; // try prescaler divider of 8 first (minimum necessary for 10 kHz)
|
||||
unsigned int divider = cs2_divider[newCS2];
|
||||
|
||||
// calculate necessary clock source and counter top value to get freq
|
||||
top = (unsigned int)(((F_CPU/16 * multiplier) + (freq >> 1))/ freq);
|
||||
|
||||
while (top > 255)
|
||||
{
|
||||
divider = cs2_divider[++newCS2];
|
||||
top = (unsigned int)(((F_CPU/2/divider * multiplier) + (freq >> 1))/ freq);
|
||||
}
|
||||
#endif
|
||||
|
||||
// set timeout (duration):
|
||||
if (multiplier == 10)
|
||||
freq = (freq + 5) / 10;
|
||||
|
||||
if (freq == 1000)
|
||||
timeout = dur; // duration for silent notes is exact
|
||||
else
|
||||
timeout = (unsigned int)((long)dur * freq / 1000);
|
||||
|
||||
if (volume > 15)
|
||||
volume = 15;
|
||||
|
||||
DISABLE_TIMER_INTERRUPT(); // disable interrupts while writing to registers
|
||||
|
||||
#ifdef __AVR_ATmega32U4__
|
||||
TCCR4B = (TCCR4B & 0xF0) | (dividerExponent + 1); // select timer 4 clock prescaler: divider = 2^n if CS4 = n+1
|
||||
TC4H = top >> 8; // set timer 1 pwm frequency: top 2 bits...
|
||||
OCR4C = top; // and bottom 8 bits
|
||||
unsigned int width = top >> (16 - volume); // set duty cycle (volume):
|
||||
TC4H = width >> 8; // top 2 bits...
|
||||
OCR4D = width; // and bottom 8 bits
|
||||
buzzerTimeout = timeout; // set buzzer duration
|
||||
|
||||
TIFR4 |= 0xFF; // clear any pending t4 overflow int.
|
||||
#else
|
||||
TCCR2B = (TCCR2B & 0xF8) | newCS2; // select timer 2 clock prescaler
|
||||
OCR2A = top; // set timer 2 pwm frequency
|
||||
OCR2B = top >> (16 - volume); // set duty cycle (volume)
|
||||
buzzerTimeout = timeout; // set buzzer duration
|
||||
|
||||
TIFR2 |= 0xFF; // clear any pending t2 overflow int.
|
||||
#endif
|
||||
|
||||
ENABLE_TIMER_INTERRUPT();
|
||||
}
|
||||
|
||||
|
||||
|
||||
// Determine the frequency for the specified note, then play that note
|
||||
// for the desired duration (in ms). This is done without using floats
|
||||
// and without having to loop. volume controls buzzer volume, with 15 being
|
||||
// loudest and 0 being quietest.
|
||||
// Note: frequency*duration/1000 must be less than 0xFFFF (65535). This
|
||||
// means that you can't use a max duration of 65535 ms for frequencies
|
||||
// greater than 1 kHz. For example, the max duration you can use for a
|
||||
// frequency of 10 kHz is 6553 ms. If you use a duration longer than this,
|
||||
// you will cause an integer overflow that produces unexpected behavior.
|
||||
void ZumoBuzzer::playNote(unsigned char note, unsigned int dur,
|
||||
unsigned char volume)
|
||||
{
|
||||
// note = key + octave * 12, where 0 <= key < 12
|
||||
// example: A4 = A + 4 * 12, where A = 9 (so A4 = 57)
|
||||
// A note is converted to a frequency by the formula:
|
||||
// Freq(n) = Freq(0) * a^n
|
||||
// where
|
||||
// Freq(0) is chosen as A4, which is 440 Hz
|
||||
// and
|
||||
// a = 2 ^ (1/12)
|
||||
// n is the number of notes you are away from A4.
|
||||
// One can see that the frequency will double every 12 notes.
|
||||
// This function exploits this property by defining the frequencies of the
|
||||
// 12 lowest notes allowed and then doubling the appropriate frequency
|
||||
// the appropriate number of times to get the frequency for the specified
|
||||
// note.
|
||||
|
||||
// if note = 16, freq = 41.2 Hz (E1 - lower limit as freq must be >40 Hz)
|
||||
// if note = 57, freq = 440 Hz (A4 - central value of ET Scale)
|
||||
// if note = 111, freq = 9.96 kHz (D#9 - upper limit, freq must be <10 kHz)
|
||||
// if note = 255, freq = 1 kHz and buzzer is silent (silent note)
|
||||
|
||||
// The most significant bit of freq is the "divide by 10" bit. If set,
|
||||
// the units for frequency are .1 Hz, not Hz, and freq must be divided
|
||||
// by 10 to get the true frequency in Hz. This allows for an extra digit
|
||||
// of resolution for low frequencies without the need for using floats.
|
||||
|
||||
unsigned int freq = 0;
|
||||
unsigned char offset_note = note - 16;
|
||||
|
||||
if (note == SILENT_NOTE || volume == 0)
|
||||
{
|
||||
freq = 1000; // silent notes => use 1kHz freq (for cycle counter)
|
||||
playFrequency(freq, dur, 0);
|
||||
return;
|
||||
}
|
||||
|
||||
if (note <= 16)
|
||||
offset_note = 0;
|
||||
else if (offset_note > 95)
|
||||
offset_note = 95;
|
||||
|
||||
unsigned char exponent = offset_note / 12;
|
||||
|
||||
// frequency table for the lowest 12 allowed notes
|
||||
// frequencies are specified in tenths of a Hertz for added resolution
|
||||
switch (offset_note - exponent * 12) // equivalent to (offset_note % 12)
|
||||
{
|
||||
case 0: // note E1 = 41.2 Hz
|
||||
freq = 412;
|
||||
break;
|
||||
case 1: // note F1 = 43.7 Hz
|
||||
freq = 437;
|
||||
break;
|
||||
case 2: // note F#1 = 46.3 Hz
|
||||
freq = 463;
|
||||
break;
|
||||
case 3: // note G1 = 49.0 Hz
|
||||
freq = 490;
|
||||
break;
|
||||
case 4: // note G#1 = 51.9 Hz
|
||||
freq = 519;
|
||||
break;
|
||||
case 5: // note A1 = 55.0 Hz
|
||||
freq = 550;
|
||||
break;
|
||||
case 6: // note A#1 = 58.3 Hz
|
||||
freq = 583;
|
||||
break;
|
||||
case 7: // note B1 = 61.7 Hz
|
||||
freq = 617;
|
||||
break;
|
||||
case 8: // note C2 = 65.4 Hz
|
||||
freq = 654;
|
||||
break;
|
||||
case 9: // note C#2 = 69.3 Hz
|
||||
freq = 693;
|
||||
break;
|
||||
case 10: // note D2 = 73.4 Hz
|
||||
freq = 734;
|
||||
break;
|
||||
case 11: // note D#2 = 77.8 Hz
|
||||
freq = 778;
|
||||
break;
|
||||
}
|
||||
|
||||
if (exponent < 7)
|
||||
{
|
||||
freq = freq << exponent; // frequency *= 2 ^ exponent
|
||||
if (exponent > 1) // if the frequency is greater than 160 Hz
|
||||
freq = (freq + 5) / 10; // we don't need the extra resolution
|
||||
else
|
||||
freq += DIV_BY_10; // else keep the added digit of resolution
|
||||
}
|
||||
else
|
||||
freq = (freq * 64 + 2) / 5; // == freq * 2^7 / 10 without int overflow
|
||||
|
||||
if (volume > 15)
|
||||
volume = 15;
|
||||
playFrequency(freq, dur, volume); // set buzzer this freq/duration
|
||||
}
|
||||
|
||||
|
||||
|
||||
// Returns 1 if the buzzer is currently playing, otherwise it returns 0
|
||||
unsigned char ZumoBuzzer::isPlaying()
|
||||
{
|
||||
return !buzzerFinished || buzzerSequence != 0;
|
||||
}
|
||||
|
||||
|
||||
// Plays the specified sequence of notes. If the play mode is
|
||||
// PLAY_AUTOMATIC, the sequence of notes will play with no further
|
||||
// action required by the user. If the play mode is PLAY_CHECK,
|
||||
// the user will need to call playCheck() in the main loop to initiate
|
||||
// the playing of each new note in the sequence. The play mode can
|
||||
// be changed while the sequence is playing.
|
||||
// This is modeled after the PLAY commands in GW-BASIC, with just a
|
||||
// few differences.
|
||||
//
|
||||
// The notes are specified by the characters C, D, E, F, G, A, and
|
||||
// B, and they are played by default as "quarter notes" with a
|
||||
// length of 500 ms. This corresponds to a tempo of 120
|
||||
// beats/min. Other durations can be specified by putting a number
|
||||
// immediately after the note. For example, C8 specifies C played as an
|
||||
// eighth note, with half the duration of a quarter note. The special
|
||||
// note R plays a rest (no sound).
|
||||
//
|
||||
// Various control characters alter the sound:
|
||||
// '>' plays the next note one octave higher
|
||||
//
|
||||
// '<' plays the next note one octave lower
|
||||
//
|
||||
// '+' or '#' after a note raises any note one half-step
|
||||
//
|
||||
// '-' after a note lowers any note one half-step
|
||||
//
|
||||
// '.' after a note "dots" it, increasing the length by
|
||||
// 50%. Each additional dot adds half as much as the
|
||||
// previous dot, so that "A.." is 1.75 times the length of
|
||||
// "A".
|
||||
//
|
||||
// 'O' followed by a number sets the octave (default: O4).
|
||||
//
|
||||
// 'T' followed by a number sets the tempo (default: T120).
|
||||
//
|
||||
// 'L' followed by a number sets the default note duration to
|
||||
// the type specified by the number: 4 for quarter notes, 8
|
||||
// for eighth notes, 16 for sixteenth notes, etc.
|
||||
// (default: L4)
|
||||
//
|
||||
// 'V' followed by a number from 0-15 sets the music volume.
|
||||
// (default: V15)
|
||||
//
|
||||
// 'MS' sets all subsequent notes to play staccato - each note is played
|
||||
// for 1/2 of its allotted time, followed by an equal period
|
||||
// of silence.
|
||||
//
|
||||
// 'ML' sets all subsequent notes to play legato - each note is played
|
||||
// for its full length. This is the default setting.
|
||||
//
|
||||
// '!' resets all persistent settings to their defaults.
|
||||
//
|
||||
// The following plays a c major scale up and back down:
|
||||
// play("L16 V8 cdefgab>cbagfedc");
|
||||
//
|
||||
// Here is an example from Bach:
|
||||
// play("T240 L8 a gafaeada c+adaeafa <aa<bac#ada c#adaeaf4");
|
||||
void ZumoBuzzer::play(const char *notes)
|
||||
{
|
||||
DISABLE_TIMER_INTERRUPT(); // prevent this from being interrupted
|
||||
buzzerSequence = notes;
|
||||
use_program_space = 0;
|
||||
staccato_rest_duration = 0;
|
||||
nextNote(); // this re-enables the timer1 interrupt
|
||||
}
|
||||
|
||||
void ZumoBuzzer::playFromProgramSpace(const char *notes_p)
|
||||
{
|
||||
DISABLE_TIMER_INTERRUPT(); // prevent this from being interrupted
|
||||
buzzerSequence = notes_p;
|
||||
use_program_space = 1;
|
||||
staccato_rest_duration = 0;
|
||||
nextNote(); // this re-enables the timer1 interrupt
|
||||
}
|
||||
|
||||
|
||||
// stop all sound playback immediately
|
||||
void ZumoBuzzer::stopPlaying()
|
||||
{
|
||||
DISABLE_TIMER_INTERRUPT(); // disable interrupts
|
||||
|
||||
#ifdef __AVR_ATmega32U4__
|
||||
TCCR4B = (TCCR4B & 0xF0) | TIMER4_CLK_8; // select IO clock
|
||||
unsigned int top = (F_CPU/16) / 1000; // set TOP for freq = 1 kHz:
|
||||
TC4H = top >> 8; // top 2 bits... (TC4H temporarily stores top 2 bits of 10-bit accesses)
|
||||
OCR4C = top; // and bottom 8 bits
|
||||
TC4H = 0; // 0% duty cycle: top 2 bits...
|
||||
OCR4D = 0; // and bottom 8 bits
|
||||
#else
|
||||
TCCR2B = (TCCR2B & 0xF8) | TIMER2_CLK_32; // select IO clock
|
||||
OCR2A = (F_CPU/64) / 1000; // set TOP for freq = 1 kHz
|
||||
OCR2B = 0; // 0% duty cycle
|
||||
#endif
|
||||
|
||||
buzzerFinished = 1;
|
||||
buzzerSequence = 0;
|
||||
}
|
||||
|
||||
// Gets the current character, converting to lower-case and skipping
|
||||
// spaces. For any spaces, this automatically increments sequence!
|
||||
static char currentCharacter()
|
||||
{
|
||||
char c = 0;
|
||||
do
|
||||
{
|
||||
if(use_program_space)
|
||||
c = pgm_read_byte(buzzerSequence);
|
||||
else
|
||||
c = *buzzerSequence;
|
||||
|
||||
if(c >= 'A' && c <= 'Z')
|
||||
c += 'a'-'A';
|
||||
} while(c == ' ' && (buzzerSequence ++));
|
||||
|
||||
return c;
|
||||
}
|
||||
|
||||
// Returns the numerical argument specified at buzzerSequence[0] and
|
||||
// increments sequence to point to the character immediately after the
|
||||
// argument.
|
||||
static unsigned int getNumber()
|
||||
{
|
||||
unsigned int arg = 0;
|
||||
|
||||
// read all digits, one at a time
|
||||
char c = currentCharacter();
|
||||
while(c >= '0' && c <= '9')
|
||||
{
|
||||
arg *= 10;
|
||||
arg += c-'0';
|
||||
buzzerSequence ++;
|
||||
c = currentCharacter();
|
||||
}
|
||||
|
||||
return arg;
|
||||
}
|
||||
|
||||
static void nextNote()
|
||||
{
|
||||
unsigned char note = 0;
|
||||
unsigned char rest = 0;
|
||||
unsigned char tmp_octave = octave; // the octave for this note
|
||||
unsigned int tmp_duration; // the duration of this note
|
||||
unsigned int dot_add;
|
||||
|
||||
char c; // temporary variable
|
||||
|
||||
// if we are playing staccato, after every note we play a rest
|
||||
if(staccato && staccato_rest_duration)
|
||||
{
|
||||
ZumoBuzzer::playNote(SILENT_NOTE, staccato_rest_duration, 0);
|
||||
staccato_rest_duration = 0;
|
||||
return;
|
||||
}
|
||||
|
||||
parse_character:
|
||||
|
||||
// Get current character
|
||||
c = currentCharacter();
|
||||
buzzerSequence ++;
|
||||
|
||||
// Interpret the character.
|
||||
switch(c)
|
||||
{
|
||||
case '>':
|
||||
// shift the octave temporarily up
|
||||
tmp_octave ++;
|
||||
goto parse_character;
|
||||
case '<':
|
||||
// shift the octave temporarily down
|
||||
tmp_octave --;
|
||||
goto parse_character;
|
||||
case 'a':
|
||||
note = NOTE_A(0);
|
||||
break;
|
||||
case 'b':
|
||||
note = NOTE_B(0);
|
||||
break;
|
||||
case 'c':
|
||||
note = NOTE_C(0);
|
||||
break;
|
||||
case 'd':
|
||||
note = NOTE_D(0);
|
||||
break;
|
||||
case 'e':
|
||||
note = NOTE_E(0);
|
||||
break;
|
||||
case 'f':
|
||||
note = NOTE_F(0);
|
||||
break;
|
||||
case 'g':
|
||||
note = NOTE_G(0);
|
||||
break;
|
||||
case 'l':
|
||||
// set the default note duration
|
||||
note_type = getNumber();
|
||||
duration = whole_note_duration/note_type;
|
||||
goto parse_character;
|
||||
case 'm':
|
||||
// set music staccato or legato
|
||||
if(currentCharacter() == 'l')
|
||||
staccato = false;
|
||||
else
|
||||
{
|
||||
staccato = true;
|
||||
staccato_rest_duration = 0;
|
||||
}
|
||||
buzzerSequence ++;
|
||||
goto parse_character;
|
||||
case 'o':
|
||||
// set the octave permanently
|
||||
octave = getNumber();
|
||||
tmp_octave = octave;
|
||||
goto parse_character;
|
||||
case 'r':
|
||||
// Rest - the note value doesn't matter.
|
||||
rest = 1;
|
||||
break;
|
||||
case 't':
|
||||
// set the tempo
|
||||
whole_note_duration = 60*400/getNumber()*10;
|
||||
duration = whole_note_duration/note_type;
|
||||
goto parse_character;
|
||||
case 'v':
|
||||
// set the volume
|
||||
volume = getNumber();
|
||||
goto parse_character;
|
||||
case '!':
|
||||
// reset to defaults
|
||||
octave = 4;
|
||||
whole_note_duration = 2000;
|
||||
note_type = 4;
|
||||
duration = 500;
|
||||
volume = 15;
|
||||
staccato = 0;
|
||||
// reset temp variables that depend on the defaults
|
||||
tmp_octave = octave;
|
||||
tmp_duration = duration;
|
||||
goto parse_character;
|
||||
default:
|
||||
buzzerSequence = 0;
|
||||
return;
|
||||
}
|
||||
|
||||
note += tmp_octave*12;
|
||||
|
||||
// handle sharps and flats
|
||||
c = currentCharacter();
|
||||
while(c == '+' || c == '#')
|
||||
{
|
||||
buzzerSequence ++;
|
||||
note ++;
|
||||
c = currentCharacter();
|
||||
}
|
||||
while(c == '-')
|
||||
{
|
||||
buzzerSequence ++;
|
||||
note --;
|
||||
c = currentCharacter();
|
||||
}
|
||||
|
||||
// set the duration of just this note
|
||||
tmp_duration = duration;
|
||||
|
||||
// If the input is 'c16', make it a 16th note, etc.
|
||||
if(c > '0' && c < '9')
|
||||
tmp_duration = whole_note_duration/getNumber();
|
||||
|
||||
// Handle dotted notes - the first dot adds 50%, and each
|
||||
// additional dot adds 50% of the previous dot.
|
||||
dot_add = tmp_duration/2;
|
||||
while(currentCharacter() == '.')
|
||||
{
|
||||
buzzerSequence ++;
|
||||
tmp_duration += dot_add;
|
||||
dot_add /= 2;
|
||||
}
|
||||
|
||||
if(staccato)
|
||||
{
|
||||
staccato_rest_duration = tmp_duration / 2;
|
||||
tmp_duration -= staccato_rest_duration;
|
||||
}
|
||||
|
||||
// this will re-enable the timer1 overflow interrupt
|
||||
ZumoBuzzer::playNote(rest ? SILENT_NOTE : note, tmp_duration, volume);
|
||||
}
|
||||
|
||||
|
||||
// This puts play() into a mode where instead of advancing to the
|
||||
// next note in the sequence automatically, it waits until the
|
||||
// function playCheck() is called. The idea is that you can
|
||||
// put playCheck() in your main loop and avoid potential
|
||||
// delays due to the note sequence being checked in the middle of
|
||||
// a time sensitive calculation. It is recommended that you use
|
||||
// this function if you are doing anything that can't tolerate
|
||||
// being interrupted for more than a few microseconds.
|
||||
// Note that the play mode can be changed while a sequence is being
|
||||
// played.
|
||||
//
|
||||
// Usage: playMode(PLAY_AUTOMATIC) makes it automatic (the
|
||||
// default), playMode(PLAY_CHECK) sets it to a mode where you have
|
||||
// to call playCheck().
|
||||
void ZumoBuzzer::playMode(unsigned char mode)
|
||||
{
|
||||
play_mode_setting = mode;
|
||||
|
||||
// We want to check to make sure that we didn't miss a note if we
|
||||
// are going out of play-check mode.
|
||||
if(mode == PLAY_AUTOMATIC)
|
||||
playCheck();
|
||||
}
|
||||
|
||||
|
||||
// Checks whether it is time to start another note, and starts
|
||||
// it if so. If it is not yet time to start the next note, this method
|
||||
// returns without doing anything. Call this as often as possible
|
||||
// in your main loop to avoid delays between notes in the sequence.
|
||||
//
|
||||
// Returns true if it is still playing.
|
||||
unsigned char ZumoBuzzer::playCheck()
|
||||
{
|
||||
if(buzzerFinished && buzzerSequence != 0)
|
||||
nextNote();
|
||||
return buzzerSequence != 0;
|
||||
}
|
||||
345
libraries/Zumo/ZumoBuzzer.h
Executable file
345
libraries/Zumo/ZumoBuzzer.h
Executable file
@@ -0,0 +1,345 @@
|
||||
/*! \file ZumoBuzzer.h
|
||||
*
|
||||
* See the ZumoBuzzer class reference for more information about this library.
|
||||
*
|
||||
* \class ZumoBuzzer ZumoBuzzer.h
|
||||
* \brief Play beeps and music with buzzer
|
||||
*
|
||||
* The ZumoBuzzer library allows various sounds to be played through the buzzer
|
||||
* on the Zumo Shield, from simple beeps to complex tunes. The buzzer is
|
||||
* controlled using a PWM output of Timer 2 (on the Arduino Uno and other
|
||||
* ATmega328/168 boards) or Timer 4 (on the Arduino Leonardo and other
|
||||
* ATmega32U4 boards), so it will conflict with any other uses of that timer.
|
||||
*
|
||||
* Note durations are timed using a timer overflow interrupt
|
||||
* (`TIMER2_OVF`/`TIMER4_OVF`), which will briefly interrupt execution of your
|
||||
* main program at the frequency of the sound being played. In most cases, the
|
||||
* interrupt-handling routine is very short (several microseconds). However,
|
||||
* when playing a sequence of notes in `PLAY_AUTOMATIC` mode (the default mode)
|
||||
* with the `play()` command, this interrupt takes much longer than normal
|
||||
* (perhaps several hundred microseconds) every time it starts a new note. It is
|
||||
* important to take this into account when writing timing-critical code.
|
||||
*
|
||||
* The ZumoBuzzer library is fully compatible with the OrangutanBuzzer functions
|
||||
* in the [Pololu AVR C/C++ Library](http://www.pololu.com/docs/0J18), so any
|
||||
* sequences and melodies written for OrangutanBuzzer functions will also work
|
||||
* with the equivalent ZumoBuzzer functions.
|
||||
*/
|
||||
|
||||
#ifndef ZumoBuzzer_h
|
||||
#define ZumoBuzzer_h
|
||||
|
||||
#define PLAY_AUTOMATIC 0
|
||||
#define PLAY_CHECK 1
|
||||
|
||||
// n
|
||||
// Equal Tempered Scale is given by f = f * a
|
||||
// n o
|
||||
//
|
||||
// where f is chosen as A above middle C (A4) at f = 440 Hz
|
||||
// o o
|
||||
// and a is given by the twelfth root of 2 (~1.059463094359)
|
||||
|
||||
/*! \anchor note_macros
|
||||
*
|
||||
* \name Note Macros
|
||||
* \a x specifies the octave of the note
|
||||
* @{
|
||||
*/
|
||||
#define NOTE_C(x) ( 0 + (x)*12)
|
||||
#define NOTE_C_SHARP(x) ( 1 + (x)*12)
|
||||
#define NOTE_D_FLAT(x) ( 1 + (x)*12)
|
||||
#define NOTE_D(x) ( 2 + (x)*12)
|
||||
#define NOTE_D_SHARP(x) ( 3 + (x)*12)
|
||||
#define NOTE_E_FLAT(x) ( 3 + (x)*12)
|
||||
#define NOTE_E(x) ( 4 + (x)*12)
|
||||
#define NOTE_F(x) ( 5 + (x)*12)
|
||||
#define NOTE_F_SHARP(x) ( 6 + (x)*12)
|
||||
#define NOTE_G_FLAT(x) ( 6 + (x)*12)
|
||||
#define NOTE_G(x) ( 7 + (x)*12)
|
||||
#define NOTE_G_SHARP(x) ( 8 + (x)*12)
|
||||
#define NOTE_A_FLAT(x) ( 8 + (x)*12)
|
||||
#define NOTE_A(x) ( 9 + (x)*12)
|
||||
#define NOTE_A_SHARP(x) (10 + (x)*12)
|
||||
#define NOTE_B_FLAT(x) (10 + (x)*12)
|
||||
#define NOTE_B(x) (11 + (x)*12)
|
||||
|
||||
/*! \brief silences buzzer for the note duration */
|
||||
#define SILENT_NOTE 0xFF
|
||||
|
||||
/*! \brief frequency bit that indicates Hz/10<br>
|
||||
* e.g. \a frequency = `(445 | DIV_BY_10)` gives a frequency of 44.5 Hz
|
||||
*/
|
||||
#define DIV_BY_10 (1 << 15)
|
||||
/*! @} */
|
||||
|
||||
class ZumoBuzzer
|
||||
{
|
||||
public:
|
||||
|
||||
// constructor
|
||||
ZumoBuzzer();
|
||||
|
||||
/*! \brief Plays the specified frequency for the specified duration.
|
||||
*
|
||||
* \param freq Frequency to play in Hz (or 0.1 Hz if the `DIV_BY_10` bit
|
||||
* is set).
|
||||
* \param duration Duration of the note in milliseconds.
|
||||
* \param volume Volume of the note (0--15).
|
||||
*
|
||||
* The \a frequency argument must be between 40 Hz and 10 kHz. If the most
|
||||
* significant bit of \a frequency is set, the frequency played is the value
|
||||
* of the lower 15 bits of \a frequency in units of 0.1 Hz. Therefore, you can
|
||||
* play a frequency of 44.5 Hz by using a \a frequency of `(DIV_BY_10 | 445)`.
|
||||
* If the most significant bit of \a frequency is not set, the units for
|
||||
* frequency are Hz. The \a volume argument controls the buzzer volume, with
|
||||
* 15 being the loudest and 0 being the quietest. A \a volume of 15 supplies
|
||||
* the buzzer with a 50% duty cycle PWM at the specified \a frequency.
|
||||
* Lowering \a volume by one halves the duty cycle (so 14 gives a 25% duty
|
||||
* cycle, 13 gives a 12.5% duty cycle, etc). The volume control is somewhat
|
||||
* crude (especially on the ATmega328/168) and should be thought of as a bonus
|
||||
* feature.
|
||||
*
|
||||
* This function plays the note in the background while your program continues
|
||||
* to execute. If you call another buzzer function while the note is playing,
|
||||
* the new function call will overwrite the previous and take control of the
|
||||
* buzzer. If you want to string notes together, you should either use the
|
||||
* `play()` function or put an appropriate delay after you start a note
|
||||
* playing. You can use the `is_playing()` function to figure out when the
|
||||
* buzzer is through playing its note or melody.
|
||||
*
|
||||
* ### Example ###
|
||||
*
|
||||
* ~~~{.ino}
|
||||
* ZumoBuzzer buzzer;
|
||||
*
|
||||
* ...
|
||||
*
|
||||
* // play a 6 kHz note for 250 ms at a lower volume
|
||||
* buzzer.playFrequency(6000, 250, 12);
|
||||
*
|
||||
* // wait for buzzer to finish playing the note
|
||||
* while (buzzer.isPlaying());
|
||||
*
|
||||
* // play a 44.5 Hz note for 1 s at full volume
|
||||
* buzzer.playFrequency(DIV_BY_10 | 445, 1000, 15);
|
||||
* ~~~
|
||||
*
|
||||
* \warning \a frequency × \a duration / 1000 must be no greater than
|
||||
0xFFFF (65535). This means you can't use a max duration of 65535 ms for
|
||||
frequencies greater than 1 kHz. For example, the maximum duration you can
|
||||
use for a frequency of 10 kHz is 6553 ms. If you use a duration longer than
|
||||
this, you will produce an integer overflow that can result in unexpected
|
||||
behavior.
|
||||
*/
|
||||
static void playFrequency(unsigned int freq, unsigned int duration,
|
||||
unsigned char volume);
|
||||
|
||||
/*! \brief Plays the specified note for the specified duration.
|
||||
*
|
||||
* \param note Note to play (see \ref note_macros "Note Macros").
|
||||
* \param duration Duration of the note in milliseconds.
|
||||
* \param volume Volume of the note (0--15).
|
||||
*
|
||||
* The \a note argument is an enumeration for the notes of the equal tempered
|
||||
* scale (ETS). See \ref note_macros "Note Macros" for more information. The
|
||||
* \a volume argument controls the buzzer volume, with 15 being the loudest
|
||||
* and 0 being the quietest. A \a volume of 15 supplies the buzzer with a 50%
|
||||
* duty cycle PWM at the specified \a frequency. Lowering \a volume by one
|
||||
* halves the duty cycle (so 14 gives a 25% duty cycle, 13 gives a 12.5% duty
|
||||
* cycle, etc). The volume control is somewhat crude (especially on the
|
||||
* ATmega328/168) and should be thought of as a bonus feature.
|
||||
*
|
||||
* This function plays the note in the background while your program continues
|
||||
* to execute. If you call another buzzer function while the note is playing,
|
||||
* the new function call will overwrite the previous and take control of the
|
||||
* buzzer. If you want to string notes together, you should either use the
|
||||
* `play()` function or put an appropriate delay after you start a note
|
||||
* playing. You can use the `is_playing()` function to figure out when the
|
||||
* buzzer is through playing its note or melody.
|
||||
*/
|
||||
static void playNote(unsigned char note, unsigned int duration,
|
||||
unsigned char volume);
|
||||
|
||||
/*! \brief Plays the specified sequence of notes.
|
||||
*
|
||||
* \param sequence Char array containing a sequence of notes to play.
|
||||
*
|
||||
* If the play mode is `PLAY_AUTOMATIC` (default), the sequence of notes will
|
||||
* play with no further action required by the user. If the play mode is
|
||||
* `PLAY_CHECK`, the user will need to call `playCheck()` in the main loop to
|
||||
* initiate the playing of each new note in the sequence. The play mode can be
|
||||
* changed while the sequence is playing. The sequence syntax is modeled after
|
||||
* the PLAY commands in GW-BASIC, with just a few differences.
|
||||
*
|
||||
* The notes are specified by the characters **C**, **D**, **E**, **F**,
|
||||
* **G**, **A**, and **B**, and they are played by default as "quarter notes"
|
||||
* with a length of 500 ms. This corresponds to a tempo of 120 beats/min.
|
||||
* Other durations can be specified by putting a number immediately after the
|
||||
* note. For example, C8 specifies C played as an eighth note, with half the
|
||||
* duration of a quarter note. The special note **R** plays a rest (no sound).
|
||||
* The sequence parser is case-insensitive and ignores spaces, which may be
|
||||
* used to format your music nicely.
|
||||
*
|
||||
* Various control characters alter the sound:
|
||||
* <table>
|
||||
* <tr><th>Control character(s)</th><th>Effect</th></tr>
|
||||
* <tr><td><strong>A--G</strong></td>
|
||||
* <td>Specifies a note that will be played.</td></tr>
|
||||
* <tr><td><strong>R</strong></td>
|
||||
* <td>Specifies a rest (no sound for the duration of the note).</td></tr>
|
||||
* <tr><td><strong>+</strong></strong> or <strong>#</strong> after a note</td>
|
||||
* <td>Raises the preceding note one half-step.</td></tr>
|
||||
* <tr><td><strong>-</strong> after a note</td>
|
||||
* <td>Lowers the preceding note one half-step.</td></tr>
|
||||
* <tr><td><strong>1--2000</strong> after a note</td>
|
||||
* <td>Determines the duration of the preceding note. For example, C16
|
||||
* specifies C played as a sixteenth note (1/16th the length of a
|
||||
* whole note).</td></tr>
|
||||
* <tr><td><strong>.</strong> after a note</td>
|
||||
* <td>"Dots" the preceding note, increasing the length by 50%. Each
|
||||
* additional dot adds half as much as the previous dot, so that "A.."
|
||||
* is 1.75 times the length of "A".</td></tr>
|
||||
* <tr><td><strong>></strong> before a note</td>
|
||||
* <td>Plays the following note one octave higher.</td></tr>
|
||||
* <tr><td><strong><</strong> before a note</td>
|
||||
* <td>Plays the following note one octave lower.</td></tr>
|
||||
* <tr><td><strong>O</strong> followed by a number</td>
|
||||
* <td>Sets the octave. (default: **O4**)</td></tr>
|
||||
* <tr><td><strong>T</strong> followed by a number</td>
|
||||
* <td>Sets the tempo in beats per minute (BPM). (default: **T120**)</td></tr>
|
||||
* <tr><td><strong>L</strong> followed by a number</td>
|
||||
* <td>Sets the default note duration to the type specified by the number:
|
||||
* 4 for quarter notes, 8 for eighth notes, 16 for sixteenth notes,
|
||||
* etc. (default: **L4**)</td></tr>
|
||||
* <tr><td><strong>V</strong> followed by a number</td>
|
||||
* <td>Sets the music volume (0--15). (default: **V15**)</td></tr>
|
||||
* <tr><td><strong>MS</strong></td>
|
||||
* <td>Sets all subsequent notes to play play staccato -- each note is
|
||||
* played for 1/2 of its allotted time, followed by an equal period of
|
||||
* silence.</td></tr>
|
||||
* <tr><td><strong>ML</strong></td>
|
||||
* <td>Sets all subsequent notes to play legato -- each note is played for
|
||||
* full length. This is the default setting.</td></tr>
|
||||
* <tr><td><strong>!</strong></td>
|
||||
* <td>Resets the octave, tempo, duration, volume, and staccato setting to
|
||||
* their default values. These settings persist from one `play()` to the
|
||||
* next, which allows you to more conveniently break up your music into
|
||||
* reusable sections.</td></tr>
|
||||
* </table>
|
||||
*
|
||||
* This function plays the string of notes in the background while your
|
||||
* program continues to execute. If you call another buzzer function while the
|
||||
* melody is playing, the new function call will overwrite the previous and
|
||||
* take control of the buzzer. If you want to string melodies together, you
|
||||
* should put an appropriate delay after you start a melody playing. You can
|
||||
* use the `is_playing()` function to figure out when the buzzer is through
|
||||
* playing the melody.
|
||||
*
|
||||
* ### Example ###
|
||||
*
|
||||
* ~~~{.ino}
|
||||
* ZumoBuzzer buzzer;
|
||||
*
|
||||
* ...
|
||||
*
|
||||
* // play a C major scale up and back down:
|
||||
* buzzer.play("!L16 V8 cdefgab>cbagfedc");
|
||||
* while (buzzer.isPlaying());
|
||||
*
|
||||
* // the first few measures of Bach's fugue in D-minor
|
||||
* buzzer.play("!T240 L8 agafaea dac+adaea fa<aa<bac#a dac#adaea f4");
|
||||
* ~~~
|
||||
*/
|
||||
static void play(const char *sequence);
|
||||
|
||||
/*! \brief Plays the specified sequence of notes from program space.
|
||||
*
|
||||
* \param sequence Char array in program space containing a sequence of notes
|
||||
* to play.
|
||||
*
|
||||
* A version of `play()` that takes a pointer to program space instead of RAM.
|
||||
* This is desirable since RAM is limited and the string must be in program
|
||||
* space anyway.
|
||||
*
|
||||
* ### Example ###
|
||||
*
|
||||
* ~~~{.ino}
|
||||
* #include <avr/pgmspace.h>
|
||||
*
|
||||
* ZumoBuzzer buzzer;
|
||||
* const char melody[] PROGMEM = "!L16 V8 cdefgab>cbagfedc";
|
||||
*
|
||||
* ...
|
||||
*
|
||||
* buzzer.playFromProgramSpace(melody);
|
||||
* ~~~
|
||||
*/
|
||||
static void playFromProgramSpace(const char *sequence_p);
|
||||
|
||||
/*! \brief Controls whether `play()` sequence is played automatically or
|
||||
* must be driven with `playCheck()`.
|
||||
*
|
||||
* \param mode Play mode (either `PLAY_AUTOMATIC` or `PLAY_CHECK`).
|
||||
*
|
||||
* This method lets you determine whether the notes of the `play()` sequence
|
||||
* are played automatically in the background or are driven by the
|
||||
* `play_check()` method. If \a mode is `PLAY_AUTOMATIC`, the sequence will
|
||||
* play automatically in the background, driven by the timer overflow
|
||||
* interrupt. The interrupt will take a considerable amount of time to execute
|
||||
* when it starts the next note in the sequence playing, so it is recommended
|
||||
* that you do not use automatic-play if you cannot tolerate being interrupted
|
||||
* for more than a few microseconds. If \a mode is `PLAY_CHECK`, you can
|
||||
* control when the next note in the sequence is played by calling the
|
||||
* `play_check()` method at acceptable points in your main loop. If your main
|
||||
* loop has substantial delays, it is recommended that you use automatic-play
|
||||
* mode rather than play-check mode. Note that the play mode can be changed
|
||||
* while the sequence is being played. The mode is set to `PLAY_AUTOMATIC` by
|
||||
* default.
|
||||
*/
|
||||
static void playMode(unsigned char mode);
|
||||
|
||||
/*! \brief Starts the next note in a sequence, if necessary, in `PLAY_CHECK`
|
||||
* mode.
|
||||
*
|
||||
* \return 0 if sequence is complete, 1 otherwise.
|
||||
*
|
||||
* This method only needs to be called if you are in `PLAY_CHECK` mode. It
|
||||
* checks to see whether it is time to start another note in the sequence
|
||||
* initiated by `play()`, and starts it if so. If it is not yet time to start
|
||||
* the next note, this method returns without doing anything. Call this as
|
||||
* often as possible in your main loop to avoid delays between notes in the
|
||||
* sequence. This method returns 0 (false) if the melody to be played is
|
||||
* complete, otherwise it returns 1 (true).
|
||||
*/
|
||||
static unsigned char playCheck();
|
||||
|
||||
/*! \brief Checks whether a note, frequency, or sequence is being played.
|
||||
*
|
||||
* \return 1 if the buzzer is current playing a note, frequency, or sequence;
|
||||
* 0 otherwise.
|
||||
*
|
||||
* This method returns 1 (true) if the buzzer is currently playing a
|
||||
* note/frequency or if it is still playing a sequence started by `play()`.
|
||||
* Otherwise, it returns 0 (false). You can poll this method to determine when
|
||||
* it's time to play the next note in a sequence, or you can use it as the
|
||||
* argument to a delay loop to wait while the buzzer is busy.
|
||||
*/
|
||||
static unsigned char isPlaying();
|
||||
|
||||
/*! \brief Stops any note, frequency, or melody being played.
|
||||
*
|
||||
* This method will immediately silence the buzzer and terminate any
|
||||
* note/frequency/melody that is currently playing.
|
||||
*/
|
||||
static void stopPlaying();
|
||||
|
||||
|
||||
private:
|
||||
|
||||
// initializes timer for buzzer control
|
||||
static void init2();
|
||||
static void init();
|
||||
};
|
||||
|
||||
#endif
|
||||
114
libraries/Zumo/ZumoMotors.cpp
Executable file
114
libraries/Zumo/ZumoMotors.cpp
Executable file
@@ -0,0 +1,114 @@
|
||||
#include "ZumoMotors.h"
|
||||
|
||||
#define PWM_L 10
|
||||
#define PWM_R 9
|
||||
#define DIR_L 8
|
||||
#define DIR_R 7
|
||||
|
||||
#if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328P__) || defined (__AVR_ATmega32U4__)
|
||||
#define USE_20KHZ_PWM
|
||||
#endif
|
||||
|
||||
static boolean flipLeft = false;
|
||||
static boolean flipRight = false;
|
||||
|
||||
// constructor (doesn't do anything)
|
||||
ZumoMotors::ZumoMotors()
|
||||
{
|
||||
}
|
||||
|
||||
// initialize timer1 to generate the proper PWM outputs to the motor drivers
|
||||
void ZumoMotors::init2()
|
||||
{
|
||||
pinMode(PWM_L, OUTPUT);
|
||||
pinMode(PWM_R, OUTPUT);
|
||||
pinMode(DIR_L, OUTPUT);
|
||||
pinMode(DIR_R, OUTPUT);
|
||||
|
||||
#ifdef USE_20KHZ_PWM
|
||||
// Timer 1 configuration
|
||||
// prescaler: clockI/O / 1
|
||||
// outputs enabled
|
||||
// phase-correct PWM
|
||||
// top of 400
|
||||
//
|
||||
// PWM frequency calculation
|
||||
// 16MHz / 1 (prescaler) / 2 (phase-correct) / 400 (top) = 20kHz
|
||||
TCCR1A = 0b10100000;
|
||||
TCCR1B = 0b00010001;
|
||||
ICR1 = 400;
|
||||
#endif
|
||||
}
|
||||
|
||||
// enable/disable flipping of left motor
|
||||
void ZumoMotors::flipLeftMotor(boolean flip)
|
||||
{
|
||||
flipLeft = flip;
|
||||
}
|
||||
|
||||
// enable/disable flipping of right motor
|
||||
void ZumoMotors::flipRightMotor(boolean flip)
|
||||
{
|
||||
flipRight = flip;
|
||||
}
|
||||
|
||||
// set speed for left motor; speed is a number between -400 and 400
|
||||
void ZumoMotors::setLeftSpeed(int speed)
|
||||
{
|
||||
init(); // initialize if necessary
|
||||
|
||||
boolean reverse = 0;
|
||||
|
||||
if (speed < 0)
|
||||
{
|
||||
speed = -speed; // make speed a positive quantity
|
||||
reverse = 1; // preserve the direction
|
||||
}
|
||||
if (speed > 400) // Max
|
||||
speed = 400;
|
||||
|
||||
#ifdef USE_20KHZ_PWM
|
||||
OCR1B = speed;
|
||||
#else
|
||||
analogWrite(PWM_L, speed * 51 / 80); // default to using analogWrite, mapping 400 to 255
|
||||
#endif
|
||||
|
||||
if (reverse ^ flipLeft) // flip if speed was negative or flipLeft setting is active, but not both
|
||||
digitalWrite(DIR_L, HIGH);
|
||||
else
|
||||
digitalWrite(DIR_L, LOW);
|
||||
}
|
||||
|
||||
// set speed for right motor; speed is a number between -400 and 400
|
||||
void ZumoMotors::setRightSpeed(int speed)
|
||||
{
|
||||
init(); // initialize if necessary
|
||||
|
||||
boolean reverse = 0;
|
||||
|
||||
if (speed < 0)
|
||||
{
|
||||
speed = -speed; // Make speed a positive quantity
|
||||
reverse = 1; // Preserve the direction
|
||||
}
|
||||
if (speed > 400) // Max PWM dutycycle
|
||||
speed = 400;
|
||||
|
||||
#ifdef USE_20KHZ_PWM
|
||||
OCR1A = speed;
|
||||
#else
|
||||
analogWrite(PWM_R, speed * 51 / 80); // default to using analogWrite, mapping 400 to 255
|
||||
#endif
|
||||
|
||||
if (reverse ^ flipRight) // flip if speed was negative or flipRight setting is active, but not both
|
||||
digitalWrite(DIR_R, HIGH);
|
||||
else
|
||||
digitalWrite(DIR_R, LOW);
|
||||
}
|
||||
|
||||
// set speed for both motors
|
||||
void ZumoMotors::setSpeeds(int leftSpeed, int rightSpeed)
|
||||
{
|
||||
setLeftSpeed(leftSpeed);
|
||||
setRightSpeed(rightSpeed);
|
||||
}
|
||||
48
libraries/Zumo/ZumoMotors.h
Executable file
48
libraries/Zumo/ZumoMotors.h
Executable file
@@ -0,0 +1,48 @@
|
||||
/*! \file ZumoMotors.h
|
||||
*
|
||||
* See the ZumoMotors class reference for more information about this library.
|
||||
*
|
||||
* \class ZumoMotors ZumoMotors.h
|
||||
* \brief Control motor speed and direction
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef ZumoMotors_h
|
||||
#define ZumoMotors_h
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
class ZumoMotors
|
||||
{
|
||||
public:
|
||||
|
||||
// constructor (doesn't do anything)
|
||||
ZumoMotors();
|
||||
|
||||
// enable/disable flipping of motors
|
||||
static void flipLeftMotor(boolean flip);
|
||||
static void flipRightMotor(boolean flip);
|
||||
|
||||
// set speed for left, right, or both motors
|
||||
static void setLeftSpeed(int speed);
|
||||
static void setRightSpeed(int speed);
|
||||
static void setSpeeds(int leftSpeed, int rightSpeed);
|
||||
|
||||
private:
|
||||
|
||||
static inline void init()
|
||||
{
|
||||
static boolean initialized = false;
|
||||
|
||||
if (!initialized)
|
||||
{
|
||||
initialized = true;
|
||||
init2();
|
||||
}
|
||||
}
|
||||
|
||||
// initializes timer1 for proper PWM generation
|
||||
static void init2();
|
||||
};
|
||||
|
||||
#endif
|
||||
408
libraries/Zumo/ZumoReflectanceSensorArray.h
Executable file
408
libraries/Zumo/ZumoReflectanceSensorArray.h
Executable file
@@ -0,0 +1,408 @@
|
||||
/*! \file ZumoReflectanceSensorArray.h
|
||||
*
|
||||
* See the ZumoReflectanceSensorArray class reference for more information about
|
||||
* this library.
|
||||
*
|
||||
* \class ZumoReflectanceSensorArray ZumoReflectanceSensorArray.h
|
||||
* \brief Read from reflectance sensor array
|
||||
*
|
||||
* The ZumoReflectanceSensorArray library provides an interface for using a
|
||||
* [Zumo Reflectance Sensor Array](http://www.pololu.com/product/1419) connected
|
||||
* to a Zumo robot. The library provides access to the raw sensor values as well
|
||||
* as to high level functions including calibration and line-tracking.
|
||||
*
|
||||
* For calibration, memory is allocated using the `malloc()` function. This
|
||||
* conserves RAM: if all six sensors are calibrated with the emitters both on
|
||||
* and off, a total of 48 bytes is dedicated to storing calibration values.
|
||||
* However, for an application where only two sensors are used, and the
|
||||
* emitters are always on during reads, only 4 bytes are required.
|
||||
*
|
||||
* Internally, this library uses all standard Arduino functions such as
|
||||
* `micros()` for timing and `digitalRead()` for getting the sensor values, so
|
||||
* it should work on all Arduinos without conflicting with other libraries.
|
||||
*
|
||||
* ### Calibration ###
|
||||
*
|
||||
* This library allows you to use the `calibrate()` method to easily calibrate
|
||||
* your sensors for the particular conditions it will encounter. Calibrating
|
||||
* your sensors can lead to substantially more reliable sensor readings, which
|
||||
* in turn can help simplify your code. As such, we recommend you build a
|
||||
* calibration phase into your Zumo's initialization routine. This can be as
|
||||
* simple as a fixed duration over which you repeatedly call the `calibrate()`
|
||||
* method.
|
||||
*
|
||||
* During this calibration phase, you will need to expose each of your
|
||||
* reflectance sensors to the lightest and darkest readings they will encounter.
|
||||
* For example, if your Zumo is programmed to be a line follower, you will want
|
||||
* to slide it across the line during the calibration phase so the each sensor
|
||||
* can get a reading of how dark the line is and how light the ground is (or you
|
||||
* can program it to automatically turn back and forth to pass all of the
|
||||
* sensors over the line). The **SensorCalibration** example included with this
|
||||
* library demonstrates a calibration routine.
|
||||
*
|
||||
* ### Reading the sensors
|
||||
*
|
||||
*
|
||||
* This library gives you a number of different ways to read the sensors.
|
||||
*
|
||||
* - You can request raw sensor values using the `read()` method.
|
||||
*
|
||||
* - You can request calibrated sensor values using the `readCalibrated()`
|
||||
* method. Calibrated sensor values will always range from 0 to 1000, with the
|
||||
* extreme values corresponding to the most and least reflective surfaces
|
||||
* encountered during calibration.
|
||||
*
|
||||
* - For line-detection applications, you can request the line location using
|
||||
* the `readLine()` method. This function provides calibrated values
|
||||
* for each sensor and returns an integer that tells you where it thinks the
|
||||
* line is.
|
||||
*
|
||||
* ### Class Inheritance ###
|
||||
*
|
||||
* The ZumoReflectanceSensorArray class is derived from the QTRSensorsRC class,
|
||||
* which is in turn derived from the QTRSensors base class. The QTRSensorsRC and
|
||||
* QTRSensors classes are part of the \ref QTRSensors.h "QTRSensors" library,
|
||||
* which provides more general functionality for working with reflectance
|
||||
* sensors and is included in the Zumo Shield libraries as a dependency for this
|
||||
* library.
|
||||
*
|
||||
* We recommend using the ZumoReflectanceSensorArray library instead of
|
||||
* the \ref QTRSensors.h "QTRSensors" library when programming an Arduino on a
|
||||
* Zumo. For documentation specific to the %QTRSensors library, please see its
|
||||
* [user's guide](http://www.pololu.com/docs/0J19) on Pololu's website.
|
||||
*/
|
||||
|
||||
#ifndef ZumoReflectanceSensorArray_h
|
||||
#define ZumoReflectanceSensorArray_h
|
||||
|
||||
#include <../QTRSensors/QTRSensors.h>
|
||||
#include <Arduino.h>
|
||||
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
// Arduino Leonardo
|
||||
#define ZUMO_SENSOR_ARRAY_DEFAULT_EMITTER_PIN A4
|
||||
#else
|
||||
// Arduino UNO and other ATmega328P/168 Arduinos
|
||||
#define ZUMO_SENSOR_ARRAY_DEFAULT_EMITTER_PIN 2
|
||||
#endif
|
||||
|
||||
class ZumoReflectanceSensorArray : public QTRSensorsRC
|
||||
{
|
||||
public:
|
||||
|
||||
/*! \brief Minimal constructor.
|
||||
*
|
||||
* This version of the constructor performs no initialization. If it is used,
|
||||
* the user must call init() before using the methods in this class.
|
||||
*/
|
||||
ZumoReflectanceSensorArray() {}
|
||||
|
||||
/*! \brief Constructor; initializes with given emitter pin and defaults for
|
||||
* other settings.
|
||||
*
|
||||
* \param emitterPin Pin that turns IR emitters on or off.
|
||||
*
|
||||
* This constructor calls `init(unsigned char emitterPin)` with the specified
|
||||
* emitter pin and default values for other settings.
|
||||
*/
|
||||
ZumoReflectanceSensorArray(unsigned char emitterPin)
|
||||
{
|
||||
init(emitterPin);
|
||||
}
|
||||
|
||||
/*! \brief Constructor; initializes with all settings as given.
|
||||
*
|
||||
* \param pins Array of pin numbers for sensors.
|
||||
* \param numSensors Number of sensors.
|
||||
* \param timeout Maximum duration of reflectance reading in microseconds.
|
||||
* \param emitterPin Pin that turns IR emitters on or off.
|
||||
*
|
||||
* This constructor calls `init(unsigned char * pins, unsigned char
|
||||
* numSensors, unsigned int timeout, unsigned char emitterPin)` with all
|
||||
* settings as given.
|
||||
*/
|
||||
ZumoReflectanceSensorArray(unsigned char * pins, unsigned char numSensors, unsigned int timeout = 2000,
|
||||
unsigned char emitterPin = ZUMO_SENSOR_ARRAY_DEFAULT_EMITTER_PIN)
|
||||
{
|
||||
QTRSensorsRC::init(pins, numSensors, timeout, emitterPin);
|
||||
}
|
||||
|
||||
/*! \brief Initializes with given emitter pin and and defaults for other
|
||||
* settings.
|
||||
*
|
||||
* \param emitterPin Pin that turns IR emitters on or off.
|
||||
*
|
||||
* This function initializes the ZumoReflectanceSensorArray object with the
|
||||
* specified emitter pin. The other settings are set to default values: all
|
||||
* six sensors on the array are active, and a timeout of 2000 microseconds is
|
||||
* used.
|
||||
*
|
||||
* \a emitterPin is the Arduino digital pin that controls whether the IR LEDs
|
||||
* are on or off. This pin is optional; if a valid pin is specified, the
|
||||
* emitters will only be turned on during a reading. If \a emitterPin is not
|
||||
* specified, the emitters will be controlled with pin 2 on the Uno (and other
|
||||
* ATmega328/168 boards) or pin A4 on the Leonardo (and other ATmega32U4
|
||||
* boards). (The "LED ON" jumper on the Zumo Reflectance Sensor Array must be
|
||||
* configured correctly for this to work.) If the value `QTR_NO_EMITTER_PIN`
|
||||
* (255) is used, you can leave the emitter pin disconnected and the IR
|
||||
* emitters will always be on.
|
||||
*/
|
||||
void init(unsigned char emitterPin = ZUMO_SENSOR_ARRAY_DEFAULT_EMITTER_PIN)
|
||||
{
|
||||
unsigned char sensorPins[] = { 4, A3, 11, A0, A2, 5 };
|
||||
QTRSensorsRC::init(sensorPins, sizeof(sensorPins), 2000, emitterPin);
|
||||
}
|
||||
|
||||
/*! \brief Initializes with all settings as given.
|
||||
*
|
||||
* \param pins Array of pin numbers for sensors.
|
||||
* \param numSensors Number of sensors.
|
||||
* \param timeout Maximum duration of reflectance reading in microseconds.
|
||||
* \param emitterPin Pin that turns IR emitters on or off.
|
||||
*
|
||||
* This function initializes the ZumoReflectanceSensorArray object with all
|
||||
* settings as given.
|
||||
*
|
||||
* The array \a pins should contain the Arduino digital pin numbers for each
|
||||
* sensor.
|
||||
*
|
||||
* \a numSensors specifies the length of the \a pins array (the number of
|
||||
* reflectance sensors you are using).
|
||||
*
|
||||
* \a 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 \a timeout, pulse timing will stop and the reading
|
||||
* for that pin will be considered full black. It is recommended that you set
|
||||
* \a timeout to be between 1000 and 3000 us, depending on factors like the
|
||||
* height of your sensors and ambient lighting. This allows you to shorten the
|
||||
* duration of a sensor-reading cycle while maintaining useful measurements of
|
||||
* reflectance. If \a timeout is not specified, it defaults to 2000 us. (See
|
||||
* the [product page](http://www.pololu.com/product/1419) for the Zumo
|
||||
* Reflectance Sensor Array on Pololu's website for an overview of the
|
||||
* sensors' principle of operation.)
|
||||
*
|
||||
* \a emitterPin is the Arduino digital pin that controls whether the IR LEDs
|
||||
* are on or off. This pin is optional; if a valid pin is specified, the
|
||||
* emitters will only be turned on during a reading. If \a emitterPin is not
|
||||
* specified, the emitters will be controlled with pin 2 on the Uno (and other
|
||||
* ATmega328/168 boards) or pin A4 on the Leonardo (and other ATmega32U4
|
||||
* boards). (The corresponding connection should be made with the "LED ON"
|
||||
* jumper on the Zumo Reflectance Sensor Array.) If the value
|
||||
* `QTR_NO_EMITTER_PIN` (255) is used, you can leave the emitter pin
|
||||
* disconnected and the IR emitters will always be on.
|
||||
*
|
||||
* This version of `%init()` can be useful if you only want to use a subset
|
||||
* of the six reflectance sensors on the array. For example, using the
|
||||
* outermost two sensors (on pins 4 and 5 by default) is usually enough for
|
||||
* detecting the ring border in sumo competitions:
|
||||
*
|
||||
* ~~~{.ino}
|
||||
* ZumoReflectanceSensorArray reflectanceSensors;
|
||||
*
|
||||
* ...
|
||||
*
|
||||
* reflectanceSensors.init((unsigned char[]) {4, 5}, 2);
|
||||
* ~~~
|
||||
*
|
||||
* Alternatively, you can use \ref ZumoReflectanceSensorArray(unsigned char * pins, unsigned char numSensors, unsigned int timeout, unsigned char emitterPin)
|
||||
* "a different constructor" to declare and initialize the object at the same
|
||||
* time:
|
||||
*
|
||||
* ~~~{.ino}
|
||||
*
|
||||
* ZumoReflectanceSensorArray reflectanceSensors((unsigned char[]) {4, 5}, 2);
|
||||
* ~~~
|
||||
*
|
||||
*/
|
||||
void init(unsigned char * pins, unsigned char numSensors, unsigned int timeout = 2000,
|
||||
unsigned char emitterPin = ZUMO_SENSOR_ARRAY_DEFAULT_EMITTER_PIN)
|
||||
{
|
||||
QTRSensorsRC::init(pins, numSensors, timeout, emitterPin);
|
||||
}
|
||||
};
|
||||
|
||||
// documentation for inherited functions
|
||||
|
||||
/*! \fn void QTRSensors::read(unsigned int *sensor_values, unsigned char readMode = QTR_EMITTERS_ON)
|
||||
\memberof ZumoReflectanceSensorArray
|
||||
* \brief Reads the raw sensor values into an array.
|
||||
*
|
||||
* \param sensorValues Array to populate with sensor readings.
|
||||
* \param readMode Read mode (`QTR_EMITTERS_OFF`, `QTR_EMITTERS_ON`, or
|
||||
* `QTR_EMITTERS_ON_AND_OFF`).
|
||||
*
|
||||
* There **must** be space in the \a sensorValues array for as many values as
|
||||
* there were sensors specified in the constructor. The values returned are
|
||||
* measures of the reflectance in units of microseconds. They will be raw
|
||||
* readings between 0 and the \a timeout argument (in units of microseconds)
|
||||
* provided in the constructor (which defaults to 2000).
|
||||
*
|
||||
* The \a readMode argument specifies the kind of read that will be performed.
|
||||
* Several options are defined:
|
||||
*
|
||||
* - `QTR_EMITTERS_OFF` specifies that the reading should be made without
|
||||
* turning on the infrared (IR) emitters, in which case the reading represents
|
||||
* ambient light levels near the sensor.
|
||||
* - `QTR_EMITTERS_ON` specifies that the emitters should be turned on for the
|
||||
* reading, which results in a measure of reflectance.
|
||||
* - `QTR_EMITTERS_ON_AND_OFF` specifies that a reading should be made in both
|
||||
* the on and off states. The values returned when this option is used are
|
||||
* given by the formula **on + max − off**, where **on** is the reading
|
||||
* with the emitters on, **off** is the reading with the emitters off, and
|
||||
* **max** is the maximum sensor reading. This option can reduce the amount of
|
||||
* interference from uneven ambient lighting.
|
||||
*
|
||||
* Note that emitter control will only work if you specify a valid emitter pin
|
||||
* in the constructor and make the corresponding connection (with the "LED ON"
|
||||
* jumper or otherwise).
|
||||
*
|
||||
* The ZumoReflectanceSensorArray class inherits this function from the
|
||||
* QTRSensors class.
|
||||
*/
|
||||
|
||||
/*! \fn void QTRSensors::emittersOff()
|
||||
* \brief Turns the IR LEDs off.
|
||||
*
|
||||
* This is mainly for use by the `read()` method, and calling this function
|
||||
* before or after reading the sensors will have no effect on the readings, but
|
||||
* you might wish to use it for testing purposes. This method will only do
|
||||
* something if the emitter pin specified in the constructor is valid (i.e. not
|
||||
* `QTR_NO_EMITTER_PIN`) and the corresponding connection is made.
|
||||
*
|
||||
* The ZumoReflectanceSensorArray class inherits this function from the
|
||||
* QTRSensors class.
|
||||
*/
|
||||
|
||||
/*! \fn void QTRSensors::emittersOn()
|
||||
* \brief Turns the IR LEDs on.
|
||||
* \copydetails emittersOff
|
||||
*/
|
||||
|
||||
/*! \fn void QTRSensors::calibrate(unsigned char readMode = QTR_EMITTERS_ON)
|
||||
* \brief Reads the sensors for calibration.
|
||||
*
|
||||
* \param readMode Read mode (`QTR_EMITTERS_OFF`, `QTR_EMITTERS_ON`, or
|
||||
* `QTR_EMITTERS_ON_AND_OFF`).
|
||||
*
|
||||
* The sensor values read by this function are not returned; instead, the
|
||||
* maximum and minimum values found over time are stored internally and used for
|
||||
* the `readCalibrated()` method. You can access the calibration (i.e raw max
|
||||
* and min sensor readings) through the public member pointers
|
||||
* `calibratedMinimumOn`, `calibratedMaximumOn`, `calibratedMinimumOff`, and
|
||||
* `calibratedMaximumOff`. Note that these pointers will point to arrays of
|
||||
* length \a numSensors, as specified in the constructor, and they will only be
|
||||
* allocated **after** `calibrate()` has been called. If you only calibrate with
|
||||
* the emitters on, the calibration arrays that hold the off values will not be
|
||||
* allocated.
|
||||
*
|
||||
* The ZumoReflectanceSensorArray class inherits this function from the
|
||||
* QTRSensors class.
|
||||
*/
|
||||
|
||||
/*! \fn void QTRSensors::resetCalibration()
|
||||
* \brief Resets all calibration that has been done.
|
||||
*
|
||||
* This function discards the calibration values that have been previously
|
||||
* recorded, resetting the min and max values.
|
||||
*
|
||||
* The ZumoReflectanceSensorArray class inherits this function from the
|
||||
* QTRSensors class.
|
||||
*/
|
||||
|
||||
/*! \fn void QTRSensors::readCalibrated(unsigned int *sensor_values, unsigned char readMode = QTR_EMITTERS_ON)
|
||||
* \brief Returns sensor readings normalized to values between 0 and 1000.
|
||||
*
|
||||
* \param sensorValues Array to populate with sensor readings.
|
||||
* \param readMode Read mode (`QTR_EMITTERS_OFF`, `QTR_EMITTERS_ON`, or
|
||||
* `QTR_EMITTERS_ON_AND_OFF`).
|
||||
*
|
||||
* 0 corresponds to a reading that is less than or equal to the minimum value
|
||||
* read by `calibrate()` and 1000 corresponds to a reading that is greater than
|
||||
* or equal to the maximum value. Calibration values are stored separately for
|
||||
* each sensor, so that differences in the sensors are accounted for
|
||||
* automatically.
|
||||
*
|
||||
* The ZumoReflectanceSensorArray class inherits this function from the
|
||||
* QTRSensors class.
|
||||
*/
|
||||
|
||||
/*! \fn int QTRSensors::readLine(unsigned int *sensor_values, unsigned char readMode = QTR_EMITTERS_ON, unsigned char whiteLine = 0)
|
||||
* \brief Returns an estimated position of a line under the sensor array.
|
||||
*
|
||||
* \param sensorValues Array to populate with sensor readings.
|
||||
* \param readMode Read mode (`QTR_EMITTERS_OFF`, `QTR_EMITTERS_ON`, or
|
||||
* `QTR_EMITTERS_ON_AND_OFF`).
|
||||
* \param whiteLine 0 to detect a dark line on a light surface; 1 to detect
|
||||
* a light line on a dark surface.
|
||||
* \return An estimated line position.
|
||||
*
|
||||
* This function operates the same as `readCalibrated()`, but with a feature
|
||||
* designed for line following: it returns an estimated position of the 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 (or was last seen by sensor 0 before being lost), a
|
||||
* return value of 1000 indicates that the line is directly below sensor 1, 2000
|
||||
* indicates that it's below sensor 2, etc. Intermediate values indicate that
|
||||
* the line is between two sensors. The formula is:
|
||||
*
|
||||
* \f[
|
||||
* \newcommand{sv}[1]{\mathtt{sensorValues[#1]}}
|
||||
* \text{return value} =
|
||||
* \frac{(0 \times \sv{0}) + (1000 \times \sv{1}) + (2000 \times \sv{2}) + \ldots}
|
||||
* {\sv{0} + \sv{1} + \sv{2} + \ldots}
|
||||
* \f]
|
||||
*
|
||||
* As long as your sensors aren't spaced too far apart relative to the line,
|
||||
* this returned value is designed to be monotonic, which makes it great for use
|
||||
* in closed-loop PID control. Additionally, this method remembers where it last
|
||||
* saw the line, so if you ever lose the line to the left or the right, its line
|
||||
* position will continue to indicate the direction you need to go to reacquire
|
||||
* the line. For example, if sensor 5 is your rightmost sensor and you end up
|
||||
* completely off the line to the left, this function will continue to return
|
||||
* 5000.
|
||||
*
|
||||
* By default, this function assumes a dark line (high values) on a light
|
||||
* background (low values). If your line is light on dark, set the optional
|
||||
* second argument \a whiteLine to true. In this case, each sensor value will be
|
||||
* replaced by the maximum possible value minus its actual value before the
|
||||
* averaging.
|
||||
*
|
||||
* The ZumoReflectanceSensorArray class inherits this function from the
|
||||
* QTRSensors class.
|
||||
*/
|
||||
|
||||
|
||||
// documentation for inherited member variables
|
||||
|
||||
/*!
|
||||
* \property unsigned int * QTRSensors::calibratedMinimumOn
|
||||
* \brief The calibrated minimum values measured for each sensor, with emitters
|
||||
* on.
|
||||
*
|
||||
* This pointer is unallocated and set to 0 until `calibrate()` is called, and
|
||||
* then allocated to exactly the size required. Depending on the \a readMode
|
||||
* argument to `calibrate()`, only the On or Off values might be allocated, as
|
||||
* required. This variable is made public so that you can use the calibration
|
||||
* values for your own calculations and do things like saving them to EEPROM,
|
||||
* performing sanity checking, etc.
|
||||
*
|
||||
* The ZumoReflectanceSensorArray class inherits this variable from the
|
||||
* QTRSensors class.
|
||||
*
|
||||
* \property unsigned int * QTRSensors::calibratedMaximumOn
|
||||
* \brief The calibrated maximum values measured for each sensor, with emitters
|
||||
* on.
|
||||
* \copydetails QTRSensors::calibratedMinimumOn
|
||||
*
|
||||
* \property unsigned int * QTRSensors::calibratedMinimumOff
|
||||
* \brief The calibrated minimum values measured for each sensor, with emitters
|
||||
* off.
|
||||
* \copydetails QTRSensors::calibratedMinimumOn
|
||||
*
|
||||
* \property unsigned int * QTRSensors::calibratedMaximumOff
|
||||
* \brief The calibrated maximum values measured for each sensor, with emitters
|
||||
* off.
|
||||
* \copydetails QTRSensors::calibratedMinimumOn
|
||||
*/
|
||||
|
||||
#endif
|
||||
Reference in New Issue
Block a user