This commit is contained in:
yikestone 2018-02-18 14:02:33 +05:30
commit c932efe7ff
512 changed files with 130574 additions and 0 deletions

View File

@ -0,0 +1,108 @@
/* Copyright (C) 2012 Kristian Lauszus, TKJ Electronics. All rights reserved.
This software may be distributed and modified under the terms of the GNU
General Public License version 2 (GPL2) as published by the Free Software
Foundation and appearing in the file GPL2.TXT included in the packaging of
this file. Please note that GPL2 Section 2[b] requires that all works based
on this software must also be made publicly available under the terms of
the GPL2 ("Copyleft").
Contact information
-------------------
Kristian Lauszus, TKJ Electronics
Web : http://www.tkjelectronics.com
e-mail : kristianl@tkjelectronics.com
*/
#ifndef _Kalman_h
#define _Kalman_h
class Kalman {
public:
Kalman() {
/* We will set the variables like so, these can also be tuned by the user */
Q_angle = 0.001;
Q_bias = 0.003;
R_measure = 0.03;
angle = 0; // Reset the angle
bias = 0; // Reset bias
P[0][0] = 0; // Since we assume that the bias is 0 and we know the starting angle (use setAngle), the error covariance matrix is set like so - see: http://en.wikipedia.org/wiki/Kalman_filter#Example_application.2C_technical
P[0][1] = 0;
P[1][0] = 0;
P[1][1] = 0;
};
// The angle should be in degrees and the rate should be in degrees per second and the delta time in seconds
double getAngle(double newAngle, double newRate, double dt) {
// KasBot V2 - Kalman filter module - http://www.x-firm.com/?page_id=145
// Modified by Kristian Lauszus
// See my blog post for more information: http://blog.tkjelectronics.dk/2012/09/a-practical-approach-to-kalman-filter-and-how-to-implement-it
// Discrete Kalman filter time update equations - Time Update ("Predict")
// Update xhat - Project the state ahead
/* Step 1 */
rate = newRate - bias;
angle += dt * rate;
// Update estimation error covariance - Project the error covariance ahead
/* Step 2 */
P[0][0] += dt * (dt*P[1][1] - P[0][1] - P[1][0] + Q_angle);
P[0][1] -= dt * P[1][1];
P[1][0] -= dt * P[1][1];
P[1][1] += Q_bias * dt;
// Discrete Kalman filter measurement update equations - Measurement Update ("Correct")
// Calculate Kalman gain - Compute the Kalman gain
/* Step 4 */
S = P[0][0] + R_measure;
/* Step 5 */
K[0] = P[0][0] / S;
K[1] = P[1][0] / S;
// Calculate angle and bias - Update estimate with measurement zk (newAngle)
/* Step 3 */
y = newAngle - angle;
/* Step 6 */
angle += K[0] * y;
bias += K[1] * y;
// Calculate estimation error covariance - Update the error covariance
/* Step 7 */
P[0][0] -= K[0] * P[0][0];
P[0][1] -= K[0] * P[0][1];
P[1][0] -= K[1] * P[0][0];
P[1][1] -= K[1] * P[0][1];
return angle;
};
void setAngle(double newAngle) { angle = newAngle; }; // Used to set angle, this should be set as the starting angle
double getRate() { return rate; }; // Return the unbiased rate
/* These are used to tune the Kalman filter */
void setQangle(double newQ_angle) { Q_angle = newQ_angle; };
void setQbias(double newQ_bias) { Q_bias = newQ_bias; };
void setRmeasure(double newR_measure) { R_measure = newR_measure; };
double getQangle() { return Q_angle; };
double getQbias() { return Q_bias; };
double getRmeasure() { return R_measure; };
private:
/* Kalman filter variables */
double Q_angle; // Process noise variance for the accelerometer
double Q_bias; // Process noise variance for the gyro bias
double R_measure; // Measurement noise variance - this is actually the variance of the measurement noise
double angle; // The angle calculated by the Kalman filter - part of the 2x1 state vector
double bias; // The gyro bias calculated by the Kalman filter - part of the 2x1 state vector
double rate; // Unbiased rate calculated from the rate and the calculated bias - you have to call getAngle to update the rate
double P[2][2]; // Error covariance matrix - This is a 2x2 matrix
double K[2]; // Kalman gain - This is a 2x1 vector
double y; // Angle difference
double S; // Estimate error
};
#endif

View File

@ -0,0 +1,324 @@
/* Copyright (C) 2014 Kristian Lauszus, TKJ Electronics. All rights reserved.
This software may be distributed and modified under the terms of the GNU
General Public License version 2 (GPL2) as published by the Free Software
Foundation and appearing in the file GPL2.TXT included in the packaging of
this file. Please note that GPL2 Section 2[b] requires that all works based
on this software must also be made publicly available under the terms of
the GPL2 ("Copyleft").
Contact information
-------------------
Kristian Lauszus, TKJ Electronics
Web : http://www.tkjelectronics.com
e-mail : kristianl@tkjelectronics.com
*/
#include <Wire.h>
#include "Kalman.h" // Source: https://github.com/TKJElectronics/KalmanFilter
#include <I2Cdev.h>
#include <stdlib.h>
#define RESTRICT_PITCH // Comment out to restrict roll to ±90deg instead - please read: http://www.freescale.com/files/sensors/doc/app_note/AN3461.pdf
Kalman kalmanX, kalmanY, kalmanZ; // Create the Kalman instances
const uint8_t MPU6050 = 0x68; // If AD0 is logic low on the PCB the address is 0x68, otherwise set this to 0x69
const uint8_t HMC5883L = 0x1E; // Address of magnetometer
/* IMU Data */
double accX, accY, accZ;
double gyroX, gyroY, gyroZ;
double magX, magY, magZ;
int16_t tempRaw;
double roll, pitch, yaw; // Roll and pitch are calculated using the accelerometer while yaw is calculated using the magnetometer
double gyroXangle, gyroYangle, gyroZangle; // Angle calculate using the gyro only
double compAngleX, compAngleY, compAngleZ; // Calculated angle using a complementary filter
double kalAngleX, kalAngleY, kalAngleZ; // Calculated angle using a Kalman filter
uint32_t timer;
uint8_t i2cData[14]; // Buffer for I2C data
#define MAG0MAX 603
#define MAG0MIN -578
#define MAG1MAX 542
#define MAG1MIN -701
#define MAG2MAX 547
#define MAG2MIN -556
float magOffset[3] = { (MAG0MAX + MAG0MIN) / 2, (MAG1MAX + MAG1MIN) / 2, (MAG2MAX + MAG2MIN) / 2 };
double magGain[3];
void setup() {
delay(100); // Wait for sensors to get ready
Serial.begin(115200);
Wire.begin();
TWBR = ((F_CPU / 400000L) - 16) / 2; // Set I2C frequency to 400kHz
I2Cdev::writeBits(MPU6050, 0x68, 2, 3, 0x01);
I2Cdev::writeBit(MPU6050, 0x6B, 6, false);
I2Cdev::writeBit(MPU6050, 0x6A, 5, false);
I2Cdev::writeBit(MPU6050, 0x37, 1, true);
I2Cdev::writeByte(HMC5883L, 0x00,(0x03 << 5) | (0x04 << 2) | (0x00 << 0));
I2Cdev::writeByte(HMC5883L, 0x01, 0x01 << 5);
i2cData[0] = 7; // Set the sample rate to 1000Hz - 8kHz/(7+1) = 1000Hz
i2cData[1] = 0x00; // Disable FSYNC and set 260 Hz Acc filtering, 256 Hz Gyro filtering, 8 KHz sampling
i2cData[2] = 0x00; // Set Gyro Full Scale Range to ±250deg/s
i2cData[3] = 0x00; // Set Accelerometer Full Scale Range to ±2g
I2Cdev::writeBytes(MPU6050, 0x19, 4, i2cData); // Write to all four registers at once
I2Cdev::writeByte(MPU6050, 0x6B, 0x01);// PLL with X axis gyroscope reference and disable sleep mode
I2Cdev::readByte(MPU6050, 0x75, i2cData,1000);
if (i2cData[0] != 0x68) { // Read "WHO_AM_I" register
Serial.print(F("Error reading sensor"));
while (1);
}
I2Cdev::writeByte(HMC5883L, 0x02, 0x00); // Configure device for continuous mode
calibrateMag();
delay(100); // Wait for sensors to stabilize
/* Set Kalman and gyro starting angle */
updateMPU6050();
updateHMC5883L();
updatePitchRoll();
updateYaw();
kalmanX.setAngle(roll); // First set roll starting angle
gyroXangle = roll;
compAngleX = roll;
kalmanY.setAngle(pitch); // Then pitch
gyroYangle = pitch;
compAngleY = pitch;
kalmanZ.setAngle(yaw); // And finally yaw
gyroZangle = yaw;
compAngleZ = yaw;
timer = micros(); // Initialize the timer
}
uint32_t tim;
void loop() {
/* Update all the IMU values */
updateMPU6050();
updateHMC5883L();
double dt = (double)(micros() - timer) / 1000000; // Calculate delta time
timer = micros();
/* Roll and pitch estimation */
updatePitchRoll();
double gyroXrate = gyroX / 131.0; // Convert to deg/s
double gyroYrate = gyroY / 131.0; // Convert to deg/s
#ifdef RESTRICT_PITCH
// This fixes the transition problem when the accelerometer angle jumps between -180 and 180 degrees
if ((roll < -90 && kalAngleX > 90) || (roll > 90 && kalAngleX < -90)) {
kalmanX.setAngle(roll);
compAngleX = roll;
kalAngleX = roll;
gyroXangle = roll;
} else
kalAngleX = kalmanX.getAngle(roll, gyroXrate, dt); // Calculate the angle using a Kalman filter
if (abs(kalAngleX) > 90)
gyroYrate = -gyroYrate; // Invert rate, so it fits the restricted accelerometer reading
kalAngleY = kalmanY.getAngle(pitch, gyroYrate, dt);
#else
// This fixes the transition problem when the accelerometer angle jumps between -180 and 180 degrees
if ((pitch < -90 && kalAngleY > 90) || (pitch > 90 && kalAngleY < -90)) {
kalmanY.setAngle(pitch);
compAngleY = pitch;
kalAngleY = pitch;
gyroYangle = pitch;
} else
kalAngleY = kalmanY.getAngle(pitch, gyroYrate, dt); // Calculate the angle using a Kalman filter
if (abs(kalAngleY) > 90)
gyroXrate = -gyroXrate; // Invert rate, so it fits the restricted accelerometer reading
kalAngleX = kalmanX.getAngle(roll, gyroXrate, dt); // Calculate the angle using a Kalman filter
#endif
/* Yaw estimation */
updateYaw();
double gyroZrate = gyroZ / 131.0; // Convert to deg/s
// This fixes the transition problem when the yaw angle jumps between -180 and 180 degrees
if ((yaw < -90 && kalAngleZ > 90) || (yaw > 90 && kalAngleZ < -90)) {
kalmanZ.setAngle(yaw);
compAngleZ = yaw;
kalAngleZ = yaw;
gyroZangle = yaw;
} else
kalAngleZ = kalmanZ.getAngle(yaw, gyroZrate, dt); // Calculate the angle using a Kalman filter
/* Estimate angles using gyro only */
gyroXangle += gyroXrate * dt; // Calculate gyro angle without any filter
gyroYangle += gyroYrate * dt;
gyroZangle += gyroZrate * dt;
//gyroXangle += kalmanX.getRate() * dt; // Calculate gyro angle using the unbiased rate from the Kalman filter
//gyroYangle += kalmanY.getRate() * dt;
//gyroZangle += kalmanZ.getRate() * dt;
/* Estimate angles using complimentary filter */
compAngleX = 0.93 * (compAngleX + gyroXrate * dt) + 0.07 * roll; // Calculate the angle using a Complimentary filter
compAngleY = 0.93 * (compAngleY + gyroYrate * dt) + 0.07 * pitch;
compAngleZ = 0.93 * (compAngleZ + gyroZrate * dt) + 0.07 * yaw;
// Reset the gyro angles when they has drifted too much
if (gyroXangle < -180 || gyroXangle > 180)
gyroXangle = kalAngleX;
if (gyroYangle < -180 || gyroYangle > 180)
gyroYangle = kalAngleY;
if (gyroZangle < -180 || gyroZangle > 180)
gyroZangle = kalAngleZ;
/* Print Data */
#if 1
// {@Plot.Angle.AccelAng.Red pitch}
Serial.print(roll); Serial.print("\t");
Serial.print(gyroXangle); Serial.print("\t");
Serial.print(compAngleX); Serial.print("\t");
Serial.print(kalAngleX); Serial.print("\t");
// Serial.print('a');
//Serial.println(millis()-tim);
//tim = millis();
Serial.print(pitch); Serial.print('\t');
Serial.print(gyroYangle); Serial.print('\t');
Serial.print(compAngleY); Serial.print('\t');
Serial.print(kalAngleY); Serial.print('\t');
Serial.print("\t");
Serial.print(yaw); Serial.print("\t");
Serial.print(gyroZangle); Serial.print("\t");
Serial.print(compAngleZ); Serial.print("\t");
Serial.print(kalAngleZ); Serial.print("\t");
#endif
#if 0 // Set to 1 to print the IMU data
Serial.print(accX / 16384.0); Serial.print("\t"); // Converted into g's
Serial.print(accY / 16384.0); Serial.print("\t");
Serial.print(accZ / 16384.0); Serial.print("\t");
Serial.print(gyroXrate); Serial.print("\t"); // Converted into degress per second
Serial.print(gyroYrate); Serial.print("\t");
Serial.print(gyroZrate); Serial.print("\t");
Serial.print(magX); Serial.print("\t"); // After gain and offset compensation
Serial.print(magY); Serial.print("\t");
Serial.print(magZ); Serial.print("\t");
#endif
#if 0 // Set to 1 to print the temperature
Serial.print("\t");
double temperature = (double)tempRaw / 340.0 + 36.53;
Serial.print(temperature); Serial.print("\t");
#endif
Serial.println();
delay(10);
}
void updateMPU6050() {
I2Cdev::readBytes(MPU6050, 0x3B, 14, i2cData); // Get accelerometer and gyroscope values
accX = ((i2cData[0] << 8) | i2cData[1]);
accY = -((i2cData[2] << 8) | i2cData[3]);
accZ = ((i2cData[4] << 8) | i2cData[5]);
tempRaw = (i2cData[6] << 8) | i2cData[7];
gyroX = -(i2cData[8] << 8) | i2cData[9];
gyroY = (i2cData[10] << 8) | i2cData[11];
gyroZ = -(i2cData[12] << 8) | i2cData[13];
}
void updateHMC5883L() {
I2Cdev::readBytes(HMC5883L, 0x03, 6, i2cData); // Get magnetometer values
magX = ((i2cData[0] << 8) | i2cData[1]);
magZ = ((i2cData[2] << 8) | i2cData[3]);
magY = ((i2cData[4] << 8) | i2cData[5]);
}
void updatePitchRoll() {
// Source: http://www.freescale.com/files/sensors/doc/app_note/AN3461.pdf eq. 25 and eq. 26
// atan2 outputs the value of -π to π (radians) - see http://en.wikipedia.org/wiki/Atan2
// It is then converted from radians to degrees
#ifdef RESTRICT_PITCH // Eq. 25 and 26
roll = atan2(accY, accZ) * RAD_TO_DEG;
pitch = atan(-accX / sqrt(accY * accY + accZ * accZ)) * RAD_TO_DEG;
#else // Eq. 28 and 29
roll = atan(accY / sqrt(accX * accX + accZ * accZ)) * RAD_TO_DEG;
pitch = atan2(-accX, accZ) * RAD_TO_DEG;
#endif
}
void updateYaw() { // See: http://www.freescale.com/files/sensors/doc/app_note/AN4248.pdf
magX *= -1; // Invert axis - this it done here, as it should be done after the calibration
magZ *= -1;
magX *= magGain[0];
magY *= magGain[1];
magZ *= magGain[2];
magX -= magOffset[0];
magY -= magOffset[1];
magZ -= magOffset[2];
double rollAngle = kalAngleX * DEG_TO_RAD;
double pitchAngle = kalAngleY * DEG_TO_RAD;
double Bfy = magZ * sin(rollAngle) - magY * cos(rollAngle);
double Bfx = magX * cos(pitchAngle) + magY * sin(pitchAngle) * sin(rollAngle) + magZ * sin(pitchAngle) * cos(rollAngle);
yaw = atan2(magY, magX) * RAD_TO_DEG;
yaw *= -1;
}
void calibrateMag() { // Inspired by: https://code.google.com/p/open-headtracker/
I2Cdev::writeByte(HMC5883L,uint8_t (0x00),uint8_t (0x11));
delay(100); // Wait for sensor to get ready
updateHMC5883L(); // Read positive bias values
int16_t magPosOff[3] = { magX, magY, magZ };
I2Cdev::writeByte(HMC5883L, 0x00, 0x12);
delay(100); // Wait for sensor to get ready
updateHMC5883L(); // Read negative bias values
int16_t magNegOff[3] = { magX, magY, magZ };
I2Cdev::writeByte(HMC5883L, uint8_t (0x00),uint8_t (0x10)); // Back to normal
magGain[0] = -2500 / float(magNegOff[0] - magPosOff[0]);
magGain[1] = -2500 / float(magNegOff[1] - magPosOff[1]);
magGain[2] = -2500 / float(magNegOff[2] - magPosOff[2]);
#if 0
Serial.print("Mag cal: ");
Serial.print(magNegOff[0] - magPosOff[0]);
Serial.print(",");
Serial.print(magNegOff[1] - magPosOff[1]);
Serial.print(",");
Serial.println(magNegOff[2] - magPosOff[2]);
Serial.print("Gain: ");
Serial.print(magGain[0]);
Serial.print(",");
Serial.print(magGain[1]);
Serial.print(",");
Serial.println(magGain[2]);
#endif
}

View File

@ -0,0 +1,6 @@
#define magX 312
#define magY 837
#define magZ 588
#define magx -1039
#define magy -640
#define magz -672

View File

@ -0,0 +1,215 @@
// Arduino sketch that returns calibration offsets for MPU6050 // Version 1.1 (31th January 2014)
// Done by Luis Ródenas <luisrodenaslorda@gmail.com>
// Based on the I2Cdev library and previous work by Jeff Rowberg <jeff@rowberg.net>
// Updates (of the library) should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
// These offsets were meant to calibrate MPU6050's internal DMP, but can be also useful for reading sensors.
// The effect of temperature has not been taken into account so I can't promise that it will work if you
// calibrate indoors and then use it outdoors. Best is to calibrate and use at the same room temperature.
/* ========== LICENSE ==================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2011 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
=========================================================
*/
// I2Cdev and MPU6050 must be installed as libraries
#include "I2Cdev.h"
#include "MPU6050.h"
#include "Wire.h"
/////////////////////////////////// CONFIGURATION /////////////////////////////
//Change this 3 variables if you want to fine tune the skecth to your needs.
int buffersize=1000; //Amount of readings used to average, make it higher to get more precision but sketch will be slower (default:1000)
int acel_deadzone=8; //Acelerometer error allowed, make it lower to get more precision, but sketch may not converge (default:8)
int giro_deadzone=1; //Giro error allowed, make it lower to get more precision, but sketch may not converge (default:1)
// default I2C address is 0x68
// specific I2C addresses may be passed as a parameter here
// AD0 low = 0x68 (default for InvenSense evaluation board)
// AD0 high = 0x69
//MPU6050 accelgyro;
MPU6050 accelgyro(0x68); // <-- use for AD0 high
int16_t ax, ay, az,gx, gy, gz;
int mean_ax,mean_ay,mean_az,mean_gx,mean_gy,mean_gz,state=0;
int ax_offset,ay_offset,az_offset,gx_offset,gy_offset,gz_offset;
/////////////////////////////////// SETUP ////////////////////////////////////
void setup() {
// join I2C bus (I2Cdev library doesn't do this automatically)
Wire.begin();
// COMMENT NEXT LINE IF YOU ARE USING ARDUINO DUE
TWBR = 24; // 400kHz I2C clock (200kHz if CPU is 8MHz). Leonardo measured 250kHz.
// initialize serial communication
Serial.begin(115200);
// initialize device
accelgyro.initialize();
// wait for ready
while (Serial.available() && Serial.read()); // empty buffer
while (!Serial.available()){
Serial.println(F("Send any character to start sketch.\n"));
delay(1500);
}
while (Serial.available() && Serial.read()); // empty buffer again
// start message
Serial.println("\nMPU6050 Calibration Sketch");
delay(2000);
Serial.println("\nYour MPU6050 should be placed in horizontal position, with package letters facing up. \nDon't touch it until you see a finish message.\n");
delay(3000);
// verify connection
Serial.println(accelgyro.testConnection() ? "MPU6050 connection successful" : "MPU6050 connection failed");
delay(1000);
// reset offsets
accelgyro.setXAccelOffset(0);
accelgyro.setYAccelOffset(0);
accelgyro.setZAccelOffset(0);
accelgyro.setXGyroOffset(0);
accelgyro.setYGyroOffset(0);
accelgyro.setZGyroOffset(0);
}
/////////////////////////////////// LOOP ////////////////////////////////////
void loop() {
if (state==0){
Serial.println("\nReading sensors for first time...");
meansensors();
state++;
delay(1000);
}
if (state==1) {
Serial.println("\nCalculating offsets...");
calibration();
state++;
delay(1000);
}
if (state==2) {
meansensors();
Serial.println("\nFINISHED!");
Serial.print("\nSensor readings with offsets:\t");
Serial.print(mean_ax);
Serial.print("\t");
Serial.print(mean_ay);
Serial.print("\t");
Serial.print(mean_az);
Serial.print("\t");
Serial.print(mean_gx);
Serial.print("\t");
Serial.print(mean_gy);
Serial.print("\t");
Serial.println(mean_gz);
Serial.print("Your offsets:\t");
Serial.print(ax_offset);
Serial.print("\t");
Serial.print(ay_offset);
Serial.print("\t");
Serial.print(az_offset);
Serial.print("\t");
Serial.print(gx_offset);
Serial.print("\t");
Serial.print(gy_offset);
Serial.print("\t");
Serial.println(gz_offset);
Serial.println("\nData is printed as: acelX acelY acelZ giroX giroY giroZ");
Serial.println("Check that your sensor readings are close to 0 0 16384 0 0 0");
Serial.println("If calibration was succesful write down your offsets so you can set them in your projects using something similar to mpu.setXAccelOffset(youroffset)");
while (1);
}
}
/////////////////////////////////// FUNCTIONS ////////////////////////////////////
void meansensors(){
long i=0,buff_ax=0,buff_ay=0,buff_az=0,buff_gx=0,buff_gy=0,buff_gz=0;
while (i<(buffersize+101)){
// read raw accel/gyro measurements from device
accelgyro.getMotion6(&ax, &ay, &az, &gx, &gy, &gz);
if (i>100 && i<=(buffersize+100)){ //First 100 measures are discarded
buff_ax=buff_ax+ax;
buff_ay=buff_ay+ay;
buff_az=buff_az+az;
buff_gx=buff_gx+gx;
buff_gy=buff_gy+gy;
buff_gz=buff_gz+gz;
}
if (i==(buffersize+100)){
mean_ax=buff_ax/buffersize;
mean_ay=buff_ay/buffersize;
mean_az=buff_az/buffersize;
mean_gx=buff_gx/buffersize;
mean_gy=buff_gy/buffersize;
mean_gz=buff_gz/buffersize;
}
i++;
delay(2); //Needed so we don't get repeated measures
}
}
void calibration(){
ax_offset=-mean_ax/8;
ay_offset=-mean_ay/8;
az_offset=(16384-mean_az)/8;
gx_offset=-mean_gx/4;
gy_offset=-mean_gy/4;
gz_offset=-mean_gz/4;
while (1){
int ready=0;
accelgyro.setXAccelOffset(ax_offset);
accelgyro.setYAccelOffset(ay_offset);
accelgyro.setZAccelOffset(az_offset);
accelgyro.setXGyroOffset(gx_offset);
accelgyro.setYGyroOffset(gy_offset);
accelgyro.setZGyroOffset(gz_offset);
meansensors();
Serial.println("...");
if (abs(mean_ax)<=acel_deadzone) ready++;
else ax_offset=ax_offset-mean_ax/acel_deadzone;
if (abs(mean_ay)<=acel_deadzone) ready++;
else ay_offset=ay_offset-mean_ay/acel_deadzone;
if (abs(16384-mean_az)<=acel_deadzone) ready++;
else az_offset=az_offset+(16384-mean_az)/acel_deadzone;
if (abs(mean_gx)<=giro_deadzone) ready++;
else gx_offset=gx_offset-mean_gx/(giro_deadzone+1);
if (abs(mean_gy)<=giro_deadzone) ready++;
else gy_offset=gy_offset-mean_gy/(giro_deadzone+1);
if (abs(mean_gz)<=giro_deadzone) ready++;
else gz_offset=gz_offset-mean_gz/(giro_deadzone+1);
if (ready==6) break;
}
}

View File

@ -0,0 +1,108 @@
/* Copyright (C) 2012 Kristian Lauszus, TKJ Electronics. All rights reserved.
This software may be distributed and modified under the terms of the GNU
General Public License version 2 (GPL2) as published by the Free Software
Foundation and appearing in the file GPL2.TXT included in the packaging of
this file. Please note that GPL2 Section 2[b] requires that all works based
on this software must also be made publicly available under the terms of
the GPL2 ("Copyleft").
Contact information
-------------------
Kristian Lauszus, TKJ Electronics
Web : http://www.tkjelectronics.com
e-mail : kristianl@tkjelectronics.com
*/
#ifndef _Kalman_h
#define _Kalman_h
class Kalman {
public:
Kalman() {
/* We will set the variables like so, these can also be tuned by the user */
Q_angle = 0.001;
Q_bias = 0.003;
R_measure = 0.03;
angle = 0; // Reset the angle
bias = 0; // Reset bias
P[0][0] = 0; // Since we assume that the bias is 0 and we know the starting angle (use setAngle), the error covariance matrix is set like so - see: http://en.wikipedia.org/wiki/Kalman_filter#Example_application.2C_technical
P[0][1] = 0;
P[1][0] = 0;
P[1][1] = 0;
};
// The angle should be in degrees and the rate should be in degrees per second and the delta time in seconds
double getAngle(double newAngle, double newRate, double dt) {
// KasBot V2 - Kalman filter module - http://www.x-firm.com/?page_id=145
// Modified by Kristian Lauszus
// See my blog post for more information: http://blog.tkjelectronics.dk/2012/09/a-practical-approach-to-kalman-filter-and-how-to-implement-it
// Discrete Kalman filter time update equations - Time Update ("Predict")
// Update xhat - Project the state ahead
/* Step 1 */
rate = newRate - bias;
angle += dt * rate;
// Update estimation error covariance - Project the error covariance ahead
/* Step 2 */
P[0][0] += dt * (dt*P[1][1] - P[0][1] - P[1][0] + Q_angle);
P[0][1] -= dt * P[1][1];
P[1][0] -= dt * P[1][1];
P[1][1] += Q_bias * dt;
// Discrete Kalman filter measurement update equations - Measurement Update ("Correct")
// Calculate Kalman gain - Compute the Kalman gain
/* Step 4 */
S = P[0][0] + R_measure;
/* Step 5 */
K[0] = P[0][0] / S;
K[1] = P[1][0] / S;
// Calculate angle and bias - Update estimate with measurement zk (newAngle)
/* Step 3 */
y = newAngle - angle;
/* Step 6 */
angle += K[0] * y;
bias += K[1] * y;
// Calculate estimation error covariance - Update the error covariance
/* Step 7 */
P[0][0] -= K[0] * P[0][0];
P[0][1] -= K[0] * P[0][1];
P[1][0] -= K[1] * P[0][0];
P[1][1] -= K[1] * P[0][1];
return angle;
};
void setAngle(double newAngle) { angle = newAngle; }; // Used to set angle, this should be set as the starting angle
double getRate() { return rate; }; // Return the unbiased rate
/* These are used to tune the Kalman filter */
void setQangle(double newQ_angle) { Q_angle = newQ_angle; };
void setQbias(double newQ_bias) { Q_bias = newQ_bias; };
void setRmeasure(double newR_measure) { R_measure = newR_measure; };
double getQangle() { return Q_angle; };
double getQbias() { return Q_bias; };
double getRmeasure() { return R_measure; };
private:
/* Kalman filter variables */
double Q_angle; // Process noise variance for the accelerometer
double Q_bias; // Process noise variance for the gyro bias
double R_measure; // Measurement noise variance - this is actually the variance of the measurement noise
double angle; // The angle calculated by the Kalman filter - part of the 2x1 state vector
double bias; // The gyro bias calculated by the Kalman filter - part of the 2x1 state vector
double rate; // Unbiased rate calculated from the rate and the calculated bias - you have to call getAngle to update the rate
double P[2][2]; // Error covariance matrix - This is a 2x2 matrix
double K[2]; // Kalman gain - This is a 2x1 vector
double y; // Angle difference
double S; // Estimate error
};
#endif

View File

@ -0,0 +1,287 @@
#include <Wire.h>
#include "Kalman.h" // Source: https://github.com/TKJElectronics/KalmanFilter
#include <I2Cdev.h>
#define RESTRICT_PITCH // Comment out to restrict roll to ±90deg instead - please read: http://www.freescale.com/files/sensors/doc/app_note/AN3461.pdf
#define LTMDIR 7
#define RTMDIR 4
#define LTMPWM 6
#define RTMPWM 5
#define LTMINT 2
#define RTMINT 3
Kalman kalmanX, kalmanY, kalmanZ; // Create the Kalman instances
const uint8_t MPU6050 = 0x68; // If AD0 is logic low on the PCB the address is 0x68, otherwise set this to 0x69
const uint8_t AK8975 = 0x0C; // Address of magnetometer
/* IMU Data */
double accX, accY, accZ;
double gyroX, gyroY, gyroZ;
double magX, magY, magZ;
int16_t tempRaw;
double roll, pitch, yaw; // Roll and pitch are calculated using the accelerometer while yaw is calculated using the magnetometer
double gyroXangle, gyroYangle, gyroZangle; // Angle calculate using the gyro only
double compAngleX, compAngleY, compAngleZ; // Calculated angle using a complementary filter
double kalAngleX, kalAngleY, kalAngleZ; // Calculated angle using a Kalman filter
uint32_t timer;
uint8_t i2cData[14]; // Buffer for I2C data
#define MAG0MAX 603
#define MAG0MIN -578
#define MAG1MAX 542
#define MAG1MIN -701
#define MAG2MAX 547
#define MAG2MIN -556
bool lDir,rDir;
float magOffset[3] = { (MAG0MAX + MAG0MIN) / 2, (MAG1MAX + MAG1MIN) / 2, (MAG2MAX + MAG2MIN) / 2 };
double magGain[3];
void motorControl(int a, int b)
{
if(lDir)
PORTD |= _BV(RTMDIR);
else
PORTD &= ~_BV(RTMDIR);
if(rDir)
PORTD |= _BV(LTMDIR);
else
PORTD &= ~_BV(LTMDIR);
analogWrite(RTMPWM,( ( abs( a ) <= 100 ) ? a + 25: 0 ));
analogWrite(LTMPWM,( ( abs( a ) <= 100 ) ? a + 25: 0 ));
}
void setup() {
delay(100); // Wait for sensors to get ready
pinMode(LTMINT, INPUT);
pinMode(RTMINT, INPUT);
pinMode(LTMDIR, OUTPUT);
pinMode(RTMDIR, OUTPUT);
pinMode(LTMPWM, OUTPUT);
pinMode(RTMPWM, OUTPUT);
Serial.begin(57600); delay(100);
Wire.begin();Serial.println('h');
TWBR = ((F_CPU / 400000L) - 16) / 2; // Set I2C frequency to 400kHz
I2Cdev::writeBits(MPU6050, 0x68, 2, 3, 0x01);
I2Cdev::writeBit(MPU6050, 0x6B, 6, 0);
I2Cdev::writeBit(MPU6050, 0x6A, 5, 0);
I2Cdev::writeBit(MPU6050, 0x37, 1, 1);
i2cData[0] = 7; // Set the sample rate to 1000Hz - 8kHz/(7+1) = 1000Hz
i2cData[1] = 0x00; // Disable FSYNC and set 260 Hz Acc filtering, 256 Hz Gyro filtering, 8 KHz sampling
i2cData[2] = 0x00; // Set Gyro Full Scale Range to ±250deg/s
i2cData[3] = 0x00; // Set Accelerometer Full Scale Range to ±2g
I2Cdev::writeBytes(MPU6050, 0x19, 4, i2cData); // Write to all four registers at once
I2Cdev::writeByte(MPU6050, 0x6B, 0x01);// PLL with X axis gyroscope reference and disable sleep mode
I2Cdev::readByte(MPU6050, 0x75, i2cData,1000);
if (i2cData[0] != 0x68) { // Read "WHO_AM_I" register
Serial.print(F("Error reading sensor"));
while (1);
}
// calibrateMag();
delay(100); // Wait for sensors to stabilize
/* Set Kalman and gyro starting angle */
updateMPU6050();
updateAK8975();
updatePitchRoll();
updateYaw();
kalmanX.setAngle(roll); // First set roll starting angle
gyroXangle = roll;
compAngleX = roll;
kalmanY.setAngle(pitch); // Then pitch
gyroYangle = pitch;
compAngleY = pitch;
kalmanZ.setAngle(yaw); // And finally yaw
gyroZangle = yaw;
compAngleZ = yaw;
timer = micros(); // Initialize the timer
}
float KP = 0,KI = 0, KD = 0;float cerr = 0;float perr = 0;
float setPitch = 0;
void control(){
float err = setPitch - kalAngleY;
cerr+=err;
cerr=(cerr>10?10:cerr);
float out = KP * (err) + KI*cerr + KD * (perr - err);
if(out<0)rDir=lDir=1;
else rDir=lDir=0;
motorControl(out,out);
}
void loop() {
/* Update all the IMU values */
updateMPU6050();
updateAK8975();
if(Serial.available()>2){
switch (Serial.read())
{
case 'p':KP = Serial.parseFloat();break;
case 'i':KI = Serial.parseFloat();break;
case 'd':KD = Serial.parseFloat();break;
case 's':setPitch = Serial.parseFloat();break;
//case 'b':kcgi = Serial.parseFloat();break;
//case 'c':kcgd = Serial.parseFloat();break;*/
//case 's':initAOffset = Serial.parseFloat();break;
//case 'e':mov = Serial.parseInt();break;
//case 't':angs = Serial.parseFloat();break;
//case 'a':an=Serial.parseFloat();break;
//case 'm':m = Serial.parseFloat();break;
}
Serial.read();
}
double dt = (double)(micros() - timer) / 1000000; // Calculate delta time
timer = micros();
/* Roll and pitch estimation */
updatePitchRoll();
double gyroXrate = gyroX / 131.0; // Convert to deg/s
double gyroYrate = gyroY / 131.0; // Convert to deg/s
#ifdef RESTRICT_PITCH
// This fixes the transition problem when the accelerometer angle jumps between -180 and 180 degrees
if ((roll < -90 && kalAngleX > 90) || (roll > 90 && kalAngleX < -90)) {
kalmanX.setAngle(roll);
compAngleX = roll;
kalAngleX = roll;
gyroXangle = roll;
} else
kalAngleX = kalmanX.getAngle(roll, gyroXrate, dt); // Calculate the angle using a Kalman filter
if (abs(kalAngleX) > 90)
gyroYrate = -gyroYrate; // Invert rate, so it fits the restricted accelerometer reading
kalAngleY = kalmanY.getAngle(pitch, gyroYrate, dt);
#else
// This fixes the transition problem when the accelerometer angle jumps between -180 and 180 degrees
if ((pitch < -90 && kalAngleY > 90) || (pitch > 90 && kalAngleY < -90)) {
kalmanY.setAngle(pitch);
compAngleY = pitch;
kalAngleY = pitch;
gyroYangle = pitch;
} else
kalAngleY = kalmanY.getAngle(pitch, gyroYrate, dt); // Calculate the angle using a Kalman filter
if (abs(kalAngleY) > 90)
gyroXrate = -gyroXrate; // Invert rate, so it fits the restricted accelerometer reading
kalAngleX = kalmanX.getAngle(roll, gyroXrate, dt); // Calculate the angle using a Kalman filter
#endif
/* Yaw estimation */
updateYaw();
double gyroZrate = gyroZ / 131.0; // Convert to deg/s
// This fixes the transition problem when the yaw angle jumps between -180 and 180 degrees
if ((yaw < -90 && kalAngleZ > 90) || (yaw > 90 && kalAngleZ < -90)) {
kalmanZ.setAngle(yaw);
compAngleZ = yaw;
kalAngleZ = yaw;
gyroZangle = yaw;
} else
kalAngleZ = kalmanZ.getAngle(yaw, gyroZrate, dt); // Calculate the angle using a Kalman filter
/* Estimate angles using gyro only */
gyroXangle += gyroXrate * dt; // Calculate gyro angle without any filter
gyroYangle += gyroYrate * dt;
gyroZangle += gyroZrate * dt;
//gyroXangle += kalmanX.getRate() * dt; // Calculate gyro angle using the unbiased rate from the Kalman filter
//gyroYangle += kalmanY.getRate() * dt;
//gyroZangle += kalmanZ.getRate() * dt;
/* Estimate angles using complimentary filter */
compAngleX = 0.93 * (compAngleX + gyroXrate * dt) + 0.07 * roll; // Calculate the angle using a Complimentary filter
compAngleY = 0.93 * (compAngleY + gyroYrate * dt) + 0.07 * pitch;
compAngleZ = 0.93 * (compAngleZ + gyroZrate * dt) + 0.07 * yaw;
// Reset the gyro angles when they has drifted too much
if (gyroXangle < -180 || gyroXangle > 180)
gyroXangle = kalAngleX;
if (gyroYangle < -180 || gyroYangle > 180)
gyroYangle = kalAngleY;
if (gyroZangle < -180 || gyroZangle > 180)
gyroZangle = kalAngleZ;
control();
/* Print Data */
#if 1
Serial.print(roll); Serial.print("\t");
Serial.print(gyroXangle); Serial.print("\t");
Serial.print(compAngleX); Serial.print("\t");
Serial.print(kalAngleX); Serial.print("\t");
Serial.print("\t");
Serial.print(pitch); Serial.print("\t");
Serial.print(gyroYangle); Serial.print("\t");
Serial.print(compAngleY); Serial.print("\t");
Serial.print(kalAngleY); Serial.print("\t");
Serial.print("\t");
Serial.print(yaw); Serial.print("\t");
Serial.print(gyroZangle); Serial.print("\t");
Serial.print(compAngleZ); Serial.print("\t");
Serial.print(kalAngleZ); Serial.print("\t");
#endif
Serial.println();
delay(10);
}
void updateMPU6050() {
I2Cdev::readBytes(MPU6050, 0x3B, 14, i2cData); // Get accelerometer and gyroscope values
accX = ((i2cData[0] << 8) | i2cData[1]);
accY = ((i2cData[2] << 8) | i2cData[3]);
accZ = ((i2cData[4] << 8) | i2cData[5]);
tempRaw = (i2cData[6] << 8) | i2cData[7];
gyroX = (i2cData[8] << 8) | i2cData[9];
gyroY = (i2cData[10] << 8) | i2cData[11];
gyroZ = (i2cData[12] << 8) | i2cData[13];
}
void updateAK8975() {
I2Cdev::writeByte(AK8975, 0x0A, 0x1);
delay(10);
I2Cdev::readBytes(AK8975, 0x03, 6, i2cData);
magY = ((i2cData[1] << 8) | i2cData[0]);
magX = ((i2cData[3] << 8) | i2cData[2]);
magZ = ((i2cData[5] << 8) | i2cData[4]);
}
void updatePitchRoll() {
#ifdef RESTRICT_PITCH // Eq. 25 and 26
roll = atan2(accY, accZ) * RAD_TO_DEG;
pitch = atan(-accX / sqrt(accY * accY + accZ * accZ)) * RAD_TO_DEG;
#else // Eq. 28 and 29
roll = atan(accY / sqrt(accX * accX + accZ * accZ)) * RAD_TO_DEG;
pitch = atan2(accX, accZ) * RAD_TO_DEG;
#endif
}
void updateYaw() { // See: http://www.freescale.com/files/sensors/doc/app_note/AN4248.pdf
/* magX *= -1; // Invert axis - this it done here, as it should be done after the calibration
magZ *= -1;
*/
double rollAngle = kalAngleX * DEG_TO_RAD;
double pitchAngle = kalAngleY * DEG_TO_RAD;
double Bfy = magZ * sin(rollAngle) - magY * cos(rollAngle);
double Bfx = magX * cos(pitchAngle) + magY * sin(pitchAngle) * sin(rollAngle) + magZ * sin(pitchAngle) * cos(rollAngle);
yaw = atan2(-Bfy, Bfx) * RAD_TO_DEG;
//yaw *= -1;
}

1
AHRS/Readme.md Normal file
View File

@ -0,0 +1 @@
These are a collection for estimating AHRS algorithms and callibration routines.

View File

@ -0,0 +1,289 @@
//ines (233 sloc) 9.04 KB
// Arduino Wire library is required if I2Cdev I2CDEV_ARDUINO_WIRE implementation
// is used in I2Cdev.h
#include "Wire.h"
// I2Cdev and MPU6050 must be installed as libraries, or else the .cpp/.h files
// for both classes must be in the include path of your project
#include "I2Cdev.h"
#include "MPU6050.h"
// class default I2C address is 0x68
// specific I2C addresses may be passed as a parameter here
// AD0 low = 0x68 (default for InvenSense evaluation board)
// AD0 high = 0x69
MPU6050 accelgyro;
int16_t ax, ay, az;
int16_t gx, gy, gz;
int16_t mx, my, mz;
// System constants
#define LED_PIN 13
//fusion
float deltat = 0.001f;
float lastt = 0;
float ct = 0;
float l = 0;
float gyroMeasError = 0; //3.14159265358979 * (0 / 180);
float gyroMeasDrift = 0;
float beta = sqrt(3.0 / 4.0) * gyroMeasError;
float zeta = sqrt(3.0 / 4.0) * gyroMeasDrift;
int b = 0;
// Global system variables
float a_x, a_y, a_z;
float w_x, w_y, w_z;
float m_x, m_y, m_z;
float SEq_1 = 1, SEq_2 = 0, SEq_3 = 0, SEq_4 = 0;
float b_x = 1, b_z = 0;
float w_bx = 0, w_by = 0, w_bz = 0;
// Local system variables
// end fusion
bool blinkState = false;
void setup() {
// join I2C bus (I2Cdev library doesn't do this automatically)
Wire.begin();
// initialize serial communication
// (38400 chosen because it works as well at 8MHz as it does at 16MHz, but
// it's really up to you depending on your project)
Serial.begin(38400);
// initialize device
Serial.println("Initializing I2C devices...");
accelgyro.initialize();
accelgyro.setFullScaleGyroRange(1); //set range to +-500°/s
accelgyro.setFullScaleAccelRange(0); //set range to +-2g
// verify connection
Serial.println("Testing device connections...");
Serial.println(accelgyro.testConnection() ? "MPU6050 connection successful" : "MPU6050 connection failed");
// configure Arduino LED for
pinMode(LED_PIN, OUTPUT);
}
float n2R(int n, float intercept) { // number to degrees
float deg = ((n/32768.0) * 500.0 + intercept);
if (abs(deg) < .3) {
return 0;
}
return deg * (1/57.29578);
}
float n2g(int n) { // number to g-force // useless because we're looking at magnitude
return n * 0.00006103515626;// 1/32768.0 * 2;
}
double getPitch(double q0, double q1, double q2, double q3) {
double top = 2*(q1*q3 + q0*q2);
double bottom = sqrt(1-pow((2*q1*q3+2*q0*q2),2));
return (-atan(top/bottom))*57.29578;
}
double getYaw(double q0, double q1, double q2, double q3) {
double arg1 = 2*(q2*q3-q0*q1);
double arg2 = 2*pow(q0,2) - 1 + 2*pow(q3,2);
return atan2(arg1,arg2)*57.29578;
}
double getRoll(double q0, double q1, double q2, double q3) {
double arg1 = 2*(q1*q2-q0*q3);
double arg2 = 2*pow(q0,2) - 1 + 2*pow(q1,2);
return atan2(arg1,arg2)*57.29578;
}
void loop() {
// read raw accel/gyro measurements from device
//if (accelgyro.testConnection()) {
//if (b > 0) {
accelgyro.getMotion9(&ax, &ay, &az, &gx, &gy, &gz, &mx, &my, &mz);
ct = millis();
deltat = (ct - lastt) * 0.001;
Serial.print("p/y/r"); Serial.print("\t");
Serial.print(ax); Serial.print("\t");
Serial.print(ay); Serial.print("\t");
Serial.print(az); Serial.print("\t");
Serial.print("p/y/r"); Serial.print("\t");
Serial.print(gx); Serial.print("\t");
Serial.print(gy); Serial.print("\t");
Serial.print(gz); Serial.print("\t");
Serial.print("p/y/r"); Serial.print("\t");
Serial.print(mx); Serial.print("\t");
Serial.print(my); Serial.print("\t");
Serial.println(mz);
/*
lastt = ct;
float xR = n2R(gx, -0.926877914);
float yR = n2R(gy, 0.758192);
float zR = n2R(gz, 1.94250294);
if (abs(zR) > abs(l)) {
l = zR;
}
filterUpdate(xR, yR, zR, ax, ay, az, mx, my, mz);
// if (b % 25 == 0) {
double pitch = getPitch(SEq_1, SEq_2, SEq_3, SEq_4);
double yaw = getYaw(SEq_1, SEq_2, SEq_3, SEq_4);
double roll = getRoll(SEq_1, SEq_2, SEq_3, SEq_4);
Serial.print("p/y/r"); Serial.print("\t");
Serial.print(pitch); Serial.print("\t");
Serial.print(yaw); Serial.print("\t");
Serial.print(roll); Serial.print("\t");
Serial.println(l * 180/3.14159);// Serial.print("\t");
} else {
lastt = millis();
}
b++;
blinkState = !blinkState;
digitalWrite(LED_PIN, blinkState);
}
else {
Serial.println("MPU6050 connection failed");
}*/
}
void filterUpdate(float w_x, float w_y, float w_z, float a_x, float a_y, float a_z, float m_x, float m_y, float m_z) {
// local system variables
float norm; // vector norm
float SEqDot_omega_1, SEqDot_omega_2, SEqDot_omega_3, SEqDot_omega_4; // quaternion rate from gyroscopes elements // objective function elements
float f_1, f_2, f_3, f_4, f_5, f_6; // objective function elements
float J_11or24, J_12or23, J_13or22, J_14or21, J_32, J_33,
J_41, J_42, J_43, J_44, J_51, J_52, J_53, J_54, J_61, J_62, J_63, J_64; // objective function Jacobian elements
float SEqHatDot_1, SEqHatDot_2, SEqHatDot_3, SEqHatDot_4;
float w_err_x, w_err_y, w_err_z;
float h_x, h_y, h_z;
// axulirary variables to avoid repeated calculations
float halfSEq_1 = 0.5f * SEq_1;
float halfSEq_2 = 0.5f * SEq_2;
float halfSEq_3 = 0.5f * SEq_3;
float halfSEq_4 = 0.5f * SEq_4;
float twoSEq_1 = 2.0f * SEq_1;
float twoSEq_2 = 2.0f * SEq_2;
float twoSEq_3 = 2.0f * SEq_3;
float twoSEq_4 = 2.0f * SEq_4;
float twob_x = 2.0f * b_x;
float twob_z = 2.0f * b_z;
float twob_xSEq_1 = 2.0f * b_x * SEq_1;
float twob_xSEq_2 = 2.0f * b_x * SEq_2;
float twob_xSEq_3 = 2.0f * b_x * SEq_3;
float twob_xSEq_4 = 2.0f * b_x * SEq_4;
float twob_zSEq_1 = 2.0f * b_z * SEq_1;
float twob_zSEq_2 = 2.0f * b_z * SEq_2;
float twob_zSEq_3 = 2.0f * b_z * SEq_3;
float twob_zSEq_4 = 2.0f * b_z * SEq_4;
float SEq_1SEq_2;
float SEq_1SEq_3 = SEq_1 * SEq_3;
float SEq_1SEq_4;
float SEq_2SEq_3;
float SEq_2SEq_4 = SEq_2 * SEq_4;
float SEq_3SEq_4;
float twom_x = 2.0f * m_x;
float twom_y = 2.0f * m_y;
float twom_z = 2.0f * m_z;
norm = sqrt(a_x * a_x + a_y * a_y + a_z * a_z);
a_x /= norm;
a_y /= norm;
a_z /= norm;
// normalise the magnetometer measurement
norm = sqrt(m_x * m_x + m_y * m_y + m_z * m_z);
m_x /= norm;
m_y /= norm;
m_z /= norm;
// compute the objective function and Jacobian
f_1 = twoSEq_2 * SEq_4 - twoSEq_1 * SEq_3 - a_x;
f_2 = twoSEq_1 * SEq_2 + twoSEq_3 * SEq_4 - a_y;
f_3 = 1.0f - twoSEq_2 * SEq_2 - twoSEq_3 * SEq_3 - a_z;
f_4 = twob_x * (0.5f - SEq_3 * SEq_3 - SEq_4 * SEq_4) + twob_z * (SEq_2SEq_4 - SEq_1SEq_3) - m_x;
f_5 = twob_x * (SEq_2 * SEq_3 - SEq_1 * SEq_4) + twob_z * (SEq_1 * SEq_2 + SEq_3 * SEq_4) - m_y;
f_6 = twob_x * (SEq_1SEq_3 + SEq_2SEq_4) + twob_z * (0.5f - SEq_2 * SEq_2 - SEq_3 * SEq_3) - m_z;
J_11or24 = twoSEq_3;
J_12or23 = 2.0f * SEq_4;
J_13or22 = twoSEq_1;
J_14or21 = twoSEq_2;
J_32 = 2.0f * J_14or21;
J_33 = 2.0f * J_11or24;
J_41 = twob_zSEq_3;
J_42 = twob_zSEq_4;
J_43 = 2.0f * twob_xSEq_3 + twob_zSEq_1;
J_44 = 2.0f * twob_xSEq_4 - twob_zSEq_2;
J_51 = twob_xSEq_4 - twob_zSEq_2;
J_52 = twob_xSEq_3 + twob_zSEq_1;
J_53 = twob_xSEq_2 + twob_zSEq_4;
J_54 = twob_xSEq_1 - twob_zSEq_3;
J_61 = twob_xSEq_3;
J_62 = twob_xSEq_4 - 2.0f * twob_zSEq_2;
J_63 = twob_xSEq_1 - 2.0f * twob_zSEq_3;
J_64 = twob_xSEq_2;
SEqHatDot_1 = J_14or21 * f_2 - J_11or24 * f_1 -J_41 * f_4 - J_51 * f_5 + J_61 * f_6;
SEqHatDot_2 = J_12or23 * f_1 + J_13or22 * f_2 -J_32 * f_3 + J_42 * f_4 + J_52 * f_5 + J_62 * f_6;
SEqHatDot_3 = J_12or23 * f_2 - J_33 * f_3 - J_13or22 * f_1 - J_43 * f_4 + J_53 * f_5 + J_63 * f_6;
SEqHatDot_4 = J_14or21 * f_1 + J_11or24 * f_2 - J_44 * f_4 - J_54 * f_5 + J_64 * f_6;
// normalise the gradient to estimate direction of the gyroscope error
norm = sqrt(SEqHatDot_1 * SEqHatDot_1 + SEqHatDot_2 * SEqHatDot_2 + SEqHatDot_3 * SEqHatDot_3 + SEqHatDot_4 * SEqHatDot_4);
SEqHatDot_1 = SEqHatDot_1 / norm;
SEqHatDot_2 = SEqHatDot_2 / norm;
SEqHatDot_3 = SEqHatDot_3 / norm;
SEqHatDot_4 = SEqHatDot_4 / norm;
w_err_x = twoSEq_1 * SEqHatDot_2 - twoSEq_2 * SEqHatDot_1 - twoSEq_3 * SEqHatDot_4 + twoSEq_4 * SEqHatDot_3;
w_err_y = twoSEq_1 * SEqHatDot_3 + twoSEq_2 * SEqHatDot_4 - twoSEq_3 * SEqHatDot_1 - twoSEq_4 * SEqHatDot_2;
w_err_z = twoSEq_1 * SEqHatDot_4 - twoSEq_2 * SEqHatDot_3 + twoSEq_3 * SEqHatDot_2 - twoSEq_4 * SEqHatDot_1;
w_bx += w_err_x * deltat * zeta;
w_by += w_err_y * deltat * zeta;
w_bz += w_err_z * deltat * zeta;
w_x -= w_bx;
w_y -= w_by;
w_z -= w_bz;
SEqDot_omega_1 = -halfSEq_2 * w_x - halfSEq_3 * w_y - halfSEq_4 * w_z;
SEqDot_omega_2 = halfSEq_1 * w_x + halfSEq_3 * w_z - halfSEq_4 * w_y;
SEqDot_omega_3 = halfSEq_1 * w_y - halfSEq_2 * w_z + halfSEq_4 * w_x;
SEqDot_omega_4 = halfSEq_1 * w_z + halfSEq_2 * w_y - halfSEq_3 * w_x;
SEq_1 += (SEqDot_omega_1 - (beta *SEqHatDot_1)) * deltat;
SEq_2 += (SEqDot_omega_2 - (beta *SEqHatDot_2)) * deltat;
SEq_3 += (SEqDot_omega_3 - (beta *SEqHatDot_3)) * deltat;
SEq_4 += (SEqDot_omega_4 - (beta *SEqHatDot_4)) * deltat;
norm = sqrt(SEq_1 * SEq_1 + SEq_2 * SEq_2 + SEq_3 * SEq_3 + SEq_4 * SEq_4);
SEq_1 /= norm;
SEq_2 /= norm;
SEq_3 /= norm;
SEq_4 /= norm;
// compute flux in the earth frame
SEq_1SEq_2 = SEq_1 * SEq_2;
SEq_1SEq_3 = SEq_1 * SEq_3;
SEq_1SEq_4 = SEq_1 * SEq_4;
SEq_3SEq_4 = SEq_3 * SEq_4;
SEq_2SEq_3 = SEq_2 * SEq_3;
SEq_2SEq_4 = SEq_2 * SEq_4;
h_x = twom_x * (0.5f - SEq_3 * SEq_3 - SEq_4 * SEq_4) + twom_y * (SEq_2SEq_3 - SEq_1SEq_4) + twom_z * (SEq_2SEq_4 + SEq_1SEq_3);
h_y = twom_x * (SEq_2SEq_3 + SEq_1SEq_4) + twom_y * (0.5f - SEq_2 * SEq_2 - SEq_4 * SEq_4) + twom_z * (SEq_3SEq_4 - SEq_1SEq_2);
h_z = twom_x * (SEq_2SEq_4 - SEq_1SEq_3) + twom_y * (SEq_3SEq_4 + SEq_1SEq_2) + twom_z * (0.5f - SEq_2 * SEq_2 - SEq_3 * SEq_3);
// normalise the flux vector to have only components in the x and z
b_x = sqrt((h_x * h_x) + (h_y * h_y));
b_z = h_z;
}

View File

@ -0,0 +1,66 @@
/* YourDuino.com Example: BlueTooth HC-05 Setup
- WHAT IT DOES:
- Sets "Key" pin on HC-05 HIGH to enable command mode
- THEN applies Vcc from 2 Arduino pins to start command mode
- SHOULD see the HC-05 LED Blink SLOWLY: 2 seconds ON/OFF
Sends, Receives AT commands
For Setup of HC-05 type BlueTooth Module
NOTE: Set Serial Monitor to 'Both NL & CR' and '9600 Baud' at bottom right
- SEE the comments after "//" on each line below
- CONNECTIONS:
- GND
- Pin 2 to HC-05 TXD
- Pin 3 to HC-05 RXD
- Pin 4 to HC-05 KEY
- Pin 5+6 to HC-05 VCC for power control
- V1.02 05/02/2015
Questions: terry@yourduino.com */
/*-----( Import needed libraries )-----*/
//#include <SoftwareSerial.h>
/*-----( Declare Constants and Pin Numbers )-----*/
//#define HC_05_TXD_ARDUINO_RXD 2
//#define HC_05_RXD_ARDUINO_TXD 3
//#define HC_05_SETUPKEY 4
//#define HC_05_PWR1 5 // Connect in parallel to HC-05 VCC
//#define HC_05_PWR2 6 // Connect in parallel to HC-05 VCC
/*-----( Declare objects )-----*/
//SoftwareSerial BTSerial(HC_05_TXD_ARDUINO_RXD, HC_05_RXD_ARDUINO_TXD); // RX | TX
/*-----( Declare Variables )-----*/
//NONE
void setup() /****** SETUP: RUNS ONCE ******/
{
//pinMode(HC_05_SETUPKEY, OUTPUT); // this pin will pull the HC-05 pin 34 (key pin) HIGH to switch module to AT mode
//pinMode(HC_05_PWR1, OUTPUT); // Connect in parallel to HC-05 VCC
//pinMode(HC_05_PWR2, OUTPUT); // Connect in parallel to HC-05 VCC
//digitalWrite(HC_05_SETUPKEY, HIGH); // Set command mode when powering up
Serial.begin(115200); // For the Arduino IDE Serial Monitor
Serial1.begin(38400); // HC-05 default speed in AT command mode
}//--(end setup )---
char c;
void loop() /****** LOOP: RUNS CONSTANTLY ******/
{
// READ from HC-05 and WRITE to Arduino Serial Monitor
if (Serial1.available())
Serial.write(Serial1.read());
// READ Arduino Serial Monitor and WRITE to HC-05
if (Serial.available()) {
Serial1.print(c=Serial.read());
Serial.print(c);
}
}
//--(end main loop )---
/*-----( Declare User-written Functions )-----*/
//NONE
//*********( THE END )***********

View File

@ -0,0 +1,267 @@
#define MtAchA 2
#define MtAchB 3
#define MtBchA 11
#define MtBchB 12
#define MtAI1 4
#define MtAI2 7
#define MtBI1 8
#define MtBI2 9
#define MtAE 5
#define MtBE 6
volatile int lastEncA = 0;
volatile long encValA = 0;
volatile int lastEncB = 0;
volatile long encValB = 0;
long lastencValA = 0;
long lastencValB = 0;
int lastMSBA = 0;
int lastLSBA = 0;
int lastMSBB = 0;
int lastLSBB = 0;
void setup() {
Serial.begin(57600);
pinMode(MtAchA, INPUT);
pinMode(MtAchB, INPUT); //interrupt pins
pinMode(MtBchA, INPUT);
pinMode(MtBchB, INPUT);
pinMode(MtAE, OUTPUT); //pwn pins
pinMode(MtBE, OUTPUT);
pinMode(MtAI1, OUTPUT); //direction pins
pinMode(MtAI2, OUTPUT);
pinMode(MtBI1, OUTPUT);
pinMode(MtBI2, OUTPUT);
PORTB = (PORTB & 0b11111100) | 0b00000011;
PORTD = (PORTD & 0b01101111) | 0b10010000;
digitalWrite(MtAchA, HIGH);
digitalWrite(MtAchB, HIGH);
digitalWrite(MtBchA, HIGH);
digitalWrite(MtBchB, HIGH);
attachInterrupt(0, updateEncA, CHANGE);
attachInterrupt(1, updateEncA, CHANGE);
*digitalPinToPCMSK(MtBchA) |= bit(digitalPinToPCMSKbit(MtBchA)); // enable pin
PCIFR |= bit(digitalPinToPCICRbit(MtBchA)); // clear any outstanding interrupt
PCICR |= bit(digitalPinToPCICRbit(MtBchA)); // enable interrupt for the group
*digitalPinToPCMSK(MtBchB) |= bit(digitalPinToPCMSKbit(MtBchB)); // enable pin
PCIFR |= bit(digitalPinToPCICRbit(MtBchB)); // clear any outstanding interrupt
PCICR |= bit(digitalPinToPCICRbit(MtBchB)); // enable interrupt for the group
analogWrite(MtAE, 1);
analogWrite(MtBE, 1);
OCR0A = OCR0B = 0;
}
int pos = 0;
int ang = 0;
int vel = 0;
float pP = 0, iP = 0, dP = 0, alphaP = 0.7;
float pA = 0, iA = 0, dA = 0, alphaA = 0.7;
int errA = 0, perrA = 0, cerrA = 0;
int errP = 0, perrP = 0, cerrP = 0;
int pwmA = 0, pwmB = 0, pwm = 0, outA = 0;
void loop() {
if (Serial.available() > 2)
{
char ch = Serial.read();
if (ch == 's')
{
switch (Serial.read())
{
case 'p':
pos = Serial.parseInt();
break;
case 'a':
ang = Serial.parseInt();
break;
case 'v':
vel = Serial.parseInt();
if (abs(vel) > 225)
vel = 255;
else
vel = abs(vel);
break;
// tuning
case 'P':
switch (Serial.read())
{
case 'p':
pP = Serial.parseFloat();
break;
case 'i':
iP = Serial.parseFloat();
break;
case 'd':
dP = Serial.parseFloat();
break;
}
case 'A':
switch (Serial.read())
{
case 'p':
pA = Serial.parseFloat();
break;
case 'i':
iA = Serial.parseFloat();
break;
case 'd':
dA = Serial.parseFloat();
break;
}
/*
case '0':
ang = 0;
cerrA = 0;
pos = 0;
cerrP = 0;
encValA = encValB = 0;
break;
*/
}
Serial.read();
}
}
errP = 2 * pos - (encValA + encValB);
cerrP += errP * iP;
if(vel > 0)
cerrP = constrain(cerrP, -vel*0.5, vel*0.5);
else if(vel == 0)
cerrP = 0;
pwm = errP * pP + (-perrP * alphaP + errP * (1 - alphaP)) * dP + cerrP;
perrP = errP;
if (vel > 0)
pwm = constrain(pwm, -vel, vel);
else if (vel == 0)
pwm = 0;
errA = ang - (encValB - encValA);
cerrA += errA * iA;
if(vel > 0)
cerrA = constrain(cerrA, -vel, vel);
else if(vel == 0)
cerrA = 0;
outA = errA * pA + (-perrA * alphaA + errA * (1 - alphaA)) * dA + cerrA;
perrA = errA;
if (vel > 0)
{
outA = constrain(outA, -vel * 0.95, vel * 0.95);
pwmA = pwm - outA;
pwmB = pwm + outA;
pwmA = constrain(pwmA, -255, 255);
pwmB = constrain(pwmB, -255, 255);
}
else if(vel == 0)
{
pwmA = pwmB = 0;
outA = 0;
errP = 0;
}
Serial.print(errP);
Serial.print('\t');
Serial.print(pwm);
Serial.print('\t');
Serial.print(errA);
Serial.print('\t');
Serial.print(outA);
Serial.print('\t');
Serial.print(pwmA);
Serial.print('\t');
Serial.println(pwmB);
/*
if (errP == 0)
{
cerrP = 0;
encValA = encValB = pos;
}
if (errA == 0)
{
ang = 0;
cerrA = 0;
}
*/
if ((errP == 0) && (errA == 0))
{
ang = 0;
cerrA = 0;
pos = 0;
cerrP = 0;
encValA = encValB = 0;
}
if (pwmB > 0)
PORTB = (PORTB & 0b11111100) | 0b00000010;
else if (pwmB < 0)
{
pwmB *= -1;
PORTB = (PORTB & 0b11111100) | 0b00000001;
}
else
PORTB = PORTB | 0b00000011;
if (pwmA > 0)
PORTD = (PORTD & 0b01101111) | 0b00010000;
else if (pwmA < 0)
{
pwmA *= -1;
PORTD = (PORTD & 0b01101111) | 0b10000000;
}
else
PORTD = PORTD | 0b10010000;
OCR0A = pwmB;
OCR0B = pwmA;
}
void updateEncA() {
int MSB = (PIND >> 2) & 0b00000001; //MSB = most significant bit
int LSB = (PIND >> 3) & 0b00000001; //LSB = least significant bit
int encoded = (MSB << 1) | LSB; //converting the 2 pin value to single number
int sum = (lastEncA << 2) | encoded; //adding it to the previous encoded value
if (sum == 0b1101 || sum == 0b0100 || sum == 0b0010 || sum == 0b1011) encValA++;
if (sum == 0b1110 || sum == 0b0111 || sum == 0b0001 || sum == 0b1000) encValA--;
lastEncA = encoded; //store this value for next time
}
ISR(PCINT0_vect) {
int MSB = (PINB >> 3) & 0b00000001; //MSB = most significant bit
int LSB = (PINB >> 4) & 0b00000001; //LSB = least significant bit
int encoded = (MSB << 1) | LSB; //converting the 2 pin value to single number
int sum = (lastEncB << 2) | encoded; //adding it to the previous encoded value
if (sum == 0b1101 || sum == 0b0100 || sum == 0b0010 || sum == 0b1011) encValB--;
if (sum == 0b1110 || sum == 0b0111 || sum == 0b0001 || sum == 0b1000) encValB++;
lastEncB = encoded; //store this value for next time
}

View File

@ -0,0 +1,2 @@
PID tuner for encoder motors.
Alpha version.

View File

@ -0,0 +1,408 @@
#include "I2Cdev.h"
#include "MPU6050_6Axis_MotionApps20.h"
#include "Wire.h"
#include "Kalman.h"
MPU6050 mpu;
#define mag 0x0C
#define LTM_DIR 7
#define RTM_DIR 4
#define LTM_PWM 6
#define RTM_PWM 5
#define LTM_INT 12
#define RTM_INT 3
#define F 1
#define MPU_INT 2
#define pitch 0
#define yaw 1
#define L 2
#define R 3
#define N 10
#define BACKLASH_COMP 20
float MPU_ZERO = 4.0;
#define ma 1000
#define m 5
#define n 5
bool dmpReady = false; // set true if DMP init was successful
uint8_t mpuIntStatus; // holds actual interrupt status byte from MPU
uint8_t devStatus; // return status after each device operation (0 = success, !0 = error)
uint16_t packetSize; // expected DMP packet size (default is 42 bytes)
uint16_t fifoCount; // count of all bytes currently in FIFO
uint8_t fifoBuffer[64]; // FIFO storage buffer
Kalman filter;
uint32_t timer;
int32_t RV;
int32_t LV;
volatile bool rDir = 0, lDir = 0;
float vel_P = -1.1, vel_I = -0.2, cerr_D; float head_P = 0.05, head_I = 0.1, cerr_Yaw;
float Offset[4] = { 0,0,0,0 };
float Offset_dot[4] = { 0,0,0,0 };
float in[4];
float in_dot[4];
float E[4];
float Er[4];/*
0 Pitch
1 Yaw
2 dist_L
3 dist_R
*/
uint8_t mode = 1;/*
0 - Calculate Offset.
1 - Maintain Balance and Position
2 - Turn by x degrees
3 - Move x distance
4 - Turn while moving
default - Maintain and Rotate
*/
volatile bool mpuInterrupt = false;
volatile uint8_t vel_tim = 0;
void dmpDataReady() {
mpuInterrupt = true;
vel_tim++;
}
volatile int16_t ERC, ELC; volatile int8_t addR = 0, addL = 0;
void encoderInt() {
ERC += addR;
}
ISR(PCINT0_vect) {
ELC += addL;
}
void turnByX(float x) {}
void moveByD(int D) {}
void moveByAndTurn(int d, float x) {}
void maintainAndRotate() {}
void calculateOffset() {}
void setMode(int a) {
mode = a;
/*
0 - Calculate Offset.
1 - Maintain Balance and Position
2 - Turn by x degrees
3 - Move x distance
4 - Turn while moving
default - Maintain and Rotate
*/
Offset[yaw] = in[yaw];
switch (mode)
{
case 0:
break;
case 1:
break;
case 2:
break;
case 3:
break;
case 4:
break;
default:
break;
}
}
int pos_e[2], pos_er[2];
int x_[] = { -10, -5, 0, 5, 10 },
x_dot[] = { -60, -20, 0, 20, 60 },
err_dom[n], err_dot_dom[m],
out[m][n] = { { -255, -248, -104, 40, 200 },
{ -255, -192, -48, 96, 255 },
{ -255, -144, 0, 144, 255 },
{ -255, -96, 48, 192, 255 },
{ -200, -40, 104, 248, 255 } }
;
void calc_dom(float err, int *x, int *dom, int l, int *pos, int maxx) {
if (err <= x[0]) {
dom[0] = maxx;
pos[0] = pos[1] = 0;
return;
}
if (err >= x[l - 1]) {
dom[l - 1] = maxx;
pos[0] = pos[1] = l - 1;
return;
}
for (int i = 0; i < l - 1; i++) {
if ((err > x[i]) && (err < x[i + 1])) {
float s = (maxx * 1.0f) / (x[i + 1] - x[i]);
dom[i] = (int)(-s * (err - x[i + 1]));
dom[i + 1] = (int)(s * (err - x[i]));
pos[0] = i;
pos[1] = i + 1;
return;
}
else
if (err == x[i]) {
dom[i] = maxx;
pos[0] = pos[1] = i;
return;
}
}
}
int calc_fuzzy(float err, int err_dot)
{
double output = 0;
calc_dom(err, x_, err_dom, n, pos_e, ma);
calc_dom(err_dot, x_dot, err_dot_dom, m, pos_er, ma);
int sum = 0; double t = 0;
for (int i = 0; i < 2; i++)
for (int j = 0; j < 2; j++) {
output += (t = min(err_dot_dom[pos_er[j]], err_dom[pos_e[i]])) * out[pos_er[j]][pos_e[i]];
sum += t;
}
output /= sum;
return output;
}
void setup() {
Serial.begin(57600);
Wire.begin();
Wire.setClock(400000); // 400kHz I2C clock. Comment this line if having compilation difficulties
mpu.initialize();
*digitalPinToPCMSK(LTM_INT) |= bit(digitalPinToPCMSKbit(LTM_INT));
PCIFR |= bit(digitalPinToPCICRbit(LTM_INT));
PCICR |= bit(digitalPinToPCICRbit(LTM_INT));
pinMode(MPU_INT, INPUT);
pinMode(LTM_INT, INPUT);
pinMode(RTM_INT, INPUT);
pinMode(LTM_DIR, OUTPUT);
pinMode(RTM_DIR, OUTPUT);
pinMode(LTM_PWM, OUTPUT);
pinMode(RTM_PWM, OUTPUT);
analogWrite(RTM_PWM, 1);
analogWrite(LTM_PWM, 1);
mpu.testConnection();
devStatus = mpu.dmpInitialize();
mpu.setXGyroOffset(-1);
mpu.setYGyroOffset(-1);
mpu.setZGyroOffset(255);
mpu.setXAccelOffset(705);
mpu.setYAccelOffset(-139);
mpu.setZAccelOffset(1219);
mpu.setDMPEnabled(true);
attachInterrupt(digitalPinToInterrupt(MPU_INT), dmpDataReady, RISING);
attachInterrupt(digitalPinToInterrupt(RTM_INT), encoderInt, CHANGE);
mpuIntStatus = mpu.getIntStatus();
dmpReady = true;
packetSize = mpu.dmpGetFIFOPacketSize();
mpu.setI2CBypassEnabled(true);
I2Cdev::writeByte(mag, 0x0A, 0x1);
setMode(1);
}
int c = 0;
float p,d,a,b;
void loop()
{
if (!dmpReady) return;
while (!mpuInterrupt && fifoCount < packetSize);
mpuInterrupt = false;
mpuIntStatus = mpu.getIntStatus();
fifoCount = mpu.getFIFOCount();
if ((mpuIntStatus & 0x10) || fifoCount == 1024)
I2Cdev::writeBit(0x68, 0x6A, 2, 1);//reset FIFO
else
if (mpuIntStatus & 0x02) {
while (fifoCount < packetSize)
fifoCount = mpu.getFIFOCount();
I2Cdev::readBytes(0x68, 0x74, packetSize, fifoBuffer);//read FIFO
fifoCount -= packetSize;
get_input();
if (Serial.available()>2) {
switch (Serial.read())
{
//case 'p':kp = Serial1.parseFloat();break;
case 'i': MPU_ZERO = Serial.parseFloat();break;
case 'd': head_I = Serial.parseFloat(); break;
case 'a': vel_P = Serial.parseFloat(); break;
case 'b': vel_I = Serial.parseFloat(); break;
case 'c': head_P = Serial.parseFloat(); break;
case 's': Offset[L] = Offset[R] = Serial.parseFloat(); break;
case 'e': c = Serial.parseInt(); break;
case 'q': p = Serial.parseFloat();break;
case 'w': d = Serial.parseFloat();break;
}
Serial.read();
}
switch (mode) {
case 0:
calculateOffset();
break;
case 1:
stayStill();
break;
case 2:
break;
case 3:
break;
case 4:
break;
default:
maintainAndRotate();
}
if (abs(in[pitch]) > 30)
output(0, 0);
else {
LV = constrain(LV, -255, 255);
RV = constrain(RV, -255, 255);
output(LV, RV);
}
}
}
uint8_t buffer[6];
void get_input() {
I2Cdev::readBytes(mag, 0x03, 4, buffer);
I2Cdev::writeByte(mag, 0x0A, 0x1);
float w = ((fifoBuffer[0] << 8) | fifoBuffer[1]) / 16384.0;
float x = ((fifoBuffer[4] << 8) | fifoBuffer[5]) / 16384.0;
float y = ((fifoBuffer[8] << 8) | fifoBuffer[9]) / 16384.0;
float z = ((fifoBuffer[12] << 8) | fifoBuffer[13]) / 16384.0;
float ty = 2 * (w * x + y * z);
float tz = w * w - x * x - y * y + z * z;
//mz = -(((int16_t)buffer[5]) << 8) | buffer[4];
float tempYaw;
double dt = (micros() - timer) / 1000000.0;
timer = micros();
float my = (((int16_t)buffer[1]) << 8) | buffer[0];
float mx = (((int16_t)buffer[3]) << 8) | buffer[2];
float mz = -(((int16_t)buffer[5]) << 8) | buffer[4];
in[pitch] = atan((2 * (x * z - w * y)) / sqrt(ty * ty + tz * tz));
tempYaw = atan2(my, mx + mz * sin(in[pitch])) * 180.0 / 3.14159265;
in[pitch] = in[pitch] * RAD_TO_DEG - MPU_ZERO;
in_dot[yaw] = -((fifoBuffer[24] << 8) | fifoBuffer[25]);
in_dot[pitch] = -((fifoBuffer[20] << 8) | fifoBuffer[21]);
if ((tempYaw < -90 && in[yaw] > 90) || (tempYaw > 90 && in[yaw] < -90)) {
filter.setAngle(tempYaw);
in[yaw] = tempYaw;
}
else
in[yaw] = filter.getAngle(tempYaw, in_dot[yaw] / 131.0, dt);
//Serial.println(dt);
if (vel_tim == N) {
int tempR = ERC, tempL = ELC;
ERC = ELC = 0;
in[R] += tempR;
in_dot[R] = tempR;
in[L] += tempL;
in_dot[L] = tempL;
//Serial.println(in[L] + in[R]);
vel_tim = 0;
}
}
void output(int16_t LT, int16_t RT) {
if (RT != 0) {
if (RT > 0) {
if (rDir != F) {
addR = 1;
rDir = F;
PORTD |= _BV(RTM_DIR);
}
}
else
if (rDir != (!F)) {
addR = -1;
rDir = !F;
PORTD &= ~_BV(RTM_DIR);
}
OCR0B = map(abs(RT), 0, 255, BACKLASH_COMP, 200) * 1.2 + 10;
}
else
OCR0B = 0;
if (LT != 0) {
if (LT > 0) {
if (lDir != F) {
addL = 1;
lDir = F;
PORTD |= _BV(LTM_DIR);
}
}
else
if (lDir != (!F)) {
addL = -1;
lDir = !F;
PORTD &= ~_BV(LTM_DIR);
}
OCR0A = map(abs(LT), 0, 255, BACKLASH_COMP, 200) + 3;
}
else
OCR0A = 0;
}
void cal_Angle_Err() {
for (int i = 0; i < 2; i++) {
E[i] = Offset[i] - in[i];
Er[i] = Offset_dot[i] - in_dot[i];
}
}
void cal_Vel_Err() {
for (int i = 2; i < 4; i++) {
E[i] = Offset[i] - in[i];
Er[i] = Offset_dot[i] - in_dot[i];
}
}
int head_PI() {
cerr_Yaw += E[yaw];
cerr_Yaw = constrain(cerr_Yaw, -50, 50);
return constrain((head_P * E[yaw] + head_I * cerr_Yaw), -60, 60);
}
float perr;
float vel_PI(float err, float *cerr) {
err = perr * 0.7 + err * 0.3;
perr = err;
//Serial.println(err);
*cerr += err;
*cerr = constrain(*cerr, -3, 3);
return constrain(vel_P * err + vel_I * (*cerr), -8, 8);
}
float dis_PI(int err) {
}
void stayStill() {
if (vel_tim == 0) {
cal_Vel_Err();
Offset[pitch] = (vel_PI(Er[L] + Er[R] + c * (E[L] + E[R]) * 0.3, &cerr_D));
}
cal_Angle_Err();
LV = RV = calc_fuzzy(E[pitch], Er[pitch]);
//LV = RV = p * E[pitch] + d * Er[pitch];
int dif = head_PI();
LV -= dif;
RV += dif;
Serial.print(p);
Serial.print(' '); Serial.print(d);
Serial.print(' ');
Serial.println(E[pitch]);
}

View File

@ -0,0 +1,108 @@
/* Copyright (C) 2012 Kristian Lauszus, TKJ Electronics. All rights reserved.
This software may be distributed and modified under the terms of the GNU
General Public License version 2 (GPL2) as published by the Free Software
Foundation and appearing in the file GPL2.TXT included in the packaging of
this file. Please note that GPL2 Section 2[b] requires that all works based
on this software must also be made publicly available under the terms of
the GPL2 ("Copyleft").
Contact information
-------------------
Kristian Lauszus, TKJ Electronics
Web : http://www.tkjelectronics.com
e-mail : kristianl@tkjelectronics.com
*/
#ifndef _Kalman_h
#define _Kalman_h
class Kalman {
public:
Kalman() {
/* We will set the variables like so, these can also be tuned by the user */
Q_angle = 0.001;
Q_bias = 0.003;
R_measure = 0.03;
angle = 0; // Reset the angle
bias = 0; // Reset bias
P[0][0] = 0; // Since we assume that the bias is 0 and we know the starting angle (use setAngle), the error covariance matrix is set like so - see: http://en.wikipedia.org/wiki/Kalman_filter#Example_application.2C_technical
P[0][1] = 0;
P[1][0] = 0;
P[1][1] = 0;
};
// The angle should be in degrees and the rate should be in degrees per second and the delta time in seconds
double getAngle(double newAngle, double newRate, double dt) {
// KasBot V2 - Kalman filter module - http://www.x-firm.com/?page_id=145
// Modified by Kristian Lauszus
// See my blog post for more information: http://blog.tkjelectronics.dk/2012/09/a-practical-approach-to-kalman-filter-and-how-to-implement-it
// Discrete Kalman filter time update equations - Time Update ("Predict")
// Update xhat - Project the state ahead
/* Step 1 */
rate = newRate - bias;
angle += dt * rate;
// Update estimation error covariance - Project the error covariance ahead
/* Step 2 */
P[0][0] += dt * (dt*P[1][1] - P[0][1] - P[1][0] + Q_angle);
P[0][1] -= dt * P[1][1];
P[1][0] -= dt * P[1][1];
P[1][1] += Q_bias * dt;
// Discrete Kalman filter measurement update equations - Measurement Update ("Correct")
// Calculate Kalman gain - Compute the Kalman gain
/* Step 4 */
S = P[0][0] + R_measure;
/* Step 5 */
K[0] = P[0][0] / S;
K[1] = P[1][0] / S;
// Calculate angle and bias - Update estimate with measurement zk (newAngle)
/* Step 3 */
y = newAngle - angle;
/* Step 6 */
angle += K[0] * y;
bias += K[1] * y;
// Calculate estimation error covariance - Update the error covariance
/* Step 7 */
P[0][0] -= K[0] * P[0][0];
P[0][1] -= K[0] * P[0][1];
P[1][0] -= K[1] * P[0][0];
P[1][1] -= K[1] * P[0][1];
return angle;
};
void setAngle(double newAngle) { angle = newAngle; }; // Used to set angle, this should be set as the starting angle
double getRate() { return rate; }; // Return the unbiased rate
/* These are used to tune the Kalman filter */
void setQangle(double newQ_angle) { Q_angle = newQ_angle; };
void setQbias(double newQ_bias) { Q_bias = newQ_bias; };
void setRmeasure(double newR_measure) { R_measure = newR_measure; };
double getQangle() { return Q_angle; };
double getQbias() { return Q_bias; };
double getRmeasure() { return R_measure; };
private:
/* Kalman filter variables */
double Q_angle; // Process noise variance for the accelerometer
double Q_bias; // Process noise variance for the gyro bias
double R_measure; // Measurement noise variance - this is actually the variance of the measurement noise
double angle; // The angle calculated by the Kalman filter - part of the 2x1 state vector
double bias; // The gyro bias calculated by the Kalman filter - part of the 2x1 state vector
double rate; // Unbiased rate calculated from the rate and the calculated bias - you have to call getAngle to update the rate
double P[2][2]; // Error covariance matrix - This is a 2x2 matrix
double K[2]; // Kalman gain - This is a 2x1 vector
double y; // Angle difference
double S; // Estimate error
};
#endif

View File

@ -0,0 +1 @@
These are various algorithms tested for two wheeled self balancing robot.

View File

@ -0,0 +1,289 @@
#include "I2Cdev.h"
#include "MPU6050_6Axis_MotionApps20.h"
#include "Wire.h"
#define LTMDIR 7
#define RTMDIR 4
#define LTMPWM 6
#define RTMPWM 5
#define LTMINT 2
#define RTMINT 3
MPU6050 mpu;
int rn = 0, ln = 0;
float r1 = 0, l1 = 0;
float rv = 0, lv = 0;
uint16_t packetSize;
uint16_t fifoCount;
uint8_t fifoBuffer[64];
bool rDir = 0;
bool lDir = 0;
uint32_t t, t1, t2;
int turn = 0;
int lout = 0;
int rout = 0;
double cgcerr = 0;
volatile uint8_t rc = 0;
volatile uint8_t lc = 0;
volatile bool mpuInterrupt = false;
Quaternion q;
VectorFloat gravity;
int16_t gyro[3];
float gy;
float ypr[3];
int m = 20;
float cg = 0;
float cgoffset = 0;
float angs = 20.0;
float alpha = 0, kcg, kcgd, kcgi, kangi =0.0, kangp = 0.5, kangd = 5.0;float angcerr = 0.0;
float angle = 0;float pangle = 0;float z;
void motorControl();
void getYPR();
void calculate();
int pout = 0;
void setup() {
Wire.begin();
Serial.begin(57600);
delay(10);
mpuInit();
//delay(15000);
intInit();
delay(10);
getYPR();
z = (pow(kangp,angs/57.2958)-1);
cgoffset = 4.7;
pinMode(LTMINT, INPUT);
pinMode(RTMINT, INPUT);
pinMode(LTMDIR, OUTPUT);
pinMode(RTMDIR, OUTPUT);
pinMode(LTMPWM, OUTPUT);
pinMode(RTMPWM, OUTPUT);
analogWrite(RTMPWM,1);
analogWrite(LTMPWM,1);
t=millis();
t1=millis();
}
int out = 0;
void loop() {
if( mpuInterrupt )
{
getYPR();
t2 = millis() - t;
t=millis();
Serial.println(t2);
odor();
cgPID(t2);
angle = cg - ypr[1];
if(abs(pangle-angle)<3){
out = anglePD() + t2 * alpha / 100.0;
pangle = angle;
}
pangle = angle;
rc = lc = 0;
lout = out + turn;
rout = out - turn;
rDir = ( (rout > 0) ? 1 : 0);
lDir = ( (lout > 0) ? 1 : 0);
lout = abs( lout );
rout = abs( rout );
/*if(lout != 0)
{
if( (lout > 0) && (lout < m) )lout = m;
}*/
lout = constrain(lout, -255, 255);
rout = constrain(rout, -255, 255);
if(lout!=0)
lout = map(lout, 0 , 255 , m, 200);
if(rout!=0)
rout = map(rout, 0 , 255 , m, 200);
/*if(rout != 0)
{
if( (rout > 0) && (rout < m) )rout = m;
}*/
if((abs(pout - out)>150)||abs(angle) > 40)
motorControl( 0, 0);
else{
motorControl( rout, lout);pout = out;}
Serial.print(out);
Serial.print("\t");
//Serial.print(", ");
Serial.print(ypr[1]);
Serial.print("\t");
Serial.println(abs(angle));
//Serial.print("\tra la\t");
//Serial.print(ra);
//Serial.print(",");
//Serial.println(la);
}
if(Serial.available()>2){
switch (Serial.read())
{
case 'p':kangp = Serial.parseFloat();z = (pow(kangp,angs/57.2958)-1);break;
case 'i':kangi = Serial.parseFloat();break;
case 'd':kangd = Serial.parseFloat();break;
case 'a':kcg = Serial.parseFloat();break;
case 'b':kcgi = Serial.parseFloat();break;
case 'c':kcgd = Serial.parseFloat();break;
case 's':cgoffset = Serial.parseFloat();t = millis();break;
case 'e':alpha = Serial.parseFloat();t = millis();break;
case 't':angs = Serial.parseFloat();z = (pow(kangp,angs/57.2958)-1);break;
//case 'a':an=Serial.parseFloat();break;
case 'm':m = Serial.parseFloat();break;
}
Serial.read();
}
//Serial.print(asp);Serial.print("\t");Serial.print(ap);Serial.print("\t");Serial.print(li);Serial.print("\t");Serial.print(ad);Serial.print("\t");Serial.println(lp);
}
void cgPID(uint32_t t){
float err = t * alpha / 100.0 - (rv + lv) / 2.0;
cgcerr += kcgi * err;
cgcerr = constrain( cgcerr, -5, 5);
cg = err * kcg + cgcerr + kcgd * gy + cgoffset;
cg = constrain(cg, -10, 10);
}
float anglePD()
{
float err = alpha - angle;
angcerr += err;
angcerr = constrain(angcerr, -20, +20);
return (err/abs(err))*
(pow(kangp,abs(err)/57.2958)-1)*255.0/z + angcerr * kangi + (gy) * kangd;
//return ( 400.0 * (1.0 / (1+exp(-err * kangp))-0.5) + angcerr * kangi + gy * kangd);
//return (err * kangp + angcerr * kangi + gy * kangd);
}
void odor(){
t1 = (millis() - t1);
if(!lDir)
{
lv = -1 * lc;
lc = 0;
}
else
{
lv = lc;
lc = 0;
}
if(!rDir)
{
rv = -1 * rc;
rc = 0;
}
else
{
rv = rc;
rc=0;
}
r1 += rv;
l1 += lv;
rv = rv * 1000.0 / t1;
lv = lv * 1000.0 / t1;
t1=millis();
if(abs(r1) > 29)
{
if(r1 > 29)
{
rn++;
r1 -= 30;
}
else
{
rn--;
r1 += 30;
}
}
if(abs(l1) > 29)
{
if(l1 > 29)
{
ln++;
l1 -= 30;
}
else
{
ln--;
l1 += 30;
}
}
}
void motorControl(int a, int b)
{
if(lDir)
PORTD |= _BV(RTMDIR);
else
PORTD &= ~_BV(RTMDIR);
if(rDir)
PORTD |= _BV(LTMDIR);
else
PORTD &= ~_BV(LTMDIR);
OCR0B = ( ( abs( a ) <= 200 ) ? a : 0 );
OCR0A = ( ( abs( b ) <= 200 ) ? b : 0 ) * 1.2 + 10;
}
void getYPR(){
mpuInterrupt = false;
fifoCount = mpu.getFIFOCount();
while (fifoCount < packetSize) {fifoCount = mpu.getFIFOCount();}
mpu.getFIFOBytes(fifoBuffer, packetSize);
fifoCount -= packetSize;
mpu.dmpGetQuaternion(&q, fifoBuffer);
mpu.dmpGetGravity(&gravity, &q);
mpu.dmpGetYawPitchRoll(ypr, &q, &gravity);
mpu.dmpGetGyro(gyro, fifoBuffer);
ypr[1] *= 180 / PI;
gy = -gyro[1]/100.0;
mpu.resetFIFO();
}
ISR(TIMER1_OVF_vect) {
mpuInterrupt = 1;
TCNT1=64886;
}
void intInit(){
mpu.resetFIFO();
TCCR1A=0;
TCCR1B=0;
TCNT1=64886;
TCCR1B |= (1 << CS12);
TIMSK1 |= (1 << TOIE1);
attachInterrupt(digitalPinToInterrupt(RTMINT),RME,RISING);
attachInterrupt(digitalPinToInterrupt(LTMINT),LME,RISING);
}
void LME(){
lc++;
}
void RME(){
rc++;
}
ISR (PCINT0_vect){
if(digitalRead(8) == 1)mpuInterrupt = 1;
}
void mpuInit(){
mpu.initialize();
mpu.testConnection();
mpu.dmpInitialize();
mpu.setXGyroOffset(-1);
mpu.setYGyroOffset(-1);
mpu.setZGyroOffset(255);
mpu.setXAccelOffset(705);
mpu.setYAccelOffset(-139);
mpu.setZAccelOffset(1219);
mpu.setDMPEnabled(true);
packetSize = mpu.dmpGetFIFOPacketSize();
}

View File

@ -0,0 +1,283 @@
#include "I2Cdev.h"
#include "MPU6050_6Axis_MotionApps20.h"
#include "Wire.h"
#define LTMDIR 7
#define RTMDIR 4
#define LTMPWM 6
#define RTMPWM 5
#define LTMINT 2
#define RTMINT 3
#define MPUINT 8
MPU6050 mpu;
int rn = 0, ln = 0;
float r1 = 0, l1 = 0;
float rv = 0, lv = 0;
bool dmpReady = false;
uint8_t mpuIntStatus;
uint8_t devStatus;
uint16_t packetSize;
uint16_t fifoCount;
uint8_t fifoBuffer[64];
bool rDir = 0;
bool lDir = 0;
uint32_t t, t1, t2;
int turn = 0;
int lout = 0;
int rout = 0;
double cgcerr = 0;
volatile uint8_t rc = 0;
volatile uint8_t lc = 0;
volatile bool mpuInterrupt = false;
Quaternion q;
VectorFloat gravity;
int16_t gyro[3];
float gy;
float ypr[3];
int m = 30;
float cg = 0;
float cgoffset = 0;
float angs = 20.0;
float alpha = 0, kcg, kcgd, kcgi, kangp = 1.0, kangd = 10.0;
float angle = 0;float pangle = 0;
void motorControl();
void getYPR();
void calculate();
void setup() {
Wire.begin();
Serial.begin(57600);
delay(10);
mpuInit();
//delay(15000);
intInit();
delay(10);
getYPR();
cgoffset = 3.2;
pinMode(LTMINT, INPUT);
pinMode(RTMINT, INPUT);
pinMode(LTMDIR, OUTPUT);
pinMode(RTMDIR, OUTPUT);
pinMode(LTMPWM, OUTPUT);
pinMode(RTMPWM, OUTPUT);
analogWrite(RTMPWM,1);
analogWrite(LTMPWM,1);
t=millis();
t1=millis();
//motorControl( 100,100);
}
int out = 0;
void loop() {
getYPR();
t2 = millis() - t;
odor();
cgPID(t2);
angle = cg - ypr[1];
if(abs(pangle-angle)<4){
out = anglePD() + t2 * alpha / 100.0;
pangle = angle;
}
rc = lc = 0;
lout = out + turn;
rout = out - turn;
rDir = ( (rout > 0) ? 1 : 0);
lDir = ( (lout > 0) ? 1 : 0);
lout = abs( lout );
rout = abs( rout );
if(lout != 0)
{
if( (lout > 0) && (lout < m) )lout = m;
}
if(rout != 0)
{
if( (rout > 0) && (rout < m) )rout = m;
}
lout = constrain(lout, -200, 200);
rout = constrain(rout, -200, 200);
if(abs(angle) > 40)
motorControl( 0, 0);
else
motorControl( rout, lout);
Serial.print(out);
Serial.print("\t");
//Serial.print(", ");
Serial.print(ypr[1]);
Serial.print("\t");
Serial.println(abs(angle));
//Serial.print("\tra la\t");
//Serial.print(ra);
//Serial.print(",");
//Serial.println(la);
if(Serial.available()>2){
switch (Serial.read())
{
case 'p':kangp = Serial.parseFloat();break;
case 'i':kcgi = Serial.parseFloat();break;
case 'a':kcg = Serial.parseFloat();break;
case 'b':kcgd = Serial.parseFloat();break;
case 'd':kangd = Serial.parseFloat();break;
case 's':cg = Serial.parseFloat();t = millis();break;
case 't':angs = Serial.parseFloat();break;
//case 'a':an=Serial.parseFloat();break;
case 'm':m = Serial.parseFloat();break;
}
Serial.read();
}
//Serial.print(asp);Serial.print("\t");Serial.print(ap);Serial.print("\t");Serial.print(li);Serial.print("\t");Serial.print(ad);Serial.print("\t");Serial.println(lp);
}
void cgPID(uint32_t t){
float err = t * alpha / 100.0 - (rv + lv) / 2.0;
cgcerr += kcgi * err;
cgcerr = constrain( cgcerr, -5, 5);
cg = err * kcg + cgcerr + kcgd * gy + cgoffset;
cg = constrain(cg, -10, 10);
}
float anglePD()
{
float err = alpha - angle;
//return (err/abs(err))*(pow(kangp,abs(err)/57.2958)-1)*255.0/(pow(kangp,angs/57.2958)-1) + (gy) * kangd;
return (err * abs(angle) * kangp + gy * kangd);
}
void odor(){
t1 = (millis() - t1);
if(!lDir)
{
lv = -1 * lc;
lc = 0;
}
else
{
lv = lc;
lc = 0;
}
if(!rDir)
{
rv = -1 * rc;
rc = 0;
}
else
{
rv = rc;
rc=0;
}
r1 += rv;
l1 += lv;
rv = rv * 1000.0 / t1;
lv = lv * 1000.0 / t1;
t1=millis();
if(abs(r1) > 29)
{
if(r1 > 29)
{
rn++;
r1 -= 30;
}
else
{
rn--;
r1 += 30;
}
}
if(abs(l1) > 29)
{
if(l1 > 29)
{
ln++;
l1 -= 30;
}
else
{
ln--;
l1 += 30;
}
}
}
void motorControl(int a, int b)
{
if(lDir)
PORTD |= _BV(RTMDIR);
else
PORTD &= ~_BV(RTMDIR);
if(rDir)
PORTD |= _BV(LTMDIR);
else
PORTD &= ~_BV(LTMDIR);
OCR0B = ( ( abs( a ) <= 200 ) ? a : 0 );
OCR0A = ( ( abs( b ) <= 200 ) ? b : 0 ) * 1.2 + 10;
}
void getYPR(){
while (!mpuInterrupt && fifoCount < packetSize);
mpuInterrupt = false;
mpuIntStatus = mpu.getIntStatus();
fifoCount = mpu.getFIFOCount();
if ((mpuIntStatus & 0x10) || fifoCount == 1024) {
mpu.resetFIFO();
} else if (mpuIntStatus & 0x02)
{
while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount();
mpu.getFIFOBytes(fifoBuffer, packetSize);
fifoCount -= packetSize;
mpu.dmpGetQuaternion(&q, fifoBuffer);
mpu.dmpGetGravity(&gravity, &q);
mpu.dmpGetYawPitchRoll(ypr, &q, &gravity);
mpu.dmpGetGyro(gyro, fifoBuffer);
ypr[1] *= 180 / PI;
gy = -gyro[1]/100.0;
}
}
void intInit(){
mpu.resetFIFO();
TCCR1A=0;
TCCR1B=0;
//TCNT1=64886;
TCCR1B |= (1 << CS12);
TIMSK1 |= (1 << TOIE1);
attachInterrupt(digitalPinToInterrupt(RTMINT),RME,RISING);
attachInterrupt(digitalPinToInterrupt(LTMINT),LME,RISING);
}
void LME(){
lc++;
}
void RME(){
rc++;
}
ISR (PCINT0_vect){
if(digitalRead(8) == 1)mpuInterrupt = 1;
}
void mpuInit(){
mpu.initialize();
pinMode(MPUINT, INPUT);
mpu.testConnection();
devStatus = mpu.dmpInitialize();
mpu.setXGyroOffset(-1);
mpu.setYGyroOffset(-1);
mpu.setZGyroOffset(255);
mpu.setXAccelOffset(705);
mpu.setYAccelOffset(-139);
mpu.setZAccelOffset(1219);
mpu.setDMPEnabled(true);
if (devStatus == 0) {
mpu.setDMPEnabled(true);
*digitalPinToPCMSK(MPUINT) |= bit (digitalPinToPCMSKbit(MPUINT));
PCIFR |= bit (digitalPinToPCICRbit(MPUINT));
PCICR |= bit (digitalPinToPCICRbit(MPUINT));
mpuIntStatus = mpu.getIntStatus();
dmpReady = true;
packetSize = mpu.dmpGetFIFOPacketSize();
}
}

View File

@ -0,0 +1,272 @@
#include "I2Cdev.h"
#include "MPU6050_6Axis_MotionApps20.h"
#include "Wire.h"
#define RAD2GRAD 57.2957795
#define LTMDIR 7
#define RTMDIR 4
#define LTMPWM 6
#define RTMPWM 5
#define LTMINT 2
#define RTMINT 3
MPU6050 mpu;
int rn = 0, ln = 0;
float r1 = 0, l1 = 0;
float rv = 0, lv = 0;
uint16_t packetSize;
uint16_t fifoCount;
uint8_t fifoBuffer[64];
bool rDir = 0;
bool lDir = 0;
int turn = 0;
int lout = 0;
int rout = 0;
volatile uint8_t rc = 0;
volatile uint8_t lc = 0;
volatile bool mpuInterrupt = false;
Quaternion q;
VectorFloat gravity;
float ypr[3];
int m = 25;
float setPoint;
uint32_t t = 0;
uint16_t DT =0;
float angle;
float initAOffset = 4.7;
float oldRSP, RSP;
float PID_errorSum;
float PID_errorOld = 0;
float PID_errorOld2 = 0;
float setPointOld = 0;
float target_angle;
float throttle;
float steering;
float Kp=0;
float Kd=0;
float Kp_thr=0;
float Ki_thr=0;
float speedFilter = 0;
uint32_t intT = 0, dt;
float out = 0;
void setup() {
Wire.begin();
Serial.begin(57600);
delay(10);
mpuInit();
delay(15000);
mpu.resetFIFO();
initAOffset = 3.7;
while(digitalRead(12)==0);
mpu.resetFIFO();
intInit();
while(!mpuInterrupt);
getYPR();
t=millis();
pinMode(LTMINT, INPUT);
pinMode(RTMINT, INPUT);
pinMode(LTMDIR, OUTPUT);
pinMode(RTMDIR, OUTPUT);
pinMode(LTMPWM, OUTPUT);
pinMode(RTMPWM, OUTPUT);
analogWrite(RTMPWM,1);
analogWrite(LTMPWM,1);
intT = dt = millis();
}
void loop() {
if(mpuInterrupt)
{
getYPR();
DT = millis() - t;
Serial.println(millis() - intT);
if((millis()-intT) > 12){intT = millis();goto x;}
intT = millis();
angle = initAOffset - ypr[1];
if((dt=millis()-dt)>50)
{
odor();
target_angle = constrain(speedPIControl(speedFilter,throttle,Kp_thr,Ki_thr),-20.0,20.0);
dt = millis();
}
out = stabilityPDControl(angle,target_angle,Kp,Kd);
out = constrain(out,-255,255);
lout = out + steering;
rout = out - steering;
rDir = ( (rout > 0) ? 1 : 0);
lDir = ( (lout > 0) ? 1 : 0);
if(lout!=0)
lout = abs( constrain(lout, -255, 255) ) + m;
if(rout!=0)
rout = abs( constrain(rout, -255, 255) ) + m;
if(abs(angle)>70)motorControl(0,0);
else
motorControl( rout, lout);
t=millis();
Serial.print(angle);Serial.print('\t');
Serial.print(target_angle);Serial.print('\t');
Serial.println(out);
}x:;
if(Serial.available()>2){
switch (Serial.read())
{
case 'p':Kp = Serial.parseFloat();break;
case 'i':Ki_thr = Serial.parseFloat();break;
case 'd':Kd = Serial.parseFloat();break;
case 'a':Kp_thr = Serial.parseFloat();break;
//case 'b':kcgi = Serial.parseFloat();break;
//case 'c':kcgd = Serial.parseFloat();break;
case 's':initAOffset = Serial.parseFloat();break;
//case 'e':alpha = Serial.parseFloat();t = millis();break;
//case 't':angs = Serial.parseFloat();z = (pow(kangp,angs/57.2958)-1);break;
//case 'a':an=Serial.parseFloat();break;
case 'm':m = Serial.parseFloat();break;
}
Serial.read();
}
}
float speedPIControl(float input, float setPoint, float Kp, float Ki)
{
float error;
float output;
error = setPoint-input;
PID_errorSum += constrain(error,-40,40);
PID_errorSum = constrain(PID_errorSum,-4000,4000);
output = Kp*error + Ki*PID_errorSum*dt*0.001;
return(output);
}
float stabilityPDControl(float input, float setPoint, float Kp, float Kd)
{
float error;
float output;
error = setPoint - input;
//output = Kp*error + (Kd*(setPoint - setPointOld) - Kd*(input - PID_errorOld2))/DT;
output = 400.0 * (1.0 / (1+exp(-error * Kp))-0.5) + (-Kd*(setPoint - setPointOld) + Kd*(input - PID_errorOld))/DT;
PID_errorOld2 = PID_errorOld;
PID_errorOld = input;
setPointOld = setPoint;
return output;
}
void odor(){
if(!lDir)
{
lv = -1 * lc;
lc = 0;
}
else
{
lv = lc;
lc = 0;
}
if(!rDir)
{
rv = -1 * rc;
rc = 0;
}
else
{
rv = rc;
rc=0;
}
r1 += rv;
l1 += lv;
rv = rv / dt;
lv = lv / dt;
if(abs(r1) > 29)
{
if(r1 > 29)
{
rn++;
r1 -= 30;
}
else
{
rn--;
r1 += 30;
}
}
if(abs(l1) > 29)
{
if(l1 > 29)
{
ln++;
l1 -= 30;
}
else
{
ln--;
l1 += 30;
}
}
RSP = ( rv + lv ) / 2.0;
speedFilter = RSP;
}
void LME(){
lc++;
}
void RME(){
rc++;
}
void mpuInit(){
mpu.initialize();
mpu.testConnection();
mpu.dmpInitialize();
mpu.setXGyroOffset(-1);
mpu.setYGyroOffset(-1);
mpu.setZGyroOffset(255);
mpu.setXAccelOffset(705);
mpu.setYAccelOffset(-139);
mpu.setZAccelOffset(1219);
mpu.setDMPEnabled(true);
packetSize = mpu.dmpGetFIFOPacketSize();
}
void getYPR(){
mpuInterrupt = false;
fifoCount = mpu.getFIFOCount();
while (fifoCount < packetSize) {fifoCount = mpu.getFIFOCount();}
mpu.getFIFOBytes(fifoBuffer, packetSize);
fifoCount -= packetSize;
mpu.dmpGetQuaternion(&q, fifoBuffer);
mpu.dmpGetGravity(&gravity, &q);
mpu.dmpGetYawPitchRoll(ypr, &q, &gravity);
ypr[1] *= 180 / PI;
mpu.resetFIFO();
}
void motorControl(int a, int b)
{
if(lDir)
PORTD |= _BV(RTMDIR);
else
PORTD &= ~_BV(RTMDIR);
if(rDir)
PORTD |= _BV(LTMDIR);
else
PORTD &= ~_BV(LTMDIR);
OCR0B = ( ( abs( a ) <= 200 ) ? a : 0 );
OCR0A = ( ( abs( b ) <= 200 ) ? b : 0 ) * 1.2 + 10;
}
ISR(TIMER1_OVF_vect) {
mpuInterrupt = 1;
TCNT1=64886;
}
void intInit(){
mpu.resetFIFO();
TCCR1A=0;
TCCR1B=0;
TCNT1=64886;
TCCR1B |= (1 << CS12);
TIMSK1 |= (1 << TOIE1);
attachInterrupt(digitalPinToInterrupt(RTMINT),RME,RISING);
attachInterrupt(digitalPinToInterrupt(LTMINT),LME,RISING);
}

View File

@ -0,0 +1,108 @@
/* Copyright (C) 2012 Kristian Lauszus, TKJ Electronics. All rights reserved.
This software may be distributed and modified under the terms of the GNU
General Public License version 2 (GPL2) as published by the Free Software
Foundation and appearing in the file GPL2.TXT included in the packaging of
this file. Please note that GPL2 Section 2[b] requires that all works based
on this software must also be made publicly available under the terms of
the GPL2 ("Copyleft").
Contact information
-------------------
Kristian Lauszus, TKJ Electronics
Web : http://www.tkjelectronics.com
e-mail : kristianl@tkjelectronics.com
*/
#ifndef _Kalman_h
#define _Kalman_h
class Kalman {
public:
Kalman() {
/* We will set the variables like so, these can also be tuned by the user */
Q_angle = 0.001;
Q_bias = 0.003;
R_measure = 0.03;
angle = 0; // Reset the angle
bias = 0; // Reset bias
P[0][0] = 0; // Since we assume that the bias is 0 and we know the starting angle (use setAngle), the error covariance matrix is set like so - see: http://en.wikipedia.org/wiki/Kalman_filter#Example_application.2C_technical
P[0][1] = 0;
P[1][0] = 0;
P[1][1] = 0;
};
// The angle should be in degrees and the rate should be in degrees per second and the delta time in seconds
double getAngle(double newAngle, double newRate, double dt) {
// KasBot V2 - Kalman filter module - http://www.x-firm.com/?page_id=145
// Modified by Kristian Lauszus
// See my blog post for more information: http://blog.tkjelectronics.dk/2012/09/a-practical-approach-to-kalman-filter-and-how-to-implement-it
// Discrete Kalman filter time update equations - Time Update ("Predict")
// Update xhat - Project the state ahead
/* Step 1 */
rate = newRate - bias;
angle += dt * rate;
// Update estimation error covariance - Project the error covariance ahead
/* Step 2 */
P[0][0] += dt * (dt*P[1][1] - P[0][1] - P[1][0] + Q_angle);
P[0][1] -= dt * P[1][1];
P[1][0] -= dt * P[1][1];
P[1][1] += Q_bias * dt;
// Discrete Kalman filter measurement update equations - Measurement Update ("Correct")
// Calculate Kalman gain - Compute the Kalman gain
/* Step 4 */
S = P[0][0] + R_measure;
/* Step 5 */
K[0] = P[0][0] / S;
K[1] = P[1][0] / S;
// Calculate angle and bias - Update estimate with measurement zk (newAngle)
/* Step 3 */
y = newAngle - angle;
/* Step 6 */
angle += K[0] * y;
bias += K[1] * y;
// Calculate estimation error covariance - Update the error covariance
/* Step 7 */
P[0][0] -= K[0] * P[0][0];
P[0][1] -= K[0] * P[0][1];
P[1][0] -= K[1] * P[0][0];
P[1][1] -= K[1] * P[0][1];
return angle;
};
void setAngle(double newAngle) { angle = newAngle; }; // Used to set angle, this should be set as the starting angle
double getRate() { return rate; }; // Return the unbiased rate
/* These are used to tune the Kalman filter */
void setQangle(double newQ_angle) { Q_angle = newQ_angle; };
void setQbias(double newQ_bias) { Q_bias = newQ_bias; };
void setRmeasure(double newR_measure) { R_measure = newR_measure; };
double getQangle() { return Q_angle; };
double getQbias() { return Q_bias; };
double getRmeasure() { return R_measure; };
private:
/* Kalman filter variables */
double Q_angle; // Process noise variance for the accelerometer
double Q_bias; // Process noise variance for the gyro bias
double R_measure; // Measurement noise variance - this is actually the variance of the measurement noise
double angle; // The angle calculated by the Kalman filter - part of the 2x1 state vector
double bias; // The gyro bias calculated by the Kalman filter - part of the 2x1 state vector
double rate; // Unbiased rate calculated from the rate and the calculated bias - you have to call getAngle to update the rate
double P[2][2]; // Error covariance matrix - This is a 2x2 matrix
double K[2]; // Kalman gain - This is a 2x1 vector
double y; // Angle difference
double S; // Estimate error
};
#endif

View File

@ -0,0 +1,365 @@
#include "I2Cdev.h"
#include "MPU6050_6Axis_MotionApps20.h"
#include "Wire.h"
#include "Kalman.h"
MPU6050 mpu;
#define HMC5883L 0x1E
#define LTM_DIR 3
#define RTM_DIR 4
#define LTM_PWM 6
#define RTM_PWM 5
#define LF 1
#define RF 0
#define MPU_INT 2
#define rW 0.127
#define g 9.8
#define Ip 0.021
#define Iw 0.00242
bool blinkState = false;
bool dmpReady = false; // set true if DMP init was successful
uint8_t mpuIntStatus; // holds actual interrupt status byte from MPU
uint8_t devStatus; // return status after each device operation (0 = success, !0 = error)
uint16_t packetSize; // expected DMP packet size (default is 42 bytes)
uint16_t fifoCount; // count of all bytes currently in FIFO
uint8_t fifoBuffer[64]; // FIFO storage buffer
float yaw[2];
float pitch[2];
Kalman filter;
uint32_t timer;
double RV, LV;
uint16_t rPWM;
uint16_t lPWM;
double RD, LD;
float yawOffset = 0.0;
float pitchOffset = 0;
uint8_t mode = 1;/*
0 - Calculate Offset.
1 - Maintain Balance and Position
2 - Turn by x degrees
3 - Move x distance
4 - Turn while moving
default - Maintain and Rotate
*/
volatile bool mpuInterrupt = false; // indicates whether MPU interrupt pin has gone high
void dmpDataReady() {
mpuInterrupt = true;
}
void setup() {
Serial3.begin(57600);
delay(100);
Wire.begin();
Wire.setClock(400000); // 400kHz I2C clock. Comment this line if having compilation difficulties
mpu.initialize();
pinMode(MPU_INT, INPUT);
pinMode(LTM_DIR, OUTPUT);
pinMode(RTM_DIR, OUTPUT);
pinMode(LTM_PWM, OUTPUT);
pinMode(RTM_PWM, OUTPUT);
mpu.testConnection();
devStatus = mpu.dmpInitialize();
/*mpu.setXGyroOffset(-1);
mpu.setYGyroOffset(-1);
mpu.setZGyroOffset(255);
mpu.setXAccelOffset(705);
mpu.setYAccelOffset(-139);
mpu.setZAccelOffset(1219);
*/
mpu.setXGyroOffset(220);
mpu.setYGyroOffset(76);
mpu.setZGyroOffset(-85);
mpu.setZAccelOffset(1788);
mpu.setDMPEnabled(true);
attachInterrupt(digitalPinToInterrupt(MPU_INT), dmpDataReady, RISING);
mpuIntStatus = mpu.getIntStatus();
dmpReady = true;
packetSize = mpu.dmpGetFIFOPacketSize();
mpu.setI2CBypassEnabled(true);
I2Cdev::writeByte(HMC5883L, 0x00,(0x03 << 5) |(0x04 << 2) |0x00 );
I2Cdev::writeByte(HMC5883L, 0x01, 0x01 << 5);
I2Cdev::writeByte(HMC5883L, 0x02, 0x01);
setMode(1);delay(5000);
while (pitch[0] != 0)readSensors();
//delay(15000);
TCCR4A = 0;
TCCR4B = 0;
TCCR4A |= (1 << COM4A0);
TCCR4B = 0;
TCCR4B |= (1 << WGM42);
TCCR3A = 0;
TCCR3B = 0;
TCCR3A |= (1 << COM3A0);
TCCR3B = 0;
TCCR3B |= (1 << WGM32);
}
void calculateOffset()
{
}
float pKpss = 0.5, pKdss = 4.5, pKiss = 0, yKpss = 1.0, yKdss = 0, dKpss, dKdss, yawcerr, yKiss = 0, preV, V, cPErr, vKiss = 5, vOffset = 0;
void stayStill() {
float yawErr = yawOffset - yaw[0];
float pitchErr = pitchOffset - pitch[0];
cPErr += pitchErr;
cPErr = constrain(cPErr, 500,500);
RD += 0.001 * RV;
LV = RV = ( pKpss * pitchErr + pKdss * pitch[1] + pKiss * cPErr);
Serial3.print('a');
Serial.print('\t');
Serial3.print(pitch[0]);
Serial3.print(',');
Serial3.print(pitch[1]);
Serial3.print(',');
Serial3.print(LV);
Serial3.print(',');
Serial3.print(pitchOffset);
Serial3.print(',');
Serial3.print(RD);
Serial3.println(',');
//LV = RV = pKpss * pitchErr + pKdss * pitch[1] + pKiss * cPErr;
/*if(pitchErr > 0)
LV = RV = yKpss * pow(pKpss, abs(pitchErr)) + pKdss * pitch[1] + pKiss * cPErr;
else
LV = RV = -yKpss * pow(pKpss, abs(pitchErr)) + pKdss * pitch[1] + pKiss * cPErr;
*/
//LV -= yawErr*0.1;
//RV += yawErr*0.1;
if (pitchErr > 50)
{
LV = RV = 0;
}
//Serial.print(pitch[0]);
//Serial.print('\t');
/*
Serial3.print(pitchOffset);
Serial3.print('\t');
Serial3.print(yaw[0]);
Serial3.print('\t');
Serial3.println(pitch[1]);
*//*
Serial.print('\t');
Serial.println(lPWM);
*/
//yawcerr = constrain(yawcerr + yawErr * yKiss, -7, 7);
//int temp = constrain(yawErr * yKpss + yaw[1] * yKdss + yawcerr, -10, 10);
//lPWM += temp;
//rPWM -= temp;
//lPWM = ((abs(pitchErr)>2) ? 0 : lPWM);
//rPWM = ((abs(pitchErr)>2) ? 0 : rPWM);
}
void turnByX(float x) {}
void moveByD(int D) {}
void moveByAndTurn(int d, float x) {}
void maintainAndRotate() {}
/*
0 - Calculate Offset.
1 - Maintain Balance and Position
2 - Turn by x degrees
3 - Move x distance
4 - Turn while moving
default - Maintain and Rotate
*/
void setMode(int m) {
mode = m;
switch (mode)
{
case 0:
yawOffset = yaw[0];
break;
case 1:
yawOffset = yaw[0];
yawcerr = 0;
break;
case 2: yawOffset = yaw[0];
break;
case 3: yawOffset = yaw[0];
break;
case 4: yawOffset = yaw[0];
break;
default:
break;
}
}
void loop() {
if (!dmpReady) return;
while (!mpuInterrupt && fifoCount < packetSize) {
}
mpuInterrupt = false;
mpuIntStatus = mpu.getIntStatus();
fifoCount = mpu.getFIFOCount();
if ((mpuIntStatus & 0x10) || fifoCount == 1024)
I2Cdev::writeBit(0x68, 0x6A, 2, 1);//reset FIFO
else
if (mpuIntStatus & 0x02) {
while (fifoCount < packetSize)
fifoCount = mpu.getFIFOCount();
I2Cdev::readBytes(0x68, 0x74, packetSize, fifoBuffer);//read FIFO
fifoCount -= packetSize;
readSensors();
if (Serial3.available()>2) {
switch (Serial3.read())
{
case 'p':pKpss = Serial3.parseFloat();break;
case 'i':pKdss = Serial3.parseFloat();break;
case 'd':yKpss = Serial3.parseFloat();break;
case 'a':yKdss = Serial3.parseFloat();break;
case 'b':dKdss = Serial3.parseFloat();break;
case 'c':dKpss = Serial3.parseFloat();break;
case 's':pitchOffset = Serial3.parseFloat();break;
case 'e':pKiss = Serial3.parseFloat();break;
case 't':cPErr = Serial3.parseFloat();break;
case 'f':yawOffset = Serial3.parseFloat();break;
}
Serial3.read();
}
switch (mode) {
case 0:
calculateOffset();
break;
case 1:
stayStill();
break;
case 2:
break;
case 3:
break;
case 4:
break;
default:
maintainAndRotate();
}
motorControl();
}
}
int16_t mx, my, mz;uint8_t buffer[6];
void readSensors() {
I2Cdev::readBytes(HMC5883L, 0x03, 6, buffer);
I2Cdev::writeByte(HMC5883L, 0x02, 0x01);
mx = (((int16_t)buffer[0]) << 8) | buffer[1];
my = (((int16_t)buffer[4]) << 8) | buffer[5];
mz = (((int16_t)buffer[2]) << 8) | buffer[3];
float w = ((fifoBuffer[0] << 8) | fifoBuffer[1]) / 16384.0;
float x = ((fifoBuffer[4] << 8) | fifoBuffer[5]) / 16384.0;
float y = ((fifoBuffer[8] << 8) | fifoBuffer[9]) / 16384.0;
float z = ((fifoBuffer[12] << 8) | fifoBuffer[13]) / 16384.0;
float ty = 2 * (w * x + y * z);
float tz = w * w - x * x - y * y + z * z;
//mz = -(((int16_t)buffer[5]) << 8) | buffer[4];
float tempYaw;
double dt = (micros() - timer) / 1000000.0;
timer = micros();
double Bfy = - my;
tempYaw *= -1;
pitch[0] = atan((2 * (x * z - w * y)) / sqrt(ty * ty + tz * tz));
yaw[1] = ((fifoBuffer[24] << 8) | fifoBuffer[25]) / 131.0;
pitch[1] = ((fifoBuffer[20] << 8) | fifoBuffer[21]) / 131.0;
double Bfx = mx + mz * sin(pitch[0]);
tempYaw = atan2(-Bfy, Bfx) * RAD_TO_DEG;
pitch[0] *= RAD_TO_DEG;
//Serial3.println(tempYaw);
if ((tempYaw < -90 && yaw[0] > 90) || (tempYaw > 90 && yaw[0] < -90)) {
filter.setAngle(tempYaw);
yaw[0] = tempYaw;
}
else
yaw[0] = filter.getAngle(tempYaw, yaw[1], dt);
//yaw[0] = tempYaw;
/*pKpss = analogRead(A0) / 100.0 + 10;
pKdss = analogRead(A1) / 100.0;
dKpss = analogRead(A2) / 100.0;
dKdss = analogRead(A3) / 100.0;
*/
/*Serial.print(vL);
Serial.print('\t');
Serial.println(vR);*/
}
uint16_t lFrq, rFrq;
double t;
int preScaler[5] = { 1,8,64,256,1024 };
int cPreScale(int freq)
{
int x = 0; double err = 10000;int ocr;int tFreq = 0;
for (int i = 0;i<5;i++)
{
ocr = round(F_CPU / (2.0 * preScaler[i] * freq)) - 1;
if (ocr>65535) { continue; }
tFreq = F_CPU / (2.0 * preScaler[i] * (ocr + 1));
if (err>abs(tFreq - freq))
{
err = abs(tFreq - freq);
x = i;
}
}
return x;
}
uint8_t pS[] = {B00000001,B00000010,B00000011,B00000100,B00000101};
void motorControl() {
if (RV > 0)
PORTG &= ~_BV(5);
else
PORTG |= _BV(5);
if (LV > 0)
PORTE |= _BV(5);
else
PORTE &= ~_BV(5);
//Serial.println(RV);
RV = constrain(abs(RV) * 900 / PI, 0, 8000);
LV = constrain(abs(LV) * 900 / PI, 0, 8000);
int t;
TCCR4B = (TCCR4B & 0b11111000) | pS[t = cPreScale(LV)];
TCNT4 = 0;
OCR4A = F_CPU / LV / 2 /preScaler[t] - 1;
TCCR3B = (TCCR3B & 0b11111000) | pS[t = cPreScale(RV)];
TCNT3 = 0;
OCR3A = F_CPU / RV / 2 / preScaler[t] - 1;
//Serial.println(OCR3A);
/*
PORTG &= ((3 << 6) | (rDir << 5) | (15));
PORTE &= ((3 << 6) | (lDir << 5) | (15));
*/
}

View File

@ -0,0 +1,230 @@
#include "I2Cdev.h"
#include "MPU6050_6Axis_MotionApps20.h"
//#include "MPU6050.h" // not necessary if using MotionApps include file
// Arduino Wire library is required if I2Cdev I2CDEV_ARDUINO_WIRE implementation
// is used in I2Cdev.h
#if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
#include "Wire.h"
#endif
// class default I2C address is 0x68
// specific I2C addresses may be passed as a parameter here
// AD0 low = 0x68 (default for SparkFun breakout and InvenSense evaluation board)
// AD0 high = 0x69
MPU6050 mpu;
bool blinkState = false;
double ra=0;
// MPU control/status vars
bool dmpReady = false; // set true if DMP init was successful
uint8_t mpuIntStatus; // holds actual interrupt status byte from MPU
uint8_t devStatus; // return status after each device operation (0 = success, !0 = error)
uint16_t packetSize; // expected DMP packet size (default is 42 bytes)
uint16_t fifoCount; // count of all bytes currently in FIFO
uint8_t fifoBuffer[64]; // FIFO storage buffer
uint16_t T=0;
uint16_t pT=0;
uint16_t dT=0;
float ITerm =0;
float DTerm =0;
float kp = 11;
float ki = 0.04;
float kd = 7.0;
// orientation/motion vars
Quaternion q; // [w, x, y, z] quaternion container
int16_t gg[3];
VectorFloat gravity; // [x, y, z] gravity vector
float Setpoint = 0;
float raSet=-10.0;
float setT=7.5;
float t=255.0/(pow(kp,setT/57.2958)-1);
int flag=0;
float disp=0;
float r=0;
volatile bool mpuInterrupt = false; // indicates whether MPU interrupt pin has gone high
void dmpDataReady() {
mpuInterrupt = true;
}
// ================================================================
// === INITIAL SETUP ===
// ================================================================
void setup() {
// join I2C bus (I2Cdev library doesn't do this automatically)
Wire.begin();
pinMode(10, OUTPUT);
pinMode(4, OUTPUT);
pinMode(5, OUTPUT);
pinMode(6, OUTPUT);
pinMode(7, OUTPUT);
pinMode(9, OUTPUT);
digitalWrite(7,0);
digitalWrite(4,0);
digitalWrite(5,HIGH);
digitalWrite(6,HIGH);
analogWrite(10,1);
analogWrite(9,1);
// initialize serial communication
// (115200 chosen because it is required for Teapot Demo output, but it's
// really up to you depending on your project)
Serial.begin(115200);
//delay(5000);
//while (!Serial); // wait for Leonardo enumeration, others continue immediately
// NOTE: 8MHz or slower host processors, like the Teensy @ 3.3v or Ardunio
// Pro Mini running at 3.3v, cannot handle this baud rate reliably due to
// the baud timing being too misaligned with processor ticks. You must use
// 38400 or slower in these cases, or use some kind of external separate
// crystal solution for the UART timer.
// initialize device
//Serial.println(F("Initializing I2C devices..."));
mpu.initialize();
// verify connection
//Serial.println(F("Testing device connections..."));
//Serial.println(mpu.testConnection() ? F("MPU6050 connection successful") : F("MPU6050 connection failed"));
mpu.testConnection();
// wait for ready
//Serial.println(F("\nSend any character to begin DMP programming and demo: "));
//while (Serial.available() && Serial.read()); // empty buffer
//while (!Serial.available()); // wait for data
//while (Serial.available() && Serial.read()); // empty buffer again
// load and configure the DMP
//Serial.println(F("Initializing DMP..."));
devStatus = mpu.dmpInitialize();
// supply your own gyro offsets here, scaled for min sensitivity
mpu.setXGyroOffset(-965);
mpu.setYGyroOffset(-102);
mpu.setZGyroOffset(35);
mpu.setZAccelOffset(1220); // 1688 factory default for my test chip
mpu.setXAccelOffset(-5082);
mpu.setYAccelOffset(-739);
// make sure it worked (returns 0 if so)
if (devStatus == 0) {
// turn on the DMP, now that it's ready
//Serial.println(F("Enabling DMP..."));
mpu.setDMPEnabled(true);
// enable Arduino interrupt detection
//Serial.println(F("Enabling interrupt detection (Arduino external interrupt 0)..."));
attachInterrupt(0, dmpDataReady, RISING);
mpuIntStatus = mpu.getIntStatus();
// set our DMP Ready flag so the main loop() function knows it's okay to use it
//Serial.println(F("DMP ready! Waiting for first interrupt..."));
dmpReady = true;
// get expected DMP packet size for later comparison
packetSize = mpu.dmpGetFIFOPacketSize();
} else {Serial.println("Start");
// ERROR!
// 1 = initial memory load failed
// 2 = DMP configuration updates failed
// (if it's going to break, usually the code will be 1)
//Serial.print(F("DMP Initialization failed (code "));
//Serial.print(devStatus);
//Serial.println(F(")"));
}
//OCR1A=OCR1B=255;
}
float error=0,output=0;
// ================================================================
// === MAIN PROGRAM LOOP ===
// ================================================================
void loop() {
// if programming failed, don't try to do anything
if (!dmpReady) return;
// wait for MPU interrupt or extra packet(s) available
while (!mpuInterrupt && fifoCount < packetSize) {
// other program behavior stuff here
// .
// .
// .
// if you are really paranoid you can frequently test in between other
// stuff to see if mpuInterrupt is true, and if so, "break;" from the
// while() loop to immediately process the MPU data
// .
// .
// .
}
// reset interrupt flag and get INT_STATUS byte
mpuInterrupt = false;
mpuIntStatus = mpu.getIntStatus();
// get current FIFO count
fifoCount = mpu.getFIFOCount();
// check for overflow (this should never happen unless our code is too inefficient)
if ((mpuIntStatus & 0x10) || fifoCount == 1024) {
// reset so we can continue cleanly
mpu.resetFIFO();
//Serial.println(F("FIFO overflow!"));
// otherwise, check for DMP data ready interrupt (this should happen frequently)
} else if (mpuIntStatus & 0x02) {
while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount();
mpu.getFIFOBytes(fifoBuffer, packetSize);
fifoCount -= packetSize;
mpu.dmpGetQuaternion(&q, fifoBuffer);
mpu.dmpGetGravity(&gravity, &q);
mpu.dmpGetGyro(gg,fifoBuffer);
if(Serial.available()>2)
{
//delay(3);
switch(Serial.read()){
case 's': raSet=Serial.parseFloat();break;
case 'p': kp=Serial.parseFloat();t=255.0/(pow(kp,setT/57.2958)-1);break;
case 'i': ki=Serial.parseFloat();break;
case 'd': kd=Serial.parseFloat();break;
case 'r': r=Serial.parseFloat();break;
case 'a': setT=Serial.parseFloat();t=255.0/(pow(kp,setT/57.2958)-1);break;
}
Serial.read();
}
//Serial.print("a ");
ra=atan2(gravity.z,gravity.x)*57.2958-raSet;
Serial.println(ra+raSet);
//Serial.print("\t");
if(ra<0)flag = -1;
else flag = 1;
//Serial.print("a ");
//Serial.print(ra,9);
ra = flag*ra;
//Serial.println();
output = (pow(kp,constrain(ra,0,setT)/57.2958)-1)*flag*t;
error = output - raSet;
DTerm = error-DTerm;
ITerm+= (ki * error);
if(ITerm > 255) ITerm= 255;
else if(ITerm < -255) ITerm= -255;
//if((ra<raSet)&&(ra>-raSet))ITerm=0;
//if((ITerm/abs(ITerm))!=(output/abs(output)))ITerm=error;
DTerm *=kd;
output=output+ITerm+DTerm;
DTerm = error;
/*if((ra>20.0)&&(ra<45))output=255*flag;
if(ra>=45)output=0;*/
if(output >=255) output= 255;
else if(output <=-255) output= -255;
//Serial.println(output);
if (output > 0) PORTD=B01100000;
else PORTD=B10010000;
if(abs(output)<7)
OCR1A=OCR1B=map(abs(output),0,255,7,255);
else
OCR1A=OCR1B=abs(output);
}
}

View File

@ -0,0 +1,251 @@
#include "I2Cdev.h"
#include "MPU6050_6Axis_MotionApps20.h"
#include "Wire.h"
#define RAD2GRAD 57.2957795
#define RAD2M 0.20734511513
#define LTMDIR 7
#define RTMDIR 4
#define LTMPWM 6
#define RTMPWM 5
#define LTMINT 2
#define RTMINT 3
MPU6050 mpu;
float displ = 0;
int rn = 0, ln = 0;
float r1 = 0, l1 = 0;
float rv = 0, lv = 0;
uint16_t packetSize;
uint16_t fifoCount;
uint8_t fifoBuffer[64];
bool rDir = 0;
bool lDir = 0;
int turn = 0;
int lout = 0;
int rout = 0;
int mov = 0;
int16_t gyro[3];
float gy;
volatile uint8_t rc = 0;
volatile uint8_t lc = 0;
volatile bool mpuInterrupt = false;
Quaternion q;
VectorFloat gravity;
float ypr[3];
int m = 25;
float setPoint;
uint32_t t = 0;
uint16_t DT =0;
float angle;
float initAOffset = 4.7;
float RSP;
float steering;
float speedFilter = 0;
uint32_t intT = 0, dt;
float out = 0;
void setup() {
Wire.begin();
Serial.begin(57600);
delay(10);
mpuInit();
//delay(15000);
mpu.resetFIFO();
initAOffset = 4.7;
//while(digitalRead(12)==0);
mpu.resetFIFO();
intInit();
while(!mpuInterrupt);
getYPR();
t=millis();
pinMode(LTMINT, INPUT);
pinMode(RTMINT, INPUT);
pinMode(LTMDIR, OUTPUT);
pinMode(RTMDIR, OUTPUT);
pinMode(LTMPWM, OUTPUT);
pinMode(RTMPWM, OUTPUT);
analogWrite(RTMPWM,1);
analogWrite(LTMPWM,1);
intT = millis();
}
void odor(){
if(!lDir)
{
lv = -1 * lc;
lc = 0;
}
else
{
lv = lc;
lc = 0;
}
if(!rDir)
{
rv = -1 * rc;
rc = 0;
}
else
{
rv = rc;
rc=0;
}
r1 += rv;
l1 += lv;
if(abs(r1) > 29)
{
if(r1 > 29)
{
rn++;
r1 -= 30;
}
else
{
rn--;
r1 += 30;
}
}
if(abs(l1) > 29)
{
if(l1 > 29)
{
ln++;
l1 -= 30;
}
else
{
ln--;
l1 += 30;
}
}
RSP = ( rv + lv ) * 3.45575191 / DT; // RAD2M / 60.0
speedFilter = speedFilter*0.9 + RSP*0.1;
displ = ( rn + ln + ( r1 + l1 ) / 30.0 ) * 0.10367255756; //RAD2M / 2.0
}
void LME(){
lc++;
}
void RME(){
rc++;
}
void mpuInit(){
mpu.initialize();
mpu.testConnection();
mpu.dmpInitialize();
mpu.setXGyroOffset(-1);
mpu.setYGyroOffset(-1);
mpu.setZGyroOffset(255);
mpu.setXAccelOffset(705);
mpu.setYAccelOffset(-139);
mpu.setZAccelOffset(1219);
mpu.setDMPEnabled(true);
packetSize = mpu.dmpGetFIFOPacketSize();
}
void getYPR(){
mpuInterrupt = false;
fifoCount = mpu.getFIFOCount();
while (fifoCount < packetSize) {fifoCount = mpu.getFIFOCount();}
mpu.getFIFOBytes(fifoBuffer, packetSize);
fifoCount -= packetSize;
mpu.dmpGetQuaternion(&q, fifoBuffer);
mpu.dmpGetGravity(&gravity, &q);
mpu.dmpGetYawPitchRoll(ypr, &q, &gravity);
ypr[1] *= 180 / PI;
mpu.dmpGetGyro(gyro, fifoBuffer);
gy = gyro[1]/100.0;
mpu.resetFIFO();
}
void motorControl(int a, int b)
{
if(lDir)
PORTD |= _BV(RTMDIR);
else
PORTD &= ~_BV(RTMDIR);
if(rDir)
PORTD |= _BV(LTMDIR);
else
PORTD &= ~_BV(LTMDIR);
OCR0B = ( ( abs( a ) <= 200 ) ? a : 0 );
OCR0A = ( ( abs( b ) <= 200 ) ? b : 0 ) * 1.2 + 10;
}
ISR(TIMER1_OVF_vect) {
mpuInterrupt = 1;
TCNT1=64886;
}
void intInit(){
mpu.resetFIFO();
TCCR1A=0;
TCCR1B=0;
TCNT1=64886;
TCCR1B |= (1 << CS12);
TIMSK1 |= (1 << TOIE1);
attachInterrupt(digitalPinToInterrupt(RTMINT),RME,RISING);
attachInterrupt(digitalPinToInterrupt(LTMINT),LME,RISING);
}
//float K1=0.1,K2=0.18,K3=6.5,K4=1.12;
//float K1=0.0577,K2=0.0725,K3=5.4045,K4=0.6276;
//float K1=31.6228,K2=41.4006,K3=942.3895,K4=84.9139;
float K1=1000,K2=731,K3=30606,K4=3146;
int getPWM(float a,float b,float c,float d){
return constrain((a*K1+b*K2+c*K3+d*K4)/20.0,-200,200);
}
/*
float K1=63.5894,K2=37.6050,K3=119.6250,K4=24.0648;
int getPWM(float a,float b,float c,float d){
return -constrain((a*K1+b*K2+c*K3+d*K4)*0.1,-200,200);
}
*/
void loop(){
if(mpuInterrupt)
{
getYPR();
DT = millis() - t;
if((millis()-intT) > 12){intT = millis();goto x;}
intT = millis();
angle = ypr[1] - initAOffset;
odor();
out = getPWM(displ,speedFilter+mov,angle/RAD2GRAD,gy/RAD2GRAD);
lout = out + steering;
rout = out - steering;
rDir = ( (rout > 0) ? 1 : 0);
lDir = ( (lout > 0) ? 1 : 0);
if(lout!=0)
lout = abs( constrain(lout, -200, 200) ) + m;
if(rout!=0)
rout = abs( constrain(rout, -200, 200) ) + m;
if(abs(angle)>70)motorControl(0,0);
else
motorControl( rout, lout);
t=millis();
Serial.print('a');
Serial.print(-displ);Serial.print(',');
Serial.print(-speedFilter);Serial.print(',');
Serial.print(angle);Serial.print(',');
Serial.print(gy);Serial.print(',');
Serial.print(out);Serial.println(',');
//Serial.println(out);
}x:;
if(Serial.available()>2){
switch (Serial.read())
{
case 'p':K1 = Serial.parseFloat();break;
case 'i':K2 = Serial.parseFloat();break;
case 'd':K3 = Serial.parseFloat();break;
case 'a':K4 = Serial.parseFloat();break;
/*case 'b':kcgi = Serial.parseFloat();break;
case 'c':kcgd = Serial.parseFloat();break;*/
case 's':initAOffset = Serial.parseFloat();break;
case 'e':mov = Serial.parseInt();break;
//case 't':angs = Serial.parseFloat();break;
//case 'a':an=Serial.parseFloat();break;
case 'm':m = Serial.parseFloat();break;
}
Serial.read();
}
}

View File

@ -0,0 +1,262 @@
#include "I2Cdev.h"
#include "MPU6050_6Axis_MotionApps20.h"
#include "Wire.h"
#include <MadgwickAHRS.h>
MPU6050 mpu;
Madgwick filter;
#define RAD2DEG 57.2957795
#define MPUINT 20
#define LTMDIR 8
#define RTMDIR 11
#define LTMPWM 9
#define RTMPWM 10
#define LTMINT 6
#define RTMINT 7
bool dmpReady = false;
uint8_t mpuIntStatus;
uint8_t devStatus;
int16_t Mag[3];
float mag[3];
uint16_t packetSize;
uint16_t fifoCount;
uint8_t fifoBuffer[64];
Quaternion q;
VectorFloat gravity;
float acc[3];
float ypr[3];
volatile bool mpuInterrupt = false;
float displ = 0;
int rn = 0, ln = 0;
float r1 = 0, l1 = 0;
float rv = 0, lv = 0;
bool rDir = 0;
bool lDir = 0;
int turn = 0;
int lout = 0;
int rout = 0;
int mov = 0;
int16_t gyro[3];
float gy[3];
volatile uint8_t rc = 0;
volatile uint8_t lc = 0;
int m = 28;
float setPoint;
uint32_t t = 0;
uint16_t DT =0;
float angle;
float initAOffset = 4.7;
float RSP;
float steering;
float cg=0;
float speedFilter = 0;
uint32_t intT = 0, dt;
float out = 0;
void dmpDataReady() {
mpuInterrupt = true;
}
void mpuInit(){
mpu.initialize();
mpu.testConnection();
devStatus = mpu.dmpInitialize();
mpu.setXGyroOffset(-1);
mpu.setYGyroOffset(-1);
mpu.setZGyroOffset(255);
mpu.setXAccelOffset(705);
mpu.setYAccelOffset(-139);
mpu.setZAccelOffset(1219);
mpu.setDMPEnabled(true);
mpuIntStatus = mpu.getIntStatus();
dmpReady = true;
packetSize = mpu.dmpGetFIFOPacketSize();
}
void LME(){
lc++;
}
void RME(){
rc++;
}
//float K1=0.1,K2=0.18,K3=6.5,K4=1.12;
//float K1=0.0577,K2=0.0725,K3=5.4045,K4=0.6276;
//float K1=0,K2=0;
//float K1=31.6228,K2=41.4006, K3=942.3895,K4=84.9139;
//float K1=31.6,K2=84.6,K3=4184.1,K4=370.2;
//float K1=70.7,K2=131.5,K3=3837.7,K4=369.4;
//float K1=1000,K2=731,K3=30606,K4=3146;
float K1=0,K2=0.3,K3=664.3,K4=49.2;
//float Kp=11,Kd=7.0,Ki=0;float verr=0;
int getPWM(float a,float b,float c,float d){
/*if(c>=0)return (pow(Kp,abs(c))-1)*255.0/(pow(Kp,20/57.2958)-1) + (Kd) * 7.0;
c*=-1;
verr+=b;
return -(pow(Kp,abs(c))-1)*255.0/(pow(Kp,20/57.2958)-1) + (Kd) * 7.0;
*/
return constrain((a*K1+b*K2+c*K3+d*K4),-200,200);
}
void odor(){
if(!lDir)
{
lv = -1 * lc;
lc = 0;
}
else
{
lv = lc;
lc = 0;
}
if(!rDir)
{
rv = -1 * rc;
rc = 0;
}
else
{
rv = rc;
rc=0;
}
r1 += rv;
l1 += lv;
if(abs(r1) > 29)
{
if(r1 > 29)
{
rn++;
r1 -= 30;
}
else
{
rn--;
r1 += 30;
}
}
if(abs(l1) > 29)
{
if(l1 > 29)
{
ln++;
l1 -= 30;
}
else
{
ln--;
l1 += 30;
}
}
RSP = ( rv + lv ) * 3.45575191 / DT; // RAD2M / 60.0
speedFilter = speedFilter*0.9 + RSP*0.1;
displ = ( rn + ln + ( r1 + l1 ) / 30.0 ) * 0.10367255756; //RAD2M / 2.0
}
void motorControl(int a, int b)
{
digitalWriteFast(LTMDIR, !lDir);
digitalWriteFast(RTMDIR, !rDir);
analogWrite(RTMPWM, a * 1.2 + 10);
analogWrite(LTMPWM, b);
}
void setup() {
pinMode(13,OUTPUT);
digitalWrite(13,1);
Wire.begin();
Wire.setClock(400000); // 400kHz I2C clock. Comment this line if having compilation difficulties
Serial.begin(57600);
pinMode(LTMINT, INPUT);
pinMode(RTMINT, INPUT);
pinMode(LTMDIR, OUTPUT);
pinMode(RTMDIR, OUTPUT);
pinMode(LTMPWM, OUTPUT);
pinMode(RTMPWM, OUTPUT);
pinMode(MPUINT, INPUT);
digitalWrite(LTMINT,HIGH);
digitalWrite(RTMINT,HIGH);
digitalWrite(MPUINT,HIGH);
mpuInit();
filter.begin(100);
attachInterrupt(digitalPinToInterrupt(MPUINT), dmpDataReady, RISING);
attachInterrupt(digitalPinToInterrupt(RTMINT),RME,RISING);
attachInterrupt(digitalPinToInterrupt(LTMINT),LME,RISING);
initAOffset = 6.3;
t=millis();
}
void loop() {
t=millis();
Serial.print('a');
//Serial.print(-displ);Serial.print(',');
//Serial.print(-speedFilter);Serial.print(',');
Serial.print(angle);Serial.println(',');
for(int i=0;i<3;i++){
Serial.print("\tgyro: ");Serial.print(gyro[i]);Serial.print(',');
}
for(int i=0;i<3;i++){
Serial.print("\tMAG: ");Serial.print(Mag[i]);Serial.print(',');
}
Serial.print("\tgravity: ");
Serial.print(gravity.x);Serial.print(',');
Serial.print(gravity.y);Serial.print(',');
Serial.print(gravity.z);Serial.print(',');
//Serial.print(gy);Serial.print(',');
//Serial.print(out);Serial.print(',');
//Serial.println(DT);
while (!mpuInterrupt && fifoCount < packetSize) {
if(Serial.available()>2){
switch (Serial.read())
{
case 'p':K1 = Serial.parseFloat();break;
case 'i':K2 = Serial.parseFloat();break;
case 'd':K3 = Serial.parseFloat();break;
case 'a':K4 = Serial.parseFloat();break;
/*case 'b':kcgi = Serial.parseFloat();break;
case 'c':kcgd = Serial.parseFloat();break;*/
case 's':initAOffset = Serial.parseFloat();break;
case 'e':mov = Serial.parseInt();break;
//case 't':angs = Serial.parseFloat();break;
//case 'a':an=Serial.parseFloat();break;
case 'm':m = Serial.parseFloat();break;
}
Serial.read();
}
}
mpuInterrupt = false;
mpuIntStatus = mpu.getIntStatus();
fifoCount = mpu.getFIFOCount();
if ((mpuIntStatus & 0x10) || fifoCount == 1024)
mpu.resetFIFO();
else if (mpuIntStatus & 0x02)
{
while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount();
mpu.getFIFOBytes(fifoBuffer, packetSize);
fifoCount -= packetSize;
mpu.dmpGetQuaternion(&q, fifoBuffer);
mpu.dmpGetGravity(&gravity, &q);
mpu.dmpGetYawPitchRoll(ypr, &q, &gravity);
mpu.dmpGetGyro(gyro, fifoBuffer);
mpu.dmpGetMag(Mag, fifoBuffer);
mag[0] = Mag[1] * 1200.0 / 32768.0;
mag[1] = Mag[0] * 1200.0 / 32768.0;
mag[2] = -Mag[2] * 1200.0 / 32768.0;
acc[0] = gravity.x * 2.0 / 32768.0;
acc[1] = gravity.x * 2.0 / 32768.0;
acc[2] = gravity.x * 2.0 / 32768.0;
gy[0] = gyro[0] * 250.0 / 32768.0;
gy[1] = gyro[1] * 250.0 / 32768.0;
gy[2] = gyro[2] * 250.0 / 32768.0;
ypr[0] *= 180 / M_PI;
ypr[1] *= 180 / M_PI;
ypr[2] *= 180 / M_PI;
}
angle = ypr[1] - initAOffset;
DT = millis() - t;
odor();
out = getPWM(displ,speedFilter+mov,angle/RAD2DEG,gy[1]);
lout = out + steering;
rout = out - steering;
rDir = ( (rout > 0) ? 1 : 0);
lDir = ( (lout > 0) ? 1 : 0);
if(lout!=0)
lout = abs( constrain(lout, -200, 200) ) + m;
if(rout!=0)
rout = abs( constrain(rout, -200, 200) ) + m;
/*if(abs(angle)>70)motorControl(0,0);
else
motorControl( rout, lout);
*/}

View File

@ -0,0 +1,76 @@
void LEDToggle(void);
void SERVOCTRLSPEED(char Speed);
void SERVOSET(unsigned char LSB1, unsigned char MSB1, unsigned char LSB2, unsigned char MSB2, unsigned char LSB3, unsigned char MSB3, unsigned char LSB4, unsigned char MSB4, unsigned char LSB5, unsigned char MSB5, unsigned char LSB6, unsigned char MSB6, unsigned char LSB7, unsigned char MSB7, unsigned char LSB8, unsigned char MSB8, unsigned char LSB9, unsigned char MSB9, unsigned char LSB10, unsigned char MSB10, unsigned char LSB11, unsigned char MSB11, unsigned char LSB12, unsigned char MSB12, unsigned char LSB13, unsigned char MSB13, unsigned char LSB14, unsigned char MSB14, unsigned char LSB15, unsigned char MSB15, unsigned char LSB16, unsigned char MSB16);
#define LED 13
char LEDState = 0;
void setup()
{
Serial.begin(115200);
Serial.write("CCCCC");
delay(1000);
}
void loop()
{
delay(700);
SERVOSET(16, 11, 52, 13, 80, 4, 116, 20, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16);
delay(292);
SERVOCTRLSPEED(0);
delay(600);
SERVOSET(28, 20, 16, 16, 80, 4, 116, 20, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16);
delay(646);
SERVOSET(24, 21, 16, 17, 80, 4, 116, 20, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16);
delay(517);
SERVOCTRLSPEED(120);
delay(200);
SERVOSET(76, 33, 24, 18, 80, 4, 116, 20, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16);
delay(3147);
SERVOSET(76, 33, 24, 18, 80, 4, 92, 5, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16);
delay(4640);
SERVOSET(104, 21, 24, 18, 80, 4, 92, 5, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16);
delay(2713);
SERVOSET(80, 16, 116, 15, 80, 4, 92, 5, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16);
delay(1307);
SERVOSET(16, 11, 52, 13, 80, 4, 92, 5, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16);
delay(1000);
// Comment or remove the next 5 lines to run code in loop...
while(1)
{
LEDToggle();
delay(100);
}
}
void SERVOCTRLSPEED(char Speed)
{
int count;
for (count=0; count <16; count++)
{
Serial.write(170);
Serial.write(8);
Serial.write(0);
Serial.write(127-Speed);
}
}
void SERVOSET(unsigned char LSB1, unsigned char MSB1, unsigned char LSB2, unsigned char MSB2, unsigned char LSB3, unsigned char MSB3, unsigned char LSB4, unsigned char MSB4, unsigned char LSB5, unsigned char MSB5, unsigned char LSB6, unsigned char MSB6, unsigned char LSB7, unsigned char MSB7, unsigned char LSB8, unsigned char MSB8, unsigned char LSB9, unsigned char MSB9, unsigned char LSB10, unsigned char MSB10, unsigned char LSB11, unsigned char MSB11, unsigned char LSB12, unsigned char MSB12, unsigned char LSB13, unsigned char MSB13, unsigned char LSB14, unsigned char MSB14, unsigned char LSB15, unsigned char MSB15, unsigned char LSB16, unsigned char MSB16)
{
Serial.write(170); Serial.write(10);
Serial.write(LSB1); Serial.write(MSB1);Serial.write(LSB2);Serial.write(MSB2);Serial.write(LSB3);Serial.write(MSB3);Serial.write(LSB4);Serial.write(MSB4);
Serial.write(LSB5);Serial.write(MSB5);Serial.write(LSB6);Serial.write(MSB6);Serial.write(LSB7);Serial.write(MSB7);Serial.write(LSB8);Serial.write(MSB8);
Serial.write(LSB9);Serial.write(MSB9);Serial.write(LSB10);Serial.write(MSB10);Serial.write(LSB11);Serial.write(MSB11);Serial.write(LSB12);Serial.write(MSB12);
Serial.write(LSB13);Serial.write(MSB13);Serial.write(LSB14);Serial.write(MSB14);Serial.write(LSB15);Serial.write(MSB15);Serial.write(LSB16); Serial.write(MSB16);
LEDToggle();
}
void LEDToggle(void)
{
if (LEDState == 0)
LEDState = 1;
else
LEDState = 0;
digitalWrite(LED, LEDState);
}

View File

@ -0,0 +1,76 @@
void LEDToggle(void);
void SERVOCTRLSPEED(char Speed);
void SERVOSET(unsigned char LSB1, unsigned char MSB1, unsigned char LSB2, unsigned char MSB2, unsigned char LSB3, unsigned char MSB3, unsigned char LSB4, unsigned char MSB4, unsigned char LSB5, unsigned char MSB5, unsigned char LSB6, unsigned char MSB6, unsigned char LSB7, unsigned char MSB7, unsigned char LSB8, unsigned char MSB8, unsigned char LSB9, unsigned char MSB9, unsigned char LSB10, unsigned char MSB10, unsigned char LSB11, unsigned char MSB11, unsigned char LSB12, unsigned char MSB12, unsigned char LSB13, unsigned char MSB13, unsigned char LSB14, unsigned char MSB14, unsigned char LSB15, unsigned char MSB15, unsigned char LSB16, unsigned char MSB16);
#define LED 13
char LEDState = 0;
void setup()
{
Serial.begin(115200);
Serial.write("CCCCC");
delay(1000);
}
void loop()
{
delay(700);
SERVOSET(16, 11, 52, 13, 80, 4, 116, 20, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16);
delay(3440);
SERVOCTRLSPEED(0);
delay(600);
SERVOSET(28, 20, 16, 16, 80, 4, 116, 20, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16);
delay(646);
SERVOSET(24, 21, 16, 17, 80, 4, 116, 20, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16);
delay(517);
SERVOCTRLSPEED(120);
delay(200);
SERVOSET(76, 33, 24, 18, 80, 4, 116, 20, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16);
delay(3147);
SERVOSET(76, 33, 24, 18, 80, 4, 92, 5, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16);
delay(4640);
SERVOSET(104, 21, 24, 18, 80, 4, 92, 5, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16);
delay(2713);
SERVOSET(80, 16, 116, 15, 80, 4, 92, 5, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16);
delay(1307);
SERVOSET(16, 11, 52, 13, 80, 4, 92, 5, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16, 100, 16);
delay(1000);
// Comment or remove the next 5 lines to run code in loop...
while(1)
{
LEDToggle();
delay(100);
}
}
void SERVOCTRLSPEED(char Speed)
{
int count;
for (count=0; count <16; count++)
{
Serial.write(170);
Serial.write(8);
Serial.write(0);
Serial.write(127-Speed);
}
}
void SERVOSET(unsigned char LSB1, unsigned char MSB1, unsigned char LSB2, unsigned char MSB2, unsigned char LSB3, unsigned char MSB3, unsigned char LSB4, unsigned char MSB4, unsigned char LSB5, unsigned char MSB5, unsigned char LSB6, unsigned char MSB6, unsigned char LSB7, unsigned char MSB7, unsigned char LSB8, unsigned char MSB8, unsigned char LSB9, unsigned char MSB9, unsigned char LSB10, unsigned char MSB10, unsigned char LSB11, unsigned char MSB11, unsigned char LSB12, unsigned char MSB12, unsigned char LSB13, unsigned char MSB13, unsigned char LSB14, unsigned char MSB14, unsigned char LSB15, unsigned char MSB15, unsigned char LSB16, unsigned char MSB16)
{
Serial.write(170); Serial.write(10);
Serial.write(LSB1); Serial.write(MSB1);Serial.write(LSB2);Serial.write(MSB2);Serial.write(LSB3);Serial.write(MSB3);Serial.write(LSB4);Serial.write(MSB4);
Serial.write(LSB5);Serial.write(MSB5);Serial.write(LSB6);Serial.write(MSB6);Serial.write(LSB7);Serial.write(MSB7);Serial.write(LSB8);Serial.write(MSB8);
Serial.write(LSB9);Serial.write(MSB9);Serial.write(LSB10);Serial.write(MSB10);Serial.write(LSB11);Serial.write(MSB11);Serial.write(LSB12);Serial.write(MSB12);
Serial.write(LSB13);Serial.write(MSB13);Serial.write(LSB14);Serial.write(MSB14);Serial.write(LSB15);Serial.write(MSB15);Serial.write(LSB16); Serial.write(MSB16);
LEDToggle();
}
void LEDToggle(void)
{
if (LEDState == 0)
LEDState = 1;
else
LEDState = 0;
digitalWrite(LED, LEDState);
}

View File

@ -0,0 +1 @@
These are codes for https://robokits.co.in/robot-kits/robotic-arm-kit/robotic-arm-6-dof-diy-kit-with-usb-servo-controller-and-software?zenid=ikleh0e4bsd2o23lqe7da8qid7

View File

@ -0,0 +1,90 @@
#include <NewPing.h>
#define SONAR_NUM 5
#define FR_R 9
#define FR_L 6
#define RE_L 4
#define LT_F 8
#define LT_R 4
#define FILTER 0
unsigned long pingTimer[SONAR_NUM];
unsigned int cm[SONAR_NUM];
int dur[SONAR_NUM] = {0,0,0,0,0};
float dis[SONAR_NUM] = {0,0,0,0,0};
const int SONAR[SONAR_NUM] = {RE_L, LT_R, FR_L, LT_F, FR_R};
void setup()
{
Serial.begin(115200);
}
uint32_t t = 0;
void loop() {
t = millis();
oneSensorCycle();
/*for (float i : dis)
{
Serial.print(i);
Serial.print('\t');
}*/
Serial.println(millis() - t);
//delay(100);
}
uint8_t port;
void oneSensorCycle() {
for (int i = 0;i < SONAR_NUM;i++) {
if (i < 3)
{
DDRD |= _BV(SONAR[i]);
PORTD &= ~_BV(SONAR[i]);
}
else
{
DDRB |= _BV(SONAR[i]-8);
PORTB &= ~_BV(SONAR[i]-8);
}
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
if (i < 3)
PORTD |= _BV(SONAR[i]);
else
PORTB |= _BV(SONAR[i] - 8);
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");__asm__("nop\n\t");
if (i < 3)
{
PORTD &= ~_BV(SONAR[i]);
DDRD &= ~_BV(SONAR[i]);
}
else
{
PORTB &= ~_BV(SONAR[i] - 8);
DDRB &= ~_BV(SONAR[i] - 8);
}
#if FILTER
dur[i] = dur[i] * 0.75 + pulseIn(SONAR[i], 1) * 0.25;
#else
dur[i] = pulseIn(SONAR[i], 1);
dis[i] = 330.0 * dur[i] / 1000000.0;
#endif
delay(1);
}
}

View File

@ -0,0 +1 @@
Localization using ultrasonic distance sensors. Still in development.

View File

@ -0,0 +1,2 @@
This is Two-wheeled self balancing robot with robotic arm. Its function is to pick and place objects while avoiding obstacles.
Not yet completed.

View File

@ -0,0 +1,90 @@
#define ma 1000
int pos_e[2], pos_er[2], pos_s[2], pos_sr[2];
int x[] = { -30, -15, -7, -2, 0, 2, 7, 15, 30 }, n = 9,
x_dot[] = { -70, -30, 0, 30, 70 }, m = 5,
q = 5,
s_dot[] = { -5000,-1500,0,1500,5000 }, o = 5,
err_dom[9], err_dot_dom[5], s_dot_dom[5], s_dom[5],
s[] = { -100, -5, 0, 5, 100 },
outs[5][5] = { { 5, 1, 0, -1, -5 },
{ 5, 1, 0, -1, -5 },
{ 5, 1, 0, -1, -5 }, //0
{ 5, 1, 0, -1, -5 },
{ 5, 1, 0, -1, -5 } },
/* outs[5][5] = { { 35, 30, 30, 20, 0 },
{ 20, 7, 7, 0, -5 },
{ 7, 2, 0, -2, -7 }, //0
{ 5, 0, -7, -7, -20 },
{ 0, -20, -30, -30, -35 } },*/
out[5][9] =
{ { -7700, -4500, -1400, -800, -80, 200, 800, 3000, 4000 },
{ -6000, -4000, -1200, -700, -10, 350, 900, 3300, 4500 },
{ -5000, -3500, -1000, -550, 0, 550, 1000, 3500, 5000 }, //0
{ -4500, -3300, -900, -350, 10, 700, 1200, 4000, 6000 },
{ -4000, -3000, -800, -200, 80, 800, 1400, 4500, 7700 } }
;
FASTRUN void calc_dom(float err, int x[], int dom[], int n, int pos[]) {
if (err <= x[0]) {
dom[0] = ma;
pos[0] = pos[1] = 0;
return;
}
if (err >= x[n - 1]) {
dom[n - 1] = ma;
pos[0] = pos[1] = n - 1;
return;
}
for (int i = 0; i < n - 1; i++) {
if ((err > x[i]) && (err < x[i + 1])) {
float m = (ma * 1.0f) / (x[i + 1] - x[i]);
dom[i] = (int)(-m * (err - x[i + 1]));
dom[i + 1] = (int)(m * (err - x[i]));
pos[0] = i;
pos[1] = i + 1;
return;
}
else
if (err == x[i]) {
dom[i] = ma;
pos[0] = pos[1] = i;
return;
}
}
}
FASTRUN float calc_vel_fuzzy(float err, int err_dot)
{
float output = 0;
calc_dom(err, s, s_dom, q, pos_s);
calc_dom(err_dot, s_dot, s_dot_dom, o, pos_sr);
//calc_dom(pre_V, V, V_dom, o, pos_V);
float sum = 0; float t = 0;
for (int i = 0; i < 2; i++)
for (int j = 0; j < 2; j++) {
output += (t = ((s_dot_dom[pos_sr[j]] < s_dom[pos_s[i]]) ? s_dot_dom[pos_sr[j]] : s_dom[pos_s[i]])) * outs[pos_sr[j]][pos_s[i]];
sum += t;
}
output /= sum;
return output;
}
FASTRUN int calc_fuzzy(float err, int err_dot)
{
int output = 0;
calc_dom(err, x, err_dom, n, pos_e);
calc_dom(err_dot, x_dot, err_dot_dom, m, pos_er);
//calc_dom(pre_V, V, V_dom, o, pos_V);
float sum = 0; int t = 0;
for (int i = 0; i < 2; i++)
for (int j = 0; j < 2; j++) {
output += (t = ((err_dot_dom[pos_er[j]] < err_dom[pos_e[i]]) ? err_dot_dom[pos_er[j]] : err_dom[pos_e[i]])) * out[pos_er[j]][pos_e[i]];
sum += t;
}
output /= sum;
return output;
}

View File

@ -0,0 +1,123 @@
#define LTM_DIR 4
#define RTM_DIR 2
#define LTM_FRQ 5
#define RTM_FRQ 3
#define LF 1
#define RF 0
int BACKLASH_COMP = 0;
int32_t RV = 0;
int32_t LV = 0;
volatile bool rDir = 0, lDir = 0;
IntervalTimer motorR;
IntervalTimer motorL;
volatile int32_t sL = 0; volatile int addL = 0;
volatile bool LPS = 0;
FASTRUN void motorL_callback() {
if (LPS)
sL += addL;
digitalWriteFast(LTM_FRQ, LPS = !LPS);
}
volatile int32_t sR = 0; volatile int addR = 0;
volatile bool RPS = 0;
FASTRUN void motorR_callback() {
if (RPS)
sR += addR;
digitalWriteFast(RTM_FRQ, RPS = !RPS);
}
#define ALT_OUT 0
#if ALT_OUT
bool pRd, pLd;
FASTRUN void output(int32_t LT, int32_t RT) {
motorL.end();
motorR.end();
if (RT != 0) {
if (RT > 0) {
if (rDir != RF) {
addR = 1;
digitalWriteFast(RTM_DIR, rDir = RF);
motorR.begin(motorR_callback, 500000.0 / abs(7700));
motorR.end();
}
}
else {
if (rDir != (!RF)) {
addR = -1;
digitalWriteFast(RTM_DIR, rDir = !RF);
motorR.begin(motorR_callback, 500000.0 / abs(7700));
motorR.end();
}
}
motorR.begin(motorR_callback, 500000.0 / abs(RT));
}
if (LT != 0) {
if (LT > 0) {
if (lDir != LF) {
addL = 1;
digitalWriteFast(LTM_DIR, lDir = LF);
motorL.begin(motorL_callback, 500000.0 / abs(7700));
motorL.end();
}
}
else {
if (lDir != (!LF)) {
addL = -1;
digitalWriteFast(LTM_DIR, lDir = !LF);
motorL.begin(motorL_callback, 500000.0 / abs(7700));
motorL.end();
}
}
motorL.begin(motorL_callback, 500000.0 / abs(LT));
}
}
#else
FASTRUN void output(int32_t LT, int32_t RT) {
motorL.end();
motorR.end();
sR = sL = 0;
if (RT != 0) {
if (RT > 0) {
if (rDir != RF) {
addR = 1;
digitalWriteFast(RTM_DIR, rDir = RF);
}
RT += BACKLASH_COMP;
}
else {
if (rDir != (!RF)) {
addR = -1;
digitalWriteFast(RTM_DIR, rDir = !RF);
}
RT -= BACKLASH_COMP;
}
motorR.begin(motorR_callback, 500000.0 / abs(RT));
}
if (LT != 0) {
if (LT > 0) {
if (lDir != LF) {
addL = 1;
digitalWriteFast(LTM_DIR, lDir = LF);
}
LT += BACKLASH_COMP;
}
else {
if (lDir != (!LF)) {
addL = -1;
digitalWriteFast(LTM_DIR, lDir = !LF);
}
LT -= BACKLASH_COMP;
}
motorL.begin(motorL_callback, 500000.0 / abs(LT));
}
}
#endif

View File

@ -0,0 +1,209 @@
#include "Fuzzy_controller.h"
#include "Motor_driver.h"
#include <I2Cdev.h>
#include <MPU6050_6Axis_MotionApps20.h>
#include <Wire.h>
//#include "Kalman.h"
#define MPU_INT 20
#define PID 1
//#define MPU_ZERO -3
float MPU_ZERO = -5.0;
#define L 0
#define R 1
#define P 2
#define Y 3
#define N 5
//const int16_t magX = -364, magY = 99, magZ = -42; //HMC5883L Mag Calibration Offsets
volatile uint8_t vel_tim = 0;
bool dmpReady = false; // set true if DMP init was successful
uint8_t mpuIntStatus; // holds actual interrupt status byte from MPU
uint8_t devStatus; // return status after each device operation (0 = success, !0 = error)
uint16_t packetSize; // expected DMP packet size (default is 42 bytes)
uint16_t fifoCount; // count of all bytes currently in FIFO
uint8_t fifoBuffer[64]; // FIFO storage buffer
//Kalman filter;
uint32_t timer;
uint32_t tim;
float Offset[4] = { 0,0,0,0 };
float Offset_dot[4] = { 0,0,0,0 };
float in[4];
float in_dot[4];
float in_dot_dot[2];
float E[4];
float Err[2];
float Er[4];
/*
0 P
1 Y
2 dist_L
3 dist_R
*/
uint8_t mode = 1;/*
0 - Calculate Offset.
1 - Maintain Balance and Position
2 - Turn by x degrees
3 - Move x distance
4 - Turn while moving
default - Maintain and Rotate
*/
//uint8_t buffer[6];int mx, my, mz;
MPU6050 mpu;
//#define HMC5883L 0x1E
volatile bool mpuInterrupt = false;
FASTRUN void dmpDataReady() {
mpuInterrupt = true;
vel_tim++;
}
FASTRUN void get_input() {
/* I2Cdev::readBytes(HMC5883L, 0x03, 6, buffer);
I2Cdev::writeByte(HMC5883L, 0x02, 0x01);
mx = ((int16_t)((buffer[0] << 8) | buffer[1])) - magX;
my = ((int16_t)((buffer[4] << 8) | buffer[5])) - magY;
mz = ((int16_t)((buffer[2] << 8) | buffer[3])) - magZ;
*/
float w = (int16_t)((fifoBuffer[0] << 8) | fifoBuffer[1]) / 16384.0;
float x = (int16_t)((fifoBuffer[4] << 8) | fifoBuffer[5]) / 16384.0;
float y = (int16_t)((fifoBuffer[8] << 8) | fifoBuffer[9]) / 16384.0;
float z = (int16_t)((fifoBuffer[12] << 8) | fifoBuffer[13]) / 16384.0;
float ty = 2 * (w * x + y * z);
float tz = w * w - x * x - y * y + z * z;
double dt = (micros() - timer) / 1000000.0;
timer = micros();
in[P] = atan(2 * (x * z - w * y)) / sqrt(ty * ty + tz * tz);
//in_dot[Y] = (int16_t)((fifoBuffer[24] << 8) | fifoBuffer[25]);
in_dot[P] = -(int16_t)((fifoBuffer[20] << 8) | fifoBuffer[21]);
// float tempY = atan2(-my, mx + mz * sin(in[P])) * RAD_TO_DEG;
in[P] = in[P] * RAD_TO_DEG - MPU_ZERO;
/* if ((tempY < -90 && in[Y] > 90) || (tempY > 90 && in[Y] < -90)) {
filter.setAngle(tempY);
in[Y] = tempY;
}
else
in[Y] = filter.getAngle(tempY, in_dot[Y] / 131.0, dt);
*/
if (vel_tim == N) {
float temp = (sL * 0.2) * DEG_TO_RAD * 6.25;
in_dot[L] = temp / dt;
in[L] += temp;
temp = (sR * 0.2) * DEG_TO_RAD * 6.25;
in_dot[R] = temp / dt;
in[R] += temp;
vel_tim = 0;
in_dot[Y] = RAD_TO_DEG * (in_dot[L] - in_dot[R]) / 35.0;
in[Y] = RAD_TO_DEG * (in[L] - in[R]) / 35.0;
if (in[Y] > 360)
in[Y] = (int)(in[Y]) % 360;
else if (in[Y] < -360)
in[Y] = - ((int)(-in[Y]) % 360);
}
/*
if (vel_tim == N) {
float temp = (sL * 0.2) * DEG_TO_RAD * 6.25;
in_dot[L] = (temp - in[L]) / dt;
in[L] = temp;
temp = (sR * 0.2) * DEG_TO_RAD * 6.25;
in_dot[R] = (temp - in[R]) / dt;
in[R] = temp;
vel_tim = 0;
in[Y] = in[L] - in[R];
in[L] = in_dot[L];
in[R] = in_dot[R];
}*/
}
void setMode(int m) {
mode = m;
/*
0 - Calculate Offset.
1 - Maintain Balance and Position
2 - Turn by x degrees
3 - Move x distance
4 - Turn while moving
default - Maintain and Rotate
*/
Offset[Y] = in[Y];
switch (mode)
{
case 0:
break;
case 1:
Offset[L] = in[L];
Offset[R] = in[R];
Offset[P] = 0;
break;
case 2:
break;
case 3:
break;
case 4:
break;
default:
break;
}
}
void turnByX(float x) {}
void moveByD(int D) {}
void moveByAndTurn(int d, float x) {}
void maintainAndRotate() {}
void calculateOffset() {}
FASTRUN void cal_Err() {
if ((millis() - tim) >= 2000)
{
Offset_dot[L] = Offset_dot[R] = Offset_dot[Y] = 0;
tim = millis();
E[L] = Offset[L] - in[L];
E[R] = Offset[R] - in[R];
E[Y] = Offset[Y] - in[Y];
Er[L] = Offset_dot[L] - in_dot[L];
Er[R] = Offset_dot[R] - in_dot[R];
Er[Y] = Offset_dot[Y] - in_dot[Y];
}
if (!vel_tim)
{
E[L] = Offset[L] - in[L];
E[R] = Offset[R] - in[R];
E[Y] = Offset[Y] - in[Y];
Er[L] = Offset_dot[L] - in_dot[L];
Er[R] = Offset_dot[R] - in_dot[R];
Er[Y] = Offset_dot[Y] - in_dot[Y];
}
E[P] = Offset[P] - in[P];
Er[P] = Offset_dot[P] - in_dot[P];
}

View File

@ -0,0 +1,172 @@
#include "SBR_final_teensy.h"
int tem1, c = 0; float p = -0.02, i = -0.0015, d = 0;
float pp = 200.0, dp = 10.0; float tempCEy = 0.0;
float py = 0;
float tempCE = 0.0; float tempE = 0; int diff = 0;
void setup()
{
pinMode(13, OUTPUT);
digitalWrite(13, 1);
delay(2000);
Serial1.begin(115200);
digitalWrite(13, 0);
delay(500);
digitalWrite(13, 1);
Wire.begin();
Wire.setClock(400000); // 400kHz I2C clock. Comment this line if having compilation difficulties
mpu.initialize();
pinMode(MPU_INT, INPUT);
pinMode(LTM_DIR, OUTPUT);
pinMode(RTM_DIR, OUTPUT);
pinMode(LTM_FRQ, OUTPUT);
pinMode(RTM_FRQ, OUTPUT);
mpu.testConnection();
devStatus = mpu.dmpInitialize();
mpu.setXGyroOffset(220);
mpu.setYGyroOffset(76);
mpu.setZGyroOffset(-85);
mpu.setZAccelOffset(1788);
mpu.setDMPEnabled(true);
attachInterrupt(digitalPinToInterrupt(MPU_INT), dmpDataReady, RISING);
mpuIntStatus = mpu.getIntStatus();
dmpReady = true;
packetSize = mpu.dmpGetFIFOPacketSize();
/* mpu.setI2CBypassEnabled(true);
I2Cdev::writeByte(HMC5883L, 0x00, (0x03 << 5) | (0x04 << 2) | 0x00);
I2Cdev::writeByte(HMC5883L, 0x01, 0x01 << 5);
I2Cdev::writeByte(HMC5883L, 0x02, 0x01);
*/ setMode(1);
}
void loop()
{
if (!dmpReady) return;
while (!mpuInterrupt && fifoCount < packetSize);
mpuInterrupt = false;
mpuIntStatus = mpu.getIntStatus();
fifoCount = mpu.getFIFOCount();
if ((mpuIntStatus & 0x10) || fifoCount == 1024)
I2Cdev::writeBit(0x68, 0x6A, 2, 1);//reset FIFO
else
if (mpuIntStatus & 0x02) {
while (fifoCount < packetSize)
fifoCount = mpu.getFIFOCount();
I2Cdev::readBytes(0x68, 0x74, packetSize, fifoBuffer);//read FIFO
fifoCount -= packetSize;
get_input();
if (Serial1.available() > 2) {
switch (Serial1.read())
{
//case 'x':x1 = Serial1.parseInt();
// Serial1.read();x[x1] = -Serial1.parseInt();x[6 - x1] = -x[x1];
// break;
case 'o': Offset_dot[L] = Offset_dot[R] = Serial1.parseInt();break;
case 'd':d = Serial1.parseFloat();break;
case 'p':p = Serial1.parseFloat();break;
case 'i':i = Serial1.parseFloat();break;
case 's':MPU_ZERO = Serial1.parseFloat();break;
case 'y':pp = Serial1.parseFloat();break;
case 'z':dp = Serial1.parseFloat(); break;
case 'a':py = Serial1.parseFloat();break;
case 'b':Offset_dot[L] = Offset_dot[R] = Offset_dot[Y] = 0; tim = 0; break;
case 't':Offset_dot[Y] = Serial1.parseInt(); Offset_dot[L] = Offset_dot[R] = 0; tim = millis(); break;
case 'c':BACKLASH_COMP = Serial1.parseInt(); break;
case 'f':Offset_dot[L] = Offset_dot[R] = Serial1.parseFloat(); Offset_dot[Y] = 0; tim = millis(); break;
}
Serial1.read();
}
switch (mode) {
case 0:
calculateOffset();
break;
case 1:
stayStill();
break;
case 2:
break;
case 3:
break;
case 4:
break;
default:
maintainAndRotate();
}
if (abs(in[P]) > 40)
output(0, 0);
else
output(LV, RV);
}
}
void display_debug()
{
Serial1.print('a');
Serial1.print(Er[Y]);
Serial1.print("\t");
Serial1.print(in[Y]);
Serial1.print("\t");
Serial1.print(in[L] - in[R]);
Serial1.print("\t");
Serial1.print(tem1);
Serial1.print("\t");
Serial1.print(diff);
Serial1.print("\t");
Serial1.print(LV-RV);
Serial1.print("\t");
Serial1.println(RV);
}
//float f;
FASTRUN void stayStill() {
cal_Err();
#if PID
if (!vel_tim) {
tempE = (Er[L] + Er[R]);
if (tempE == 0) tempCE = 0;
tempCE += tempE * i;
tempCE = ((tempCE > 15) ? 15 : (tempCE < -15) ? -15 : tempCE);
diff = py * Er[Y];
}
Offset[P] = tempE * p + tempCE + (in_dot_dot[R] + in_dot_dot[L]) * d;
if (abs(tempE) > 0)
Offset[P] = ((Offset[P] > 20) ? 20 : (Offset[P] < -20) ? -20 : Offset[P]);
else
Offset[P] = 0;
cal_Err();
tem1 = E[P] * pp + Er[P] * dp;
#else
//Serial1.print(LV);
//Serial1.print('\t');
Offset[P] = calc_vel_fuzzy(((E[L] + E[R]) / 2.0), (Er[L] + Er[R]) / 2.0);
cal_Err();
tem1 = calc_fuzzy(E[P], Er[P]);
LV = RV = tem1;
#endif
LV = tem1 + diff;
RV = tem1 - diff;
display_debug();
}

View File

@ -0,0 +1 @@
Code for driving motor using Stepper drive with Pulse and Direction pins.

View File

@ -0,0 +1,166 @@
#define LD 40
#define RD 42
#define LP 44
#define RP 46
void delay_1us()
{
__asm__ __volatile__(
"nop" "\n\t"
"nop" "\n\t"
"nop" "\n\t"
"nop" "\n\t"
"nop" "\n\t"
"nop" "\n\t"
"nop" "\n\t"
"nop" "\n\t"
"nop" "\n\t"
"nop" "\n\t"
"nop" "\n\t"
"nop" "\n\t"
"nop" "\n\t"
"nop" "\n\t"
"nop" "\n\t"
"nop");
}
void setup() {
Serial.begin(115200);
pinMode(30, OUTPUT);
pinMode(31, OUTPUT);
pinMode(LP, OUTPUT);
pinMode(RP, OUTPUT);
digitalWrite(30,1);
digitalWrite(RD,0);
/*int del = 65;
delay(100);
/*PORTD = B00000000;Serial.println("done");
for(int k = 0;k < 15;k++)
for (int j = 0;j < (1800);j++)
{
PORTD = B00000000;
delayMicroseconds(del);
/*for (int i = 0;i < del;i++) {
delay_1us();
}*/
/*PORTD = B00001000;
delayMicroseconds(del);
/*for (int i = 0;i < del;i++) {
delay_1us();
}*/
}
//Serial.println("done");
//for (int k = 0;k < 10000000000;k++)
/*for (int i = 0;i < 10000000;i++) {
PORTD = B00000000;
for (int j = i;j < 1000;j++)
{
delay_1us();
}
delay_1us();
PORTD = B00001000;
}*/
void loop() {
delayMicroseconds(65);
digitalWrite(31,0);
// digitalWrite(RP,0);
delayMicroseconds(65);
digitalWrite(31,1);
// digitalWrite(,1);
}
/*
#define LD 2
#define RD 3
#define LP 4
#define RP 5
void setup()
{
pinMode(LD, OUTPUT);
// pinMode(RD, OUTPUT);
pinMode(LP, OUTPUT);
pinMode(RP, OUTPUT);
PORTD = B00000000;
/*for (int i = 0;i < 3;i++) {
delay(100);
PORTD = B00101000;
PORTD = B00001000;
}
*/
//pinMode(3, OUTPUT);
/*pinMode(11, OUTPUT);
TCCR2A = _BV(COM2A0) | _BV(COM2B1) | _BV(WGM20);
TCCR2B = _BV(WGM22) | _BV(CS22) | _BV(CS21) | _BV(CS20);
OCR2A = 156;
OCR2B = 4;
*/
/*}
void loop()
{
/*
PORTD = B00001000;
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
PORTD = B00101000;
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
__asm__("nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t""nop\n\t");
*/
//}

View File

@ -0,0 +1,215 @@
uint32_t start=0;volatile int duration=0;
volatile bool chaR=false;volatile int i=0;
volatile int msg=0;
const int led=3;
const int n=70;
void setup(){
Serial.begin(9600);
pinMode(2,INPUT);
pinMode(led,OUTPUT);
attachInterrupt(0,startM,RISING);
attachInterrupt(0,endM,FALLING);
}
void startM()
{
start=millis();
}
void endM(){
duration = millis()-start;
duration +=40;
i++;
msg=msg*10+duration/100;
}
void loop(){
if(i==4){
Serial.print(decodeMsg(msg));i=0;msg=0;
}
if(Serial.available()>0) //if the input field of the serial monitor has a value
{
char ch = Serial.read();
sendCode(encodeMsg(ch));
}
}
int encodeMsg(char ch){
switch(ch){
case '\n': return 1111;
case 'a': return 1112;
case 'b': return 1121;
case 'c': return 1332;
case 'd': return 1122;
case 'e': return 1211;
case 'f': return 1212;
case 'g': return 1221;
case 'h': return 1222;
case 'i': return 2111;
case 'j': return 2112;
case 'k': return 2121;
case 'l': return 2122;
case 'm': return 2211;
case 'n': return 2212;
case 'o': return 2221;
case 'p': return 2222;
case 'q': return 3111;
case 'r': return 3112;
case 's': return 3121;
case 't': return 3122;
case 'u': return 3211;
case 'v': return 3212;
case 'w': return 3221;
case 'x': return 3222;
case 'y': return 4111;
case 'z': return 1311;
case '1': return 4121;
case '2': return 4122;
case '3': return 4211;
case '4': return 4212;
case '5': return 4221;
case '6': return 4222;
case '7': return 5111;
case '8': return 5112;
case '9': return 5121;
case '.': return 5122;
case '(': return 5211;
case ')': return 5212;
case '+': return 5221;
case '-': return 5222;
case '!': return 4112;
case '?': return 1312;
case ',': return 1313;
case '0': return 1321;
case 'A': return 1322;
case 'B': return 1323;
case 'C': return 1331;
case 'D': return 1333;
case 'E': return 2311;
case 'F': return 2312;
case 'G': return 2313;
case 'H': return 2321;
case 'I': return 2322;
case 'J': return 2323;
case 'K': return 2331;
case 'L': return 2332;
case 'M': return 2333;
case 'N': return 3311;
case 'O': return 3312;
case 'P': return 3313;
case 'Q': return 3321;
case 'R': return 3322;
case 'S': return 3323;
case 'T': return 3331;
case 'U': return 3332;
case 'V': return 4311;
case 'W': return 4312;
case 'X': return 4313;
case 'Y': return 4321;
case 'Z': return 4322;
// enter all the codes here should be exactly same as in letters array
}
}
char decodeMsg(int i){
switch(i){
//make all cases for all the values of i
case 1111: return '\n';
case 1112: return 'a';
case 1121: return 'b';
case 1332: return 'c';
case 1122: return 'd';
case 1211: return 'e';
case 1212: return 'f';
case 1221: return 'g';
case 1222: return 'h';
case 2111: return 'i';
case 2112: return 'j';
case 2121: return 'k';
case 2122: return 'l';
case 2211: return 'm';
case 2212: return 'n';
case 2221: return 'o';
case 2222: return 'p';
case 3111: return 'q';
case 3112: return 'r';
case 3121: return 's';
case 3122: return 't';
case 3211: return 'u';
case 3212: return 'v';
case 3221: return 'w';
case 3222: return 'x';
case 4111: return 'y';
case 1311: return 'z';
case 4121: return '1';
case 4122: return '2';
case 4211: return '3';
case 4212: return '4';
case 4221: return '5';
case 4222: return '6';
case 5111: return '7';
case 5112: return '8';
case 5121: return '9';
case 5122: return '.';
case 5211: return '(';
case 5212: return ')';
case 5221: return '+';
case 5222: return '-';
case 4112: return '!';
case 1312: return '?';
case 1313: return ',';
case 1321: return '0';
case 1322: return 'A';
case 1323: return 'B';
case 1331: return 'C';
case 1333: return 'D';
case 2311: return 'E';
case 2312: return 'F';
case 2313: return 'G';
case 2321: return 'H';
case 2322: return 'I';
case 2323: return 'J';
case 2331: return 'K';
case 2332: return 'L';
case 2333: return 'M';
case 3311: return 'N';
case 3312: return 'O';
case 3313: return 'P';
case 3321: return 'Q';
case 3322: return 'R';
case 3323: return 'S';
case 3331: return 'T';
case 3332: return 'U';
case 4311: return 'V';
case 4312: return 'W';
case 4313: return 'X';
case 4321: return 'Y';
case 4322: return 'Z';
}
}
void sendCode(int code) //convert the char to the corresponding element in the array
{
int ch = 0;
while((ch=(code%10))!=0)
{
digitalWrite(led, HIGH); //turn on the LED
dela(ch*100);
digitalWrite(led, LOW); //turn off the LED
dela(100);
code = code/10;
}
dela(100);
}
void dela(int d)
{
uint32_t t = millis();
while((millis()-t)<d);
}

View File

@ -0,0 +1,243 @@
uint16_t start=0;bool high=false;int duration=0;char c=0;
bool chaR=false;int i=0;
int dotdelay = 500;
int dashdelay = 1500;
int halfdelay = (dotdelay+dashdelay)/2.0;
int delaybc=500;//delay between next char sent
//change this letters array to your own code, each should be of 6 . or - exactly.
char* letters[] = {"......" ,
"...../" ,
"..../." ,
"....//" ,
".../.." ,
"..././" ,
"...//." ,
"...///" ,
"../..." ,
"../../" ,
".././." ,
"..//.." ,
"..//./" ,
"..///." ,
"..////" ,
"./...." ,
"./.../" ,
"./../." ,
"./..//" ,
"././.." ,
"./././" ,
"././/." ,
"././//" ,
".//..." ,
".//../" ,
".//./." ,
".//.//" ,
".///.." ,
".///./" ,
".////." ,
"./////" ,
"/....." ,
"/..../" ,
"/.../." ,
"/...//" ,
"/../.." ,
"/.././" ,
"/..//." ,
"/..///" ,
"/./..." ,
"/./../" ,
"/././." ,
"/././/" ,
"//////" };
int led=3;
int photoDetector=2;
int n=40;// size of letters array
char msg[7]={0,0,0,0,0,0,'\0'};
void setup(){
Serial.begin(57600);
Serial.println("Starting....");
pinMode(photoDetector,INPUT);
pinMode(led,OUTPUT);
attachInterrupt(photoDetector,startM,RISING);
attachInterrupt(photoDetector,endM,FALLING);
}
void startM()
{
start=millis();
Serial.println("Hello!!!");
//high=true;
//while(high);
}
void endM(){
duration = millis()-start;
Serial.println("Bye!!!");
//high=false;
if(duration<halfdelay)c='.';
else c='/';
chaR=true;
}
void loop(){
if(chaR){
Serial.println("OK...");
msg[i++]=c;
chaR=false;
if(i==6){
int j=0;
while(strcmp(letters[j++],msg)&&(j<n));
Serial.print(decodeMsg(j));i=0;
}
}
if(Serial.available()>0) //if the input field of the serial monitor has a value
{
char ch = Serial.read();
sendCode(encodeMsg(ch));
}
}
char* encodeMsg(char ch){
switch(ch){
case '\n': return "......";
case 'A': return "...../";
case 'B': return "..../.";
case 'D': return "....//";
case 'E': return ".../..";
case 'F': return "..././";
case 'G': return "...//.";
case 'H': return "...///";
case 'I': return "../...";
case 'J': return "../../";
case 'K': return ".././.";
case 'L': return "..//..";
case 'M': return "..//./";
case 'N': return "..///.";
case 'O': return "..////";
case 'P': return "./....";
case 'Q': return "./.../";
case 'R': return "./../.";
case 'S': return "./..//";
case 'T': return "././..";
case 'U': return "./././";
case 'V': return "././/.";
case 'W': return "././//";
case 'X': return ".//...";
case 'Y': return ".//../";
case 'Z': return ".//./.";
case '1': return ".//.//";
case '2': return ".///..";
case '3': return ".///./";
case '4': return ".////.";
case '5': return "./////";
case '6': return "/.....";
case '7': return "/..../";
case '8': return "/.../.";
case '9': return "/...//";
case '.': return "/../..";
case '(': return "/.././";
case ')': return "/..//.";
case '+': return "/..///";
case '-': return "/./...";
case '!': return "/./../";
case '?': return "/././.";
case ',': return "/././/";
case '0': return "//////";
// enter all the codes here should be exactly same as in letters array
}
}
char decodeMsg(int i){
switch(i){
//make all cases for all the values of i
case 0 :return '\n';
case 1 :return 'A';
case 2 :return 'B';
case 3 :return 'C';
case 4 :return 'D';
case 5 :return 'F';
case 6 :return 'G';
case 7 :return 'H';
case 8 :return 'I';
case 9 :return 'J';
case 10 :return 'K';
case 11 :return 'L';
case 12 :return 'M';
case 13 :return 'N';
case 14 :return 'O';
case 15 :return 'P';
case 16 :return 'Q';
case 17 :return 'R';
case 18 :return 'S';
case 19 :return 'T';
case 20 :return 'U';
case 21 :return 'V';
case 22 :return 'W';
case 23 :return 'X';
case 24 :return 'Y';
case 25 :return 'Z';
case 26 :return '1';
case 27 :return '2';
case 28 :return '3';
case 29 :return '4';
case 30 :return '5';
case 31 :return '6';
case 32 :return '7';
case 33 :return '8';
case 34 :return '9';
case 35 :return '.';
case 36 :return '(';
case 37 :return ')';
case 38 :return '+';
case 39 :return '-';
case 40 :return '!';
case 41 :return '?';
case 42 :return ',';
case 43 :return '0';
//etc...
}
}
void sendCode(char* sequence) //convert the char to the corresponding element in the array
{
Serial.println("Character recevied.");
int i = 0;
while(sequence[i] != '\0') // the symbol \0 is the end of a sentence
{
makeBlink(sequence[i]); //call makeBlink to evaluate if the it is a dot or dash
i++;
}
dela(dotdelay); //the delay between symbols in one occurrence of the array is one unit
}
void dela(int d)
{
uint64_t t = millis();
while((millis()-t)<d);
}
void makeBlink(char dotOrDash)
{
Serial.println("Blinking.....");
digitalWrite(led, HIGH); //turn on the LED
if(dotOrDash == '.')
{
dela(dotdelay); //500 milliseconds
}
else //must be a dash
{
dela(dashdelay); //1500 milliseconds
}
digitalWrite(led, LOW); //turn off the LED
dela(delaybc); //the delay between letters is 3 units
}

84
i2cScanner/i2cScanner.ino Normal file
View File

@ -0,0 +1,84 @@
// --------------------------------------
// i2c_scanner
//
// Version 1
// This program (or code that looks like it)
// can be found in many places.
// For example on the Arduino.cc forum.
// The original author is not know.
// Version 2, Juni 2012, Using Arduino 1.0.1
// Adapted to be as simple as possible by Arduino.cc user Krodal
// Version 3, Feb 26 2013
// V3 by louarnold
// Version 4, March 3, 2013, Using Arduino 1.0.3
// by Arduino.cc user Krodal.
// Changes by louarnold removed.
// Scanning addresses changed from 0...127 to 1...119,
// according to the i2c scanner by Nick Gammon
// http://www.gammon.com.au/forum/?id=10896
// Version 5, March 28, 2013
// As version 4, but address scans now to 127.
// A sensor seems to use address 120.
// Version 6, November 27, 2015.
// Added waiting for the Leonardo serial communication.
//
//
// This sketch tests the standard 7-bit addresses
// Devices with higher bit address might not be seen properly.
//
#include <Wire.h>
void setup()
{
Wire.begin();
Serial.begin(9600);
// while (!Serial); // Leonardo: wait for serial monitor
delay(1000);
Serial.println("\nI2C Scanner");
}
void loop()
{
byte error, address;
int nDevices;
Serial.println("Scanning...");
nDevices = 0;
for(address = 1; address < 127; address++ )
{
// The i2c_scanner uses the return value of
// the Write.endTransmisstion to see if
// a device did acknowledge to the address.
Wire.beginTransmission(address);
error = Wire.endTransmission();
Serial.println(address);
if (error == 0)
{
Serial.print("I2C device found at address 0x");
if (address<16)
Serial.print("0");
Serial.print(address,HEX);
Serial.println(" !");
nDevices++;
}
else if (error==4)
{
Serial.print("Unknow error at address 0x");
if (address<16)
Serial.print("0");
Serial.println(address,HEX);
}
}
if (nDevices == 0)
Serial.println("No I2C devices found\n");
else
Serial.println("done\n");
delay(5000); // wait 5 seconds for next scan
}

1
ir_maze_solver/Readme.md Normal file
View File

@ -0,0 +1 @@
IR based Maze Solver using PID and Flood fill algorithms. Done in my freshman year.

View File

@ -0,0 +1,298 @@
int A[11][11];
int b[6][2]={{6,2},{5,2},{0,0}};
int ch[20][2];int nch=-1;
int nb=6,ib=0,M[18],im;
int ix,iy;
int X,Y,D;
int in[10];
int ma[7]={0,0,0,0,0,0,0};
int mi[7]={0,500,500,0,500,500,0};
int md[]={8,7,9,3,4,5};
int cv;int m,pcv;
float kp=0.19,ki=0.00008,kd=0.05;
int a;
int mov(){
int b=0;int perr;long cerr=0;int pwma=0,pwmb=0,pwmm=180;
while((b==0)||(in[7]==0)&&(in[9]==0)){
takeInput();
if(in[7]==0&&in[9]==0) b=1;
if(in[0]==0&&in[6]==0) pwmm=180;
setValues();
int err = 0 - cv;
cerr+=err;
float pwm = err*kp + cerr*ki + (err-perr)*kd;
perr=err;
pwma=pwmm-pwm;pwmb=pwmm+pwm;
pwma=(pwma>pwmm)?pwmm:pwma;
pwmb=(pwmb>pwmm)?pwmm:pwmb;
pwma=(pwma<0)?0:pwma;
pwmb=(pwmb<0)?0:pwmb;
if(abs(pwm)>100)return 0;
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
speedControl(pwma,pwmb);}
speedControl(0,0);
return in[8];
}
void setup(){
D=2;X=1;Y=1;im=-1;
Serial.begin(9600);
pinMode(13,OUTPUT);pinMode(10,INPUT);
pinMode(11,INPUT);pinMode(12,INPUT);
pinMode(4,OUTPUT);pinMode(5,OUTPUT);//motor B
pinMode(7,OUTPUT);pinMode(8,OUTPUT);//motor A
pinMode(9,OUTPUT);//motor A pwm
pinMode(3,OUTPUT);//motor B pwm
digitalWrite(13,HIGH);
digitalWrite(13,HIGH);
for(int i=0;i<500;i++)
{
takeInput();
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],HIGH);
digitalWrite(md[5],LOW);
speedControl(255,255);
}
for(int i=0;i<1000;i++)
{takeInput();
digitalWrite(md[0],LOW);
digitalWrite(md[1],HIGH);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
speedControl(255,255);
}
while(in[3]==0){
takeInput();
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],HIGH);
digitalWrite(md[5],LOW);
speedControl(255,255);
}
speedControl(0,0);
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
digitalWrite(13,LOW);
ix=0;iy=0;
for(int i=0;i<6;i++){printf("%d,%d\n",b[i][0]+1,b[i][1]+1);}
for(int i=0;i<11;i++){
A[i][0]=1000;A[0][i]=1000;A[10][i]=1000;A[i][10]=1000;
}
mov();
}
void calc(){
for(int i=1;i<10;i++)
for(int j=1;j<10;j++)
if(A[i][j]!=500)
A[i][j]=abs(b[ib][0]-i+1)+abs(b[ib][1]-j+1);
}
void takeInput(){
in[0]=digitalRead(12);
in[1]=analogRead(18);
in[2]=analogRead(19);
in[3]=digitalRead(11);
in[4]=analogRead(20);
in[5]=analogRead(21);
in[6]=digitalRead(10);
for(int i=1;i<6;i++){
if(i==3)continue;
if(in[i]>ma[i])
{ma[i]=in[i];}
else
if(in[i]<mi[i])
mi[i]=in[i];
in[i]=map(in[i],mi[i],ma[i],0,255);
}
in[7]=analogRead(15);in[7]=((in[7]>500)?1:0);
in[8]=analogRead(16);in[8]=((in[8]>500)?1:0);
in[9]=analogRead(17);in[9]=((in[9]>150)?1:0);
}
void setValues(){
if(in[3]==1)m=(-in[1]*3-in[2]+in[4]+in[5]*3);
if((in[1]>60||in[2]>60||in[4]>60||in[5]>60||in[3]==1))
cv =m*in[3]
+(1-in[3])*(((in[1]+in[2])>(in[4]+in[5]))?(m-(+(255-in[1])*3+(255-in[2]))):((255-in[4])+(255-in[5])*3+m));
else cv=1800*(pcv/abs(pcv));
pcv=cv;
}
void turn(int c){
int e=0;
while(e==0||(in[3]==0))
{
takeInput();
if(in[3]==0)e=1;
if(c){
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],HIGH);
digitalWrite(md[5],LOW);
}
else{
digitalWrite(md[0],LOW);
digitalWrite(md[1],HIGH);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
}
speedControl(200,200);
}
if(c){D--;if(D==0)D=4;}
else{D++;if(D==5)D=1;}
speedControl(0,0);
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
}
void loop(){
sp();
if(!go())
{digitalWrite(13,HIGH);
delay(1000);
digitalWrite(13,LOW);
ib++;}
}
int go(){
for(int i=0;i<=im;i++){if(goto_(M[i]))return -1;}
return 0;
}
void setp(int d){
switch(d){
case 1:Y++;break;
case 2:X++;break;
case 3:Y--;break;
case 4:X--;break;
}
}
int goto_(int d){
if(d==D){if(!mov()){setp(D);turn(0);turn(0);mov();ch[++nch][0]=X;ch[nch][1]=Y;A[X][Y]=500;setp(D);return -1;}else {setp(D);return 0;}}
if((abs(d-D)==2)){turn(1);turn(1);if(!mov()){setp(D);turn(0);turn(0);mov();ch[++nch][0]=X;A[X][Y]=500;ch[nch][1]=Y;setp(D);return -1;}else setp(D);return 0;}
if((d==4&&D==1)||(d<D)){turn(1);if(!mov()){setp(D);turn(0);turn(0);mov();ch[++nch][0]=X;A[X][Y]=500;ch[nch][1]=Y;setp(D);return -1;}else setp(D);return 0;}
if((d>D)||(D==4&&d==1)){turn(0);if(!mov()){setp(D);turn(0);turn(0);mov();ch[++nch][0]=X;A[X][Y]=500;ch[nch][1]=Y;setp(D);return -1;}else setp(D);return 0;}
}
void sp(){
ix=X;iy=Y;im=-1;
calc();
int i=0,j=0,k=0;
while(!((b[ib][0]==(ix-1))&&(b[ib][1]==(iy-1)))){
A[ix][iy]+=2;
nextd(min(A[ix][iy+1],min(A[ix-1][iy],min(A[ix+1][iy],A[ix][iy-1]))));
for(k=0;k<nch;k++){
if((ix==ch[k][0])&&(iy==ch[k][1])){
A[ix][iy]=500;
switch(M[im]){
case 1:A[ix][--iy]+=2;break;
case 2:A[--ix][iy]+=2;break;
case 3:A[ix][++iy]+=2;break;
case 4:A[++ix][iy]+=2;break;
}
im--;break;
}
}
}
for(i=1;i<im;i++){
if(abs(M[i]-M[i-1])==2){for(j=i-1;j<=im-2;j++)M[j]=M[j+2];im-=2;i=((i<2)?0:(i-2));}
else if(abs(M[i+1]-M[i-1])==2){M[i-1]=M[i];for(j=i;j<=im-2;j++)M[j]=M[j+2];im-=2;i=((i<2)?0:(i-2));}
}
}
void nextd(int t1){
if(im!=0){
switch(M[im]){
case 1:if(t1==A[ix][iy+1]){iy++;M[++im]=1;return;}break;
case 2:if(t1==A[ix+1][iy]){ix++;M[++im]=2;return;}break;
case 3:if(t1==A[ix][iy-1]){iy--;M[++im]=3;return;}break;
case 4:if(t1==A[ix-1][iy]){ix--;M[++im]=4;return;}break;
}
}
switch(D){
case 1:
if(t1==A[ix][iy+1]){
iy++;M[++im]=1;return;
}
if(t1==A[ix+1][iy]){
ix++;M[++im]=2;return;
}
if(t1==A[ix-1][iy]){
ix--;M[++im]=4;return;
}
if(t1==A[ix][iy-1]){
iy--;M[++im]=3;return;
}break;
case 2:
if(t1==A[ix+1][iy]){
ix++;M[++im]=2;return;
}
if(t1==A[ix][iy+1]){
iy++;M[++im]=1;return;
}
if(t1==A[ix][iy-1]){
iy--;M[++im]=3;return;
}
if(t1==A[ix-1][iy]){
ix--;M[++im]=4;return;
}
break;
case 3:
if(t1==A[ix][iy-1]){
iy--;M[++im]=3;return;
}break;
if(t1==A[ix+1][iy]){
ix++;M[++im]=2;return;
}
if(t1==A[ix-1][iy]){
ix--;M[++im]=4;return;
}
if(t1==A[ix][iy+1]){
iy++;M[++im]=1;return;
}
case 4:
if(t1==A[ix-1][iy]){
ix--;M[++im]=4;return;
}
if(t1==A[ix][iy-1]){
iy--;M[++im]=3;return;
}
if(t1==A[ix][iy+1]){
iy++;M[++im]=1;return;
}
if(t1==A[ix+1][iy]){
ix++;M[++im]=2;return;
}
break;
}
}
void speedControl(int a, int b){
analogWrite(9, map(a,0,255,0,145));
analogWrite(3, map(b,0,255,0,150));
}

View File

@ -0,0 +1,311 @@
int A[11][11];
int b[6][2]={{7,3},{0,0}};
int ch[20][2];int nch=-1;
int nb=2,ib=0,M[18],im;
int ix,iy;
int X,Y,D;
int in[10];
int ma[7]={0,0,0,0,0,0,0};
int mi[7]={0,500,500,0,500,500,0};
int md[]={8,7,9,3,4,5};
int cv;int m,pcv;
float kp=0.19,ki=0.00008,kd=0.05;
int a;
int mov(int aaaa){
long tt=millis();
int b=0;int perr;long cerr=0;int pwma=0,pwmb=0,pwmm=180;
while((b==0)||(in[7]==0)||(in[9]==0)){
takeInput();long tt1=millis();
if(in[7]==0&&in[9]==0) b=1;
if((b==1)&&((in[7]==1)||(in[9]==1))){speedControl(0,0);return in[8];}
if(in[0]==0&&in[6]==0) pwmm=180;
setValues();
int err = 0 - cv;
cerr+=err;
float pwm = err*kp + cerr*ki + (err-perr)*kd;
if(aaaa==0&&abs(pwm)>100&&((tt1-tt)>80)&&((tt1-tt)<1900)){turn(0);D++;if(D==5)D=1;return mov(1);}
perr=err;
pwma=pwmm-pwm;pwmb=pwmm+pwm;
pwma=(pwma>pwmm)?pwmm:pwma;
pwmb=(pwmb>pwmm)?pwmm:pwmb;
pwma=(pwma<0)?0:pwma;
pwmb=(pwmb<0)?0:pwmb;
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
speedControl(pwma,pwmb);}
speedControl(0,0);
return in[8];
}
void setup(){
/*A[1][3]=500;
A[6][3]=500;
A[4][2]=500;
A[3][1]=500;
A[3][6]=500;
A[7][7]=500;
A[2][4]=500;
*/
D=1;X=1;Y=1;im=-1;
Serial.begin(9600);
pinMode(13,OUTPUT);pinMode(10,INPUT);
pinMode(11,INPUT);pinMode(12,INPUT);
pinMode(4,OUTPUT);pinMode(5,OUTPUT);//motor B
pinMode(7,OUTPUT);pinMode(8,OUTPUT);//motor A
pinMode(9,OUTPUT);//motor A pwm
pinMode(3,OUTPUT);//motor B pwm
digitalWrite(13,HIGH);
digitalWrite(13,HIGH);
for(int i=0;i<500;i++)
{
takeInput();
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],HIGH);
digitalWrite(md[5],LOW);
speedControl(255,255);
}
for(int i=0;i<1000;i++)
{takeInput();
digitalWrite(md[0],LOW);
digitalWrite(md[1],HIGH);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
speedControl(255,255);
}
while(in[3]==0){
takeInput();
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],HIGH);
digitalWrite(md[5],LOW);
speedControl(255,255);
}
speedControl(0,0);
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
digitalWrite(13,LOW);
ix=0;iy=0;
for(int i=0;i<6;i++){printf("%d,%d\n",b[i][0]+1,b[i][1]+1);}
for(int i=0;i<11;i++){
A[i][0]=1000;A[0][i]=1000;A[10][i]=1000;A[i][10]=1000;
}
mov(0);
}
void calc(){
for(int i=1;i<10;i++)
for(int j=1;j<10;j++)
if(A[i][j]!=500)
A[i][j]=abs(b[ib][0]-i+1)+abs(b[ib][1]-j+1);
}
void takeInput(){
in[0]=digitalRead(12);
in[1]=analogRead(18);
in[2]=analogRead(19);
in[3]=digitalRead(11);
in[4]=analogRead(20);
in[5]=analogRead(21);
in[6]=digitalRead(10);
for(int i=1;i<6;i++){
if(i==3)continue;
if(in[i]>ma[i])
{ma[i]=in[i];}
else
if(in[i]<mi[i])
mi[i]=in[i];
in[i]=map(in[i],mi[i],ma[i],0,255);
}
in[7]=analogRead(15);in[7]=((in[7]>500)?1:0);
in[8]=analogRead(16);in[8]=((in[8]>500)?1:0);
in[9]=analogRead(17);in[9]=((in[9]>150)?1:0);
}
void setValues(){
if(in[3]==1)m=(-in[1]*3-in[2]+in[4]+in[5]*3);
if((in[1]>60||in[2]>60||in[4]>60||in[5]>60||in[3]==1))
cv =m*in[3]
+(1-in[3])*(((in[1]+in[2])>(in[4]+in[5]))?(m-(+(255-in[1])*3+(255-in[2]))):((255-in[4])+(255-in[5])*3+m));
else cv=1800*(pcv/abs(pcv));
pcv=cv;
}
void turn(int c){
int e=0;
while(e==0||(in[3]==0))
{
takeInput();
if(in[3]==0)e=1;
if(c){
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],HIGH);
digitalWrite(md[5],LOW);
}
else{
digitalWrite(md[0],LOW);
digitalWrite(md[1],HIGH);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
}
speedControl(200,200);
}
if(c){D--;if(D==0)D=4;}
else{D++;if(D==5)D=1;}
speedControl(0,0);
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
}
void loop(){
sp();
if(!go())
for(int i=0;i<50;i++){
digitalWrite(6,HIGH);
delay(100);
digitalWrite(6,LOW);
delay(100);
ib++;}
if(ib==nb)delay(100000);
}
int go(){
for(int i=0;i<=im;i++){if(goto_(M[i]))return -1;}
return 0;
}
void setp(int d){
switch(d){
case 1:Y++;break;
case 2:X++;break;
case 3:Y--;break;
case 4:X--;break;
}
}
int goto_(int d){
int t=0;
if(d==D){if(!(t=mov(0))){setp(D);turn(0);turn(0);mov(0);ch[++nch][0]=X;ch[nch][1]=Y;A[X][Y]=500;setp(D);return -1;}else {if(t==-1)setp(D);return 0;}}
if((abs(d-D)==2)){turn(1);turn(1);if(!(t=mov(0))){setp(D);turn(0);turn(0);mov(0);ch[++nch][0]=X;A[X][Y]=500;ch[nch][1]=Y;setp(D);return -1;}else setp(D);return 0;}
if((d==4&&D==1)||(d<D)){turn(1);if(!(t=mov(0))){setp(D);turn(0);turn(0);mov(0);ch[++nch][0]=X;A[X][Y]=500;ch[nch][1]=Y;setp(D);return -1;}else setp(D);return 0;}
if((d>D)||(D==4&&d==1)){turn(0);if(!(t=mov(0))){setp(D);turn(0);turn(0);mov(0);ch[++nch][0]=X;A[X][Y]=500;ch[nch][1]=Y;setp(D);return -1;}else setp(D);return 0;}
}
void sp(){
ix=X;iy=Y;im=-1;
calc();
int i=0,j=0,k=0;
while(!((b[ib][0]==(ix-1))&&(b[ib][1]==(iy-1)))){
A[ix][iy]+=2;
nextd(min(A[ix][iy+1],min(A[ix-1][iy],min(A[ix+1][iy],A[ix][iy-1]))));
for(k=0;k<nch;k++){
if((ix==ch[k][0])&&(iy==ch[k][1])){
A[ix][iy]=500;
switch(M[im]){
case 1:A[ix][--iy]+=2;break;
case 2:A[--ix][iy]+=2;break;
case 3:A[ix][++iy]+=2;break;
case 4:A[++ix][iy]+=2;break;
}
im--;break;
}
}
}
for(i=1;i<im;i++){
if(abs(M[i]-M[i-1])==2){for(j=i-1;j<=im-2;j++)M[j]=M[j+2];im-=2;i=((i<2)?0:(i-2));}
else if(abs(M[i+1]-M[i-1])==2){M[i-1]=M[i];for(j=i;j<=im-2;j++)M[j]=M[j+2];im-=2;i=((i<2)?0:(i-2));}
}
}
void nextd(int t1){
if(im!=0){
switch(M[im]){
case 1:if(t1==A[ix][iy+1]){iy++;M[++im]=1;return;}break;
case 2:if(t1==A[ix+1][iy]){ix++;M[++im]=2;return;}break;
case 3:if(t1==A[ix][iy-1]){iy--;M[++im]=3;return;}break;
case 4:if(t1==A[ix-1][iy]){ix--;M[++im]=4;return;}break;
}
}
switch(D){
case 1:
if(t1==A[ix][iy+1]){
iy++;M[++im]=1;return;
}
if(t1==A[ix+1][iy]){
ix++;M[++im]=2;return;
}
if(t1==A[ix-1][iy]){
ix--;M[++im]=4;return;
}
if(t1==A[ix][iy-1]){
iy--;M[++im]=3;return;
}break;
case 2:
if(t1==A[ix+1][iy]){
ix++;M[++im]=2;return;
}
if(t1==A[ix][iy+1]){
iy++;M[++im]=1;return;
}
if(t1==A[ix][iy-1]){
iy--;M[++im]=3;return;
}
if(t1==A[ix-1][iy]){
ix--;M[++im]=4;return;
}
break;
case 3:
if(t1==A[ix][iy-1]){
iy--;M[++im]=3;return;
}break;
if(t1==A[ix+1][iy]){
ix++;M[++im]=2;return;
}
if(t1==A[ix-1][iy]){
ix--;M[++im]=4;return;
}
if(t1==A[ix][iy+1]){
iy++;M[++im]=1;return;
}
case 4:
if(t1==A[ix-1][iy]){
ix--;M[++im]=4;return;
}
if(t1==A[ix][iy-1]){
iy--;M[++im]=3;return;
}
if(t1==A[ix][iy+1]){
iy++;M[++im]=1;return;
}
if(t1==A[ix+1][iy]){
ix++;M[++im]=2;return;
}
break;
}
}
void speedControl(int a, int b){
analogWrite(9, map(a,0,255,0,145));
analogWrite(3, map(b,0,255,0,150));
}

View File

@ -0,0 +1,305 @@
int A[11][11];
int b[6][2]={{7,3},{0,0}};
int ch[20][2];int nch=-1;
int nb=2,ib=0,M[18],im;
int ix,iy;
int X,Y,D;
int in[10];
int ma[7]={0,0,0,0,0,0,0};
int mi[7]={0,500,500,0,500,500,0};
int md[]={8,7,9,3,4,5};
int cv;int m,pcv;
float kp=0.19,ki=0.00008,kd=0.05;
int a;
int mov(){long tt=millis();
int bbb=0;int bb1=0;int b=0;int aa=0;int perr;long cerr=0;int pwma=0,pwmb=0,pwmm=180;
while((b==0)||(in[7]==0)||(in[9]==0)){
takeInput();long tt1=millis();int cc=0;
if((in[0]==1)||(in[6]==1)&&((tt1-tt)>100)&&((tt1-tt)<1900)){bbb=1;aa=1;}
if((bbb==1)&&in[7]==1||in[9]==1) bb1=1;
if(bbb!=1&&in[7]==0&&in[9]==0)b=1;
if(bb1==1&&in[7]==0&&in[9]==0)b=1;
if((b==1)&&((in[7]==1)||(in[9]==1))){speedControl(0,0);return in[8];}
if(in[0]==0&&in[6]==0) pwmm=180;
setValues();
int err = 0 - cv;
cerr+=err;
float pwm = err*kp + cerr*ki + (err-perr)*kd;
perr=err;
if(aa==1){pwm=0;aa=0;}
pwma=pwmm-pwm;pwmb=pwmm+pwm;
pwma=(pwma>pwmm)?pwmm:pwma;
pwmb=(pwmb>pwmm)?pwmm:pwmb;
pwma=(pwma<0)?0:pwma;
pwmb=(pwmb<0)?0:pwmb;
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
speedControl(pwma,pwmb);}
speedControl(0,0);
return in[8];
}
void setup(){
D=1;X=1;Y=1;im=-1;
Serial.begin(9600);
pinMode(13,OUTPUT);pinMode(10,INPUT);
pinMode(11,INPUT);pinMode(12,INPUT);
pinMode(4,OUTPUT);pinMode(5,OUTPUT);//motor B
pinMode(7,OUTPUT);pinMode(8,OUTPUT);//motor A
pinMode(9,OUTPUT);//motor A pwm
pinMode(3,OUTPUT);//motor B pwm
digitalWrite(13,HIGH);
digitalWrite(13,HIGH);
for(int i=0;i<500;i++)
{
takeInput();
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],HIGH);
digitalWrite(md[5],LOW);
speedControl(255,255);
}
for(int i=0;i<1000;i++)
{takeInput();
digitalWrite(md[0],LOW);
digitalWrite(md[1],HIGH);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
speedControl(255,255);
}
while(in[3]==0){
takeInput();
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],HIGH);
digitalWrite(md[5],LOW);
speedControl(255,255);
}
speedControl(0,0);
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
digitalWrite(13,LOW);
ix=0;iy=0;
for(int i=0;i<6;i++){printf("%d,%d\n",b[i][0]+1,b[i][1]+1);}
for(int i=0;i<11;i++){
A[i][0]=1000;A[0][i]=1000;A[10][i]=1000;A[i][10]=1000;
}
mov();
}
void calc(){
for(int i=1;i<10;i++)
for(int j=1;j<10;j++)
if(A[i][j]!=500)
A[i][j]=abs(b[ib][0]-i+1)+abs(b[ib][1]-j+1);
}
void takeInput(){
in[0]=digitalRead(12);
in[1]=analogRead(18);
in[2]=analogRead(19);
in[3]=digitalRead(11);
in[4]=analogRead(20);
in[5]=analogRead(21);
in[6]=digitalRead(10);
for(int i=1;i<6;i++){
if(i==3)continue;
if(in[i]>ma[i])
{ma[i]=in[i];}
else
if(in[i]<mi[i])
mi[i]=in[i];
in[i]=map(in[i],mi[i],ma[i],0,255);
}
in[7]=analogRead(15);in[7]=((in[7]>500)?1:0);
in[8]=analogRead(16);in[8]=((in[8]>500)?1:0);
in[9]=analogRead(17);in[9]=((in[9]>150)?1:0);
}
void setValues(){
if(in[3]==1)m=(-in[1]*3-in[2]+in[4]+in[5]*3);
if((in[1]>60||in[2]>60||in[4]>60||in[5]>60||in[3]==1))
cv =m*in[3]
+(1-in[3])*(((in[1]+in[2])>(in[4]+in[5]))?(m-(+(255-in[1])*3+(255-in[2]))):((255-in[4])+(255-in[5])*3+m));
else cv=1800*(pcv/abs(pcv));
pcv=cv;
}
void turn(int c){
int e=0;
while(e==0||(in[3]==0))
{
takeInput();
if(in[3]==0)e=1;
if(c){
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],HIGH);
digitalWrite(md[5],LOW);
}
else{
digitalWrite(md[0],LOW);
digitalWrite(md[1],HIGH);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
}
speedControl(200,200);
}
if(c){D--;if(D==0)D=4;}
else{D++;if(D==5)D=1;}
speedControl(0,0);
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
}
void loop(){
sp();
if(!go())
for(int i=0;i<50;i++){
digitalWrite(6,HIGH);
delay(100);
digitalWrite(6,LOW);
delay(100);
ib++;}
if(ib==nb)delay(100000);
}
int go(){
for(int i=0;i<=im;i++){if(goto_(M[i]))return -1;}
return 0;
}
void setp(int d){
switch(d){
case 1:Y++;break;
case 2:X++;break;
case 3:Y--;break;
case 4:X--;break;
}
}
int goto_(int d){
if(d==D){if(!mov()){setp(D);turn(0);turn(0);mov();ch[++nch][0]=X;ch[nch][1]=Y;A[X][Y]=500;setp(D);return -1;}else {setp(D);return 0;}}
if((abs(d-D)==2)){turn(1);turn(1);if(!mov()){setp(D);turn(0);turn(0);mov();ch[++nch][0]=X;ch[nch][1]=Y;A[X][Y]=500;setp(D);return -1;}else setp(D);return 0;}
if((d==4&&D==1)||(d<D)){turn(1);if(!mov()){setp(D);turn(0);turn(0);mov();ch[++nch][0]=X;ch[nch][1]=Y;A[X][Y]=500;setp(D);return -1;}else setp(D);return 0;}
if((d>D)||(D==4&&d==1)){turn(0);if(!mov()){setp(D);turn(0);turn(0);mov();ch[++nch][0]=X;ch[nch][1]=Y;A[X][Y]=500;setp(D);return -1;}else setp(D);return 0;}
}
void sp(){
ix=X;iy=Y;im=-1;
calc();
int i=0,j=0,k=0;
while(!((b[ib][0]==(ix-1))&&(b[ib][1]==(iy-1)))){
A[ix][iy]+=2;
nextd(min(A[ix][iy+1],min(A[ix-1][iy],min(A[ix+1][iy],A[ix][iy-1]))));
for(k=0;k<nch;k++){
if((ix==ch[k][0])&&(iy==ch[k][1])){
A[ix][iy]=500;
switch(M[im]){
case 1:A[ix][--iy]+=2;break;
case 2:A[--ix][iy]+=2;break;
case 3:A[ix][++iy]+=2;break;
case 4:A[++ix][iy]+=2;break;
}
im--;break;
}
}
}
for(i=1;i<im;i++){
if(abs(M[i]-M[i-1])==2){for(j=i-1;j<=im-2;j++)M[j]=M[j+2];im-=2;i=((i<2)?0:(i-2));}
else if(abs(M[i+1]-M[i-1])==2){M[i-1]=M[i];for(j=i;j<=im-2;j++)M[j]=M[j+2];im-=2;i=((i<2)?0:(i-2));}
}
}
void nextd(int t1){
if(im!=0){
switch(M[im]){
case 1:if(t1==A[ix][iy+1]){iy++;M[++im]=1;return;}break;
case 2:if(t1==A[ix+1][iy]){ix++;M[++im]=2;return;}break;
case 3:if(t1==A[ix][iy-1]){iy--;M[++im]=3;return;}break;
case 4:if(t1==A[ix-1][iy]){ix--;M[++im]=4;return;}break;
}
}
switch(D){
case 1:
if(t1==A[ix][iy+1]){
iy++;M[++im]=1;return;
}
if(t1==A[ix+1][iy]){
ix++;M[++im]=2;return;
}
if(t1==A[ix-1][iy]){
ix--;M[++im]=4;return;
}
if(t1==A[ix][iy-1]){
iy--;M[++im]=3;return;
}break;
case 2:
if(t1==A[ix+1][iy]){
ix++;M[++im]=2;return;
}
if(t1==A[ix][iy+1]){
iy++;M[++im]=1;return;
}
if(t1==A[ix][iy-1]){
iy--;M[++im]=3;return;
}
if(t1==A[ix-1][iy]){
ix--;M[++im]=4;return;
}
break;
case 3:
if(t1==A[ix][iy-1]){
iy--;M[++im]=3;return;
}break;
if(t1==A[ix+1][iy]){
ix++;M[++im]=2;return;
}
if(t1==A[ix-1][iy]){
ix--;M[++im]=4;return;
}
if(t1==A[ix][iy+1]){
iy++;M[++im]=1;return;
}
case 4:
if(t1==A[ix-1][iy]){
ix--;M[++im]=4;return;
}
if(t1==A[ix][iy-1]){
iy--;M[++im]=3;return;
}
if(t1==A[ix][iy+1]){
iy++;M[++im]=1;return;
}
if(t1==A[ix+1][iy]){
ix++;M[++im]=2;return;
}
break;
}
}
void speedControl(int a, int b){
analogWrite(9, map(a,0,255,0,145));
analogWrite(3, map(b,0,255,0,150));
}

View File

@ -0,0 +1,309 @@
int A[11][11];
int b[6][2]={{7,3},{0,0}};
int ch[20][2]={{1,3},{2,4},{3,6},{3,1},{4,2},{6,3},{7,7}};int nch=7;
int nb=2,ib=0,M[18],im;
int ix,iy;
int X,Y,D;
int in[10];
int ma[7]={0,0,0,0,0,0,0};
int mi[7]={0,500,500,0,500,500,0};
int md[]={8,7,9,3,4,5};
int cv;int m,pcv;
float kp=0.19,ki=0.00008,kd=0.05;
int a;
int mov(){
int b=0;int perr;long cerr=0;int pwma=0,pwmb=0,pwmm=180;
while((b==0)||(in[7]==0)||(in[9]==0)){
takeInput();
if(in[7]==0&&in[9]==0) b=1;
if((b==1)&&((in[7]==1)||(in[9]==1))){speedControl(0,0);return in[8];}
if(in[0]==0&&in[6]==0) pwmm=180;
setValues();
int err = 0 - cv;
cerr+=err;
float pwm = err*kp + cerr*ki + (err-perr)*kd;
perr=err;
pwma=pwmm-pwm;pwmb=pwmm+pwm;
pwma=(pwma>pwmm)?pwmm:pwma;
pwmb=(pwmb>pwmm)?pwmm:pwmb;
pwma=(pwma<0)?0:pwma;
pwmb=(pwmb<0)?0:pwmb;
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
speedControl(pwma,pwmb);}
speedControl(0,0);
return in[8];
}
void setup(){
A[1][3]=500;
A[6][3]=500;
A[4][2]=500;
A[3][1]=500;
A[3][6]=500;
A[7][7]=500;
A[2][4]=500;
D=1;X=1;Y=1;im=-1;
Serial.begin(9600);
pinMode(13,OUTPUT);pinMode(10,INPUT);
pinMode(11,INPUT);pinMode(12,INPUT);
pinMode(4,OUTPUT);pinMode(5,OUTPUT);//motor B
pinMode(7,OUTPUT);pinMode(8,OUTPUT);//motor A
pinMode(9,OUTPUT);//motor A pwm
pinMode(3,OUTPUT);//motor B pwm
digitalWrite(13,HIGH);
digitalWrite(13,HIGH);
for(int i=0;i<500;i++)
{
takeInput();
digitalWrite(8,HIGH);
digitalWrite(7,LOW);
digitalWrite(5,HIGH);
digitalWrite(4,LOW);
speedControl(255,255);
}
for(int i=0;i<1000;i++)
{takeInput();
digitalWrite(md[0],LOW);
digitalWrite(md[1],HIGH);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
speedControl(255,255);
}
while(in[3]==0){
takeInput();
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],HIGH);
digitalWrite(md[5],LOW);
speedControl(255,255);
}
speedControl(0,0);
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
digitalWrite(13,LOW);
ix=0;iy=0;
for(int i=0;i<6;i++){printf("%d,%d\n",b[i][0]+1,b[i][1]+1);}
for(int i=0;i<11;i++){
A[i][0]=1000;A[0][i]=1000;A[10][i]=1000;A[i][10]=1000;
}
mov();
}
void calc(){
for(int i=1;i<10;i++)
for(int j=1;j<10;j++)
if(A[i][j]!=500)
A[i][j]=abs(b[ib][0]-i+1)+abs(b[ib][1]-j+1);
}
void takeInput(){
in[0]=digitalRead(12);
in[1]=analogRead(18);
in[2]=analogRead(19);
in[3]=digitalRead(11);
in[4]=analogRead(20);
in[5]=analogRead(21);
in[6]=digitalRead(10);
for(int i=1;i<6;i++){
if(i==3)continue;
if(in[i]>ma[i])
{ma[i]=in[i];}
else
if(in[i]<mi[i])
mi[i]=in[i];
in[i]=map(in[i],mi[i],ma[i],0,255);
}
in[7]=analogRead(15);in[7]=((in[7]>500)?1:0);
in[8]=analogRead(16);in[8]=((in[8]>500)?1:0);
in[9]=analogRead(17);in[9]=((in[9]>150)?1:0);
}
void setValues(){
if(in[3]==1)m=(-in[1]*3-in[2]+in[4]+in[5]*3);
if((in[1]>60||in[2]>60||in[4]>60||in[5]>60||in[3]==1))
cv =m*in[3]
+(1-in[3])*(((in[1]+in[2])>(in[4]+in[5]))?(m-(+(255-in[1])*3+(255-in[2]))):((255-in[4])+(255-in[5])*3+m));
else cv=1800*(pcv/abs(pcv));
pcv=cv;
}
void turn(int c){
int e=0;
while(e==0||(in[3]==0))
{
takeInput();
if(in[3]==0)e=1;
if(c){
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],HIGH);
digitalWrite(md[5],LOW);
}
else{
digitalWrite(md[0],LOW);
digitalWrite(md[1],HIGH);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
}
speedControl(200,200);
}
if(c){D--;if(D==0)D=4;}
else{D++;if(D==5)D=1;}
speedControl(0,0);
digitalWrite(md[0],HIGH);
digitalWrite(md[1],LOW);
digitalWrite(md[4],LOW);
digitalWrite(md[5],HIGH);
}
void loop(){
sp();for(int i=0;i<=im;i++)Serial.println(M[i]);
if(!go())
for(int i=0;i<50;i++){
digitalWrite(6,HIGH);
delay(100);
digitalWrite(6,LOW);
delay(100);
ib++;}
if(ib==nb)delay(100000);
}
int go(){
for(int i=0;i<=im;i++){if(goto_(M[i]))return -1;}
return 0;
}
void setp(int d){
switch(d){
case 1:Y++;break;
case 2:X++;break;
case 3:Y--;break;
case 4:X--;break;
}
}
int goto_(int d){
if(d==D){if(!mov()){setp(D);turn(0);turn(0);mov();ch[++nch][0]=X;ch[nch][1]=Y;A[X][Y]=500;setp(D);return -1;}else {setp(D);return 0;}}
if((abs(d-D)==2)){turn(1);turn(1);if(!mov()){setp(D);turn(0);turn(0);mov();ch[++nch][0]=X;A[X][Y]=500;ch[nch][1]=Y;setp(D);return -1;}else setp(D);return 0;}
if((d==4&&D==1)||(d<D)){turn(1);if(!mov()){setp(D);turn(0);turn(0);mov();ch[++nch][0]=X;A[X][Y]=500;ch[nch][1]=Y;setp(D);return -1;}else setp(D);return 0;}
if((d>D)||(D==4&&d==1)){turn(0);if(!mov()){setp(D);turn(0);turn(0);mov();ch[++nch][0]=X;A[X][Y]=500;ch[nch][1]=Y;setp(D);return -1;}else setp(D);return 0;}
}
void sp(){
ix=X;iy=Y;im=-1;
calc();
int i=0,j=0,k=0;
while(!((b[ib][0]==(ix-1))&&(b[ib][1]==(iy-1)))){
A[ix][iy]+=2;
nextd(min(A[ix][iy+1],min(A[ix-1][iy],min(A[ix+1][iy],A[ix][iy-1]))));
for(k=0;k<nch;k++){
if((ix==ch[k][0])&&(iy==ch[k][1])){
A[ix][iy]=500;
switch(M[im]){
case 1:A[ix][--iy]+=2;break;
case 2:A[--ix][iy]+=2;break;
case 3:A[ix][++iy]+=2;break;
case 4:A[++ix][iy]+=2;break;
}
im--;break;
}
}
}
for(i=1;i<im;i++){
if(abs(M[i]-M[i-1])==2){for(j=i-1;j<=im-2;j++)M[j]=M[j+2];im-=2;i=((i<2)?0:(i-2));}
else if(abs(M[i+1]-M[i-1])==2){M[i-1]=M[i];for(j=i;j<=im-2;j++)M[j]=M[j+2];im-=2;i=((i<2)?0:(i-2));}
}
}
void nextd(int t1){
if(im!=0){
switch(M[im]){
case 1:if(t1==A[ix][iy+1]){iy++;M[++im]=1;return;}break;
case 2:if(t1==A[ix+1][iy]){ix++;M[++im]=2;return;}break;
case 3:if(t1==A[ix][iy-1]){iy--;M[++im]=3;return;}break;
case 4:if(t1==A[ix-1][iy]){ix--;M[++im]=4;return;}break;
}
}
switch(D){
case 1:
if(t1==A[ix][iy+1]){
iy++;M[++im]=1;return;
}
if(t1==A[ix+1][iy]){
ix++;M[++im]=2;return;
}
if(t1==A[ix-1][iy]){
ix--;M[++im]=4;return;
}
if(t1==A[ix][iy-1]){
iy--;M[++im]=3;return;
}break;
case 2:
if(t1==A[ix+1][iy]){
ix++;M[++im]=2;return;
}
if(t1==A[ix][iy+1]){
iy++;M[++im]=1;return;
}
if(t1==A[ix][iy-1]){
iy--;M[++im]=3;return;
}
if(t1==A[ix-1][iy]){
ix--;M[++im]=4;return;
}
break;
case 3:
if(t1==A[ix][iy-1]){
iy--;M[++im]=3;return;
}break;
if(t1==A[ix+1][iy]){
ix++;M[++im]=2;return;
}
if(t1==A[ix-1][iy]){
ix--;M[++im]=4;return;
}
if(t1==A[ix][iy+1]){
iy++;M[++im]=1;return;
}
case 4:
if(t1==A[ix-1][iy]){
ix--;M[++im]=4;return;
}
if(t1==A[ix][iy-1]){
iy--;M[++im]=3;return;
}
if(t1==A[ix][iy+1]){
iy++;M[++im]=1;return;
}
if(t1==A[ix+1][iy]){
ix++;M[++im]=2;return;
}
break;
}
}
void speedControl(int a, int b){
analogWrite(9, a);
analogWrite(3, b);
}

134
libraries/AD7746/AD7746.cpp Normal file
View File

@ -0,0 +1,134 @@
// I2Cdev library collection - AD7746 I2C device class
// Based on Analog Devices AD7746 Datasheet, Revision 0, 2005
// 2012-04-01 by Peteris Skorovs <pskorovs@gmail.com>
//
// This I2C device library is using (and submitted as a part of) Jeff Rowberg's I2Cdevlib library,
// which should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Changelog:
// 2012-04-01 - initial release
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2012 Peteris Skorovs
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
#include "AD7746.h"
/** Default constructor, uses default I2C address.
* @see AD7746_DEFAULT_ADDRESS
*/
AD7746::AD7746() {
devAddr = AD7746_DEFAULT_ADDRESS;
}
/** Specific address constructor.
* @param address I2C address
* @see AD7746_DEFAULT_ADDRESS
* @see AD7746_ADDRESS
*/
AD7746::AD7746(uint8_t address) {
devAddr = address;
}
/** Power on and prepare for general usage.
*/
void AD7746::initialize() {
reset();
}
/** Verify the I2C connection.
* Make sure the device is connected and responds as expected.
* @return True if connection is valid, false otherwise
*/
bool AD7746::testConnection() {
if (I2Cdev::readByte(devAddr, AD7746_RA_STATUS, buffer)) {
return true;
}
return false;
}
void AD7746::reset() {
#ifdef I2CDEV_SERIAL_DEBUG
Serial.print("I2C (0x");
Serial.print(devAddr, HEX);
Serial.print(") resetting");
Serial.print("...");
#endif
#if ((I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO < 100) || I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE)
Wire.beginTransmission(devAddr);
Wire.send((uint8_t) AD7746_RESET); // send reset
#elif (I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO >= 100)
Wire.beginTransmission(devAddr);
Wire.write((uint8_t) AD7746_RESET); // send reset
#endif
#if ((I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO < 100) || I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE)
Wire.endTransmission();
#elif (I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO >= 100)
Wire.endTransmission();
#endif
#ifdef I2CDEV_SERIAL_DEBUG
Serial.println(". Done.");
#endif
delay(1); //wait a tad for reboot
}
uint32_t AD7746::getCapacitance() {
uint32_t capacitance;
I2Cdev::readBytes(devAddr, 0, 4, buffer);
capacitance = ((uint32_t)buffer[1] << 16) | ((uint32_t)buffer[2] << 8) | (uint32_t)buffer[3];
return capacitance;
}
void AD7746::writeCapSetupRegister(uint8_t data) {
I2Cdev::writeByte(devAddr, AD7746_RA_CAP_SETUP, data);
}
void AD7746::writeVtSetupRegister(uint8_t data) {
I2Cdev::writeByte(devAddr, AD7746_RA_VT_SETUP, data);
}
void AD7746::writeExcSetupRegister(uint8_t data) {
I2Cdev::writeByte(devAddr, AD7746_RA_EXC_SETUP, data);
}
void AD7746::writeConfigurationRegister(uint8_t data) {
I2Cdev::writeByte(devAddr, AD7746_RA_CONFIGURATION, data);
}
void AD7746::writeCapDacARegister(uint8_t data) {
I2Cdev::writeByte(devAddr, AD7746_RA_CAP_DAC_A, data);
}
void AD7746::writeCapDacBRegister(uint8_t data) {
I2Cdev::writeByte(devAddr, AD7746_RA_CAP_DAC_B, data);
}

186
libraries/AD7746/AD7746.h Normal file
View File

@ -0,0 +1,186 @@
// I2Cdev library collection - AD7746 I2C device class header file
// Based on Analog Devices AD7746 Datasheet, Revision 0, 2005
// 2012-04-01 by Peteris Skorovs <pskorovs@gmail.com>
//
// This I2C device library is using (and submitted as a part of) Jeff Rowberg's I2Cdevlib library,
// which should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Changelog:
// 2012-04-01 - initial release
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2012 Peteris Skorovs
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
#ifndef _AD7746_H_
#define _AD7746_H_
#include "I2Cdev.h"
#define AD7746_ADDRESS 0x48
#define AD7746_DEFAULT_ADDRESS AD7746_ADDRESS
#define AD7746_RA_STATUS 0x00 // Status
#define AD7746_RA_CAP_DATA_H 0x01 // Cap data
#define AD7746_RA_CAP_DATA_M 0x02 // Cap data
#define AD7746_RA_CAP_DATA_L 0x03 // Cap data
#define AD7746_RA_VT_DATA_H 0x04 // VT data
#define AD7746_RA_VT_DATA_M 0x05 // VT data
#define AD7746_RA_VT_DATA_L 0x06 // VT data
#define AD7746_RA_CAP_SETUP 0x07 // Cap Setup
#define AD7746_RA_VT_SETUP 0x08 // VT Setup
#define AD7746_RA_EXC_SETUP 0x09 // Exc Setup
#define AD7746_RA_CONFIGURATION 0x0A // Configuration
#define AD7746_RA_CAP_DAC_A 0x0B // Cap DAC A
#define AD7746_RA_CAP_DAC_B 0x0C // Cap DAC B
#define AD7746_RA_CAP_OFF_H 0x0D
#define AD7746_RA_CAP_OFF_L 0x0E
#define AD7746_RA_CAP_GAIN_H 0x0F
#define AD7746_RA_CAP_GAIN_L 0x10
#define AD7746_RA_VOLT_GAIN_H 0x11
#define AD7746_RA_VOLT_GAIN_L 0x12
#define AD7746_RESET 0xBF
// Status
#define AD7746_EXCERR_BIT 3
#define AD7746_RDY_BIT 2
#define AD7746_RDYVT_BIT 1
#define AD7746_RDYCAP_BIT 0
// Cap Setup
#define AD7746_CAPEN_BIT 7
#define AD7746_CIN2_BIT 6
#define AD7746_CAPDIFF_BIT 5
#define AD7746_CACHOP_BIT 0
#define AD7746_CAPEN (1 << AD7746_CAPEN_BIT)
#define AD7746_CIN2 (1 << AD7746_CIN2_BIT)
// VT Setup
#define AD7746_VTEN_BIT 7
#define AD7746_VTMD_BIT_1 6
#define AD7746_VTMD_BIT_0 5
#define AD7746_EXTREF_BIT 4
#define AD7746_VTSHORT_BIT 1
#define AD7746_VTCHOP_BIT 0
#define AD7746_VTEN (1 << AD7746_VTEN_BIT)
#define AD7746_VTMD_INT_TEMP 0
#define AD7746_VTMD_EXT_TEMP (1 << AD7746_VTMD_BIT_0)
#define AD7746_VTMD_VDD_MON (1 << AD7746_VTMD_BIT_1)
#define AD7746_VTMD_VIN (1 << AD7746_VTMD_BIT_1) | (1 << AD7746_VTMD_BIT_0)
// Exc Setup
#define AD7746_CLKCTRL_BIT 7
#define AD7746_EXCON_BIT 6
#define AD7746_EXCB_BIT 5
#define AD7746_INV_EXCB_BIT 4
#define AD7746_EXCA_BIT 3
#define AD7746_INV_EXCA_BIT 2
#define AD7746_EXCLVL_BIT_1 1
#define AD7746_EXCLVL_BIT_0 0
#define AD7746_EXCA (1 << AD7746_EXCA_BIT)
#define AD7746_EXCB (1 << AD7746_EXCB_BIT)
#define AD7746_EXCON (1 << AD7746_EXCON_BIT)
#define AD7746_EXCLVL_VDD_X_1_8 0
#define AD7746_EXCLVL_VDD_X_1_4 (1 << AD7746_EXCLVL_BIT_0)
#define AD7746_EXCLVL_VDD_X_3_8 (1 << AD7746_EXCLVL_BIT_1)
#define AD7746_EXCLVL_VDD_X_1_2 (1 << AD7746_EXCLVL_BIT_1) | (1 << AD7746_EXCLVL_BIT_0)
// Configuration
#define AD7746_VTF_BIT_1 7
#define AD7746_VTF_BIT_0 6
#define AD7746_CAPF_BIT_2 5
#define AD7746_CAPF_BIT_1 4
#define AD7746_CAPF_BIT_0 3
#define AD7746_MD_BIT_2 2
#define AD7746_MD_BIT_1 1
#define AD7746_MD_BIT_0 0
#define AD7746_VTF_20P1 0
#define AD7746_VTF_32P1 (1 << AD7746_VTF_BIT_0)
#define AD7746_VTF_62P1 (1 << AD7746_VTF_BIT_1)
#define AD7746_VTF_122P1 (1 << AD7746_VTF_BIT_1) | (1 << AD7746_VTF_BIT_0)
#define AD7746_CAPF_11P0 0
#define AD7746_CAPF_11P9 (1 << AD7746_CAPF_BIT_0)
#define AD7746_CAPF_20P0 (1 << AD7746_CAPF_BIT_1)
#define AD7746_CAPF_38P0 (1 << AD7746_CAPF_BIT_1) | (1 << AD7746_CAPF_BIT_0)
#define AD7746_CAPF_62P0 (1 << AD7746_CAPF_BIT_2)
#define AD7746_CAPF_77P0 (1 << AD7746_CAPF_BIT_2) | (1 << AD7746_CAPF_BIT_0)
#define AD7746_CAPF_92P0 (1 << AD7746_CAPF_BIT_2) | (1 << AD7746_CAPF_BIT_1)
#define AD7746_CAPF_109P6 (1 << AD7746_CAPF_BIT_2) | (1 << AD7746_CAPF_BIT_1) | (1 << AD7746_CAPF_BIT_0)
#define AD7746_MD_IDLE 0
#define AD7746_MD_CONTINUOUS_CONVERSION (1 << AD7746_MD_BIT_0)
#define AD7746_MD_SINGLE_CONVERSION (1 << AD7746_MD_BIT_1)
#define AD7746_MD_POWER_DOWN (1 << AD7746_MD_BIT_1) | (1 << AD7746_MDF_BIT_0)
#define AD7746_MD_OFFSET_CALIBRATION (1 << AD7746_MD_BIT_2) | (1 << AD7746_MD_BIT_0)
#define AD7746_MD_GAIN_CALIBRATION (1 << AD7746_MD_BIT_2) | (1 << AD7746_MD_BIT_1)
// Cap DAC A
#define AD7746_DACAEN_BIT 7
#define AD7746_DACAEN (1 << AD7746_DACAEN_BIT)
// Cap DAC B
#define AD7746_DACBEN_BIT 7
#define AD7746_DACBEN (1 << AD7746_DACBEN_BIT)
#define AD7746_DAC_COEFFICIENT 0.13385826771654F // 17pF/127
class AD7746 {
public:
AD7746();
AD7746(uint8_t address);
void initialize();
bool testConnection();
void reset();
uint32_t getCapacitance();
void writeCapSetupRegister(uint8_t data);
void writeVtSetupRegister(uint8_t data);
void writeExcSetupRegister(uint8_t data);
void writeConfigurationRegister(uint8_t data);
void writeCapDacARegister(uint8_t data);
void writeCapDacBRegister(uint8_t data);
private:
uint8_t devAddr;
uint8_t buffer[19];
};
#endif /* _AD7746_H_ */

View File

@ -0,0 +1,18 @@
{
"name": "I2Cdevlib-AD7746",
"keywords": "capacitance, converter, sensor, i2cdevlib, i2c",
"description": "The AD7745/AD7746 are 24-Bit Capacitance-to-Digital Converter with Temperature Sensor",
"include": "Arduino/AD7746",
"repository":
{
"type": "git",
"url": "https://github.com/jrowberg/i2cdevlib.git"
},
"dependencies":
{
"name": "I2Cdevlib-Core",
"frameworks": "arduino"
},
"frameworks": "arduino",
"platforms": "atmelavr"
}

View File

@ -0,0 +1,649 @@
// I2Cdev library collection - ADS1115 I2C device class
// Based on Texas Instruments ADS1113/4/5 datasheet, May 2009 (SBAS444B, revised October 2009)
// Note that the ADS1115 uses 16-bit registers, not 8-bit registers.
// 8/2/2011 by Jeff Rowberg <jeff@rowberg.net>
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Changelog:
// 2013-05-05 - Add debug information. Rename methods to match datasheet.
// 2011-11-06 - added getVoltage, F. Farzanegan
// 2011-10-29 - added getDifferentialx() methods, F. Farzanegan
// 2011-08-02 - initial release
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2011 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
#include "ADS1115.h"
/** Default constructor, uses default I2C address.
* @see ADS1115_DEFAULT_ADDRESS
*/
ADS1115::ADS1115() {
devAddr = ADS1115_DEFAULT_ADDRESS;
}
/** Specific address constructor.
* @param address I2C address
* @see ADS1115_DEFAULT_ADDRESS
* @see ADS1115_ADDRESS_ADDR_GND
* @see ADS1115_ADDRESS_ADDR_VDD
* @see ADS1115_ADDRESS_ADDR_SDA
* @see ADS1115_ADDRESS_ADDR_SDL
*/
ADS1115::ADS1115(uint8_t address) {
devAddr = address;
}
/** Power on and prepare for general usage.
* This device is ready to use automatically upon power-up. It defaults to
* single-shot read mode, P0/N1 mux, 2.048v gain, 128 samples/sec, default
* comparator with hysterysis, active-low polarity, non-latching comparator,
* and comparater-disabled operation.
*/
void ADS1115::initialize() {
setMultiplexer(ADS1115_MUX_P0_N1);
setGain(ADS1115_PGA_2P048);
setMode(ADS1115_MODE_SINGLESHOT);
setRate(ADS1115_RATE_128);
setComparatorMode(ADS1115_COMP_MODE_HYSTERESIS);
setComparatorPolarity(ADS1115_COMP_POL_ACTIVE_LOW);
setComparatorLatchEnabled(ADS1115_COMP_LAT_NON_LATCHING);
setComparatorQueueMode(ADS1115_COMP_QUE_DISABLE);
}
/** Verify the I2C connection.
* Make sure the device is connected and responds as expected.
* @return True if connection is valid, false otherwise
*/
bool ADS1115::testConnection() {
return I2Cdev::readWord(devAddr, ADS1115_RA_CONVERSION, buffer) == 1;
}
/** Poll the operational status bit until the conversion is finished
* Retry at most 'max_retries' times
* conversion is finished, then return true;
* @see ADS1115_CFG_OS_BIT
* @return True if data is available, false otherwise
*/
bool ADS1115::pollConversion(uint16_t max_retries) {
for(uint16_t i = 0; i < max_retries; i++) {
if (isConversionReady()) return true;
}
return false;
}
/** Read differential value based on current MUX configuration.
* The default MUX setting sets the device to get the differential between the
* AIN0 and AIN1 pins. There are 8 possible MUX settings, but if you are using
* all four input pins as single-end voltage sensors, then the default option is
* not what you want; instead you will need to set the MUX to compare the
* desired AIN* pin with GND. There are shortcut methods (getConversion*) to do
* this conveniently, but you can also do it manually with setMultiplexer()
* followed by this method.
*
* In single-shot mode, this register may not have fresh data. You need to write
* a 1 bit to the MSB of the CONFIG register to trigger a single read/conversion
* before this will be populated with fresh data. This technique is not as
* effortless, but it has enormous potential to save power by only running the
* comparison circuitry when needed.
*
* @param triggerAndPoll If true (and only in singleshot mode) the conversion trigger
* will be executed and the conversion results will be polled.
* @return 16-bit signed differential value
* @see getConversionP0N1();
* @see getConversionPON3();
* @see getConversionP1N3();
* @see getConversionP2N3();
* @see getConversionP0GND();
* @see getConversionP1GND();
* @see getConversionP2GND();
* @see getConversionP3GND);
* @see setMultiplexer();
* @see ADS1115_RA_CONVERSION
* @see ADS1115_MUX_P0_N1
* @see ADS1115_MUX_P0_N3
* @see ADS1115_MUX_P1_N3
* @see ADS1115_MUX_P2_N3
* @see ADS1115_MUX_P0_NG
* @see ADS1115_MUX_P1_NG
* @see ADS1115_MUX_P2_NG
* @see ADS1115_MUX_P3_NG
*/
int16_t ADS1115::getConversion(bool triggerAndPoll) {
if (triggerAndPoll && devMode == ADS1115_MODE_SINGLESHOT) {
triggerConversion();
pollConversion(I2CDEV_DEFAULT_READ_TIMEOUT);
}
I2Cdev::readWord(devAddr, ADS1115_RA_CONVERSION, buffer);
return buffer[0];
}
/** Get AIN0/N1 differential.
* This changes the MUX setting to AIN0/N1 if necessary, triggers a new
* measurement (also only if necessary), then gets the differential value
* currently in the CONVERSION register.
* @return 16-bit signed differential value
* @see getConversion()
*/
int16_t ADS1115::getConversionP0N1() {
if (muxMode != ADS1115_MUX_P0_N1) setMultiplexer(ADS1115_MUX_P0_N1);
return getConversion();
}
/** Get AIN0/N3 differential.
* This changes the MUX setting to AIN0/N3 if necessary, triggers a new
* measurement (also only if necessary), then gets the differential value
* currently in the CONVERSION register.
* @return 16-bit signed differential value
* @see getConversion()
*/
int16_t ADS1115::getConversionP0N3() {
if (muxMode != ADS1115_MUX_P0_N3) setMultiplexer(ADS1115_MUX_P0_N3);
return getConversion();
}
/** Get AIN1/N3 differential.
* This changes the MUX setting to AIN1/N3 if necessary, triggers a new
* measurement (also only if necessary), then gets the differential value
* currently in the CONVERSION register.
* @return 16-bit signed differential value
* @see getConversion()
*/
int16_t ADS1115::getConversionP1N3() {
if (muxMode != ADS1115_MUX_P1_N3) setMultiplexer(ADS1115_MUX_P1_N3);
return getConversion();
}
/** Get AIN2/N3 differential.
* This changes the MUX setting to AIN2/N3 if necessary, triggers a new
* measurement (also only if necessary), then gets the differential value
* currently in the CONVERSION register.
* @return 16-bit signed differential value
* @see getConversion()
*/
int16_t ADS1115::getConversionP2N3() {
if (muxMode != ADS1115_MUX_P2_N3) setMultiplexer(ADS1115_MUX_P2_N3);
return getConversion();
}
/** Get AIN0/GND differential.
* This changes the MUX setting to AIN0/GND if necessary, triggers a new
* measurement (also only if necessary), then gets the differential value
* currently in the CONVERSION register.
* @return 16-bit signed differential value
* @see getConversion()
*/
int16_t ADS1115::getConversionP0GND() {
if (muxMode != ADS1115_MUX_P0_NG) setMultiplexer(ADS1115_MUX_P0_NG);
return getConversion();
}
/** Get AIN1/GND differential.
* This changes the MUX setting to AIN1/GND if necessary, triggers a new
* measurement (also only if necessary), then gets the differential value
* currently in the CONVERSION register.
* @return 16-bit signed differential value
* @see getConversion()
*/
int16_t ADS1115::getConversionP1GND() {
if (muxMode != ADS1115_MUX_P1_NG) setMultiplexer(ADS1115_MUX_P1_NG);
return getConversion();
}
/** Get AIN2/GND differential.
* This changes the MUX setting to AIN2/GND if necessary, triggers a new
* measurement (also only if necessary), then gets the differential value
* currently in the CONVERSION register.
* @return 16-bit signed differential value
* @see getConversion()
*/
int16_t ADS1115::getConversionP2GND() {
if (muxMode != ADS1115_MUX_P2_NG) setMultiplexer(ADS1115_MUX_P2_NG);
return getConversion();
}
/** Get AIN3/GND differential.
* This changes the MUX setting to AIN3/GND if necessary, triggers a new
* measurement (also only if necessary), then gets the differential value
* currently in the CONVERSION register.
* @return 16-bit signed differential value
* @see getConversion()
*/
int16_t ADS1115::getConversionP3GND() {
if (muxMode != ADS1115_MUX_P3_NG) setMultiplexer(ADS1115_MUX_P3_NG);
return getConversion();
}
/** Get the current voltage reading
* Read the current differential and return it multiplied
* by the constant for the current gain. mV is returned to
* increase the precision of the voltage
* @param triggerAndPoll If true (and only in singleshot mode) the conversion trigger
* will be executed and the conversion results will be polled.
*/
float ADS1115::getMilliVolts(bool triggerAndPoll) {
switch (pgaMode) {
case ADS1115_PGA_6P144:
return (getConversion(triggerAndPoll) * ADS1115_MV_6P144);
break;
case ADS1115_PGA_4P096:
return (getConversion(triggerAndPoll) * ADS1115_MV_4P096);
break;
case ADS1115_PGA_2P048:
return (getConversion(triggerAndPoll) * ADS1115_MV_2P048);
break;
case ADS1115_PGA_1P024:
return (getConversion(triggerAndPoll) * ADS1115_MV_1P024);
break;
case ADS1115_PGA_0P512:
return (getConversion(triggerAndPoll) * ADS1115_MV_0P512);
break;
case ADS1115_PGA_0P256:
case ADS1115_PGA_0P256B:
case ADS1115_PGA_0P256C:
return (getConversion(triggerAndPoll) * ADS1115_MV_0P256);
break;
}
}
/**
* Return the current multiplier for the PGA setting.
*
* This may be directly retreived by using getMilliVolts(),
* but this causes an independent read. This function could
* be used to average a number of reads from the getConversion()
* getConversionx() functions and cut downon the number of
* floating-point calculations needed.
*
*/
float ADS1115::getMvPerCount() {
switch (pgaMode) {
case ADS1115_PGA_6P144:
return ADS1115_MV_6P144;
break;
case ADS1115_PGA_4P096:
return ADS1115_MV_4P096;
break;
case ADS1115_PGA_2P048:
return ADS1115_MV_2P048;
break;
case ADS1115_PGA_1P024:
return ADS1115_MV_1P024;
break;
case ADS1115_PGA_0P512:
return ADS1115_MV_0P512;
break;
case ADS1115_PGA_0P256:
case ADS1115_PGA_0P256B:
case ADS1115_PGA_0P256C:
return ADS1115_MV_0P256;
break;
}
}
// CONFIG register
/** Get operational status.
* @return Current operational status (false for active conversion, true for inactive)
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_OS_BIT
*/
bool ADS1115::isConversionReady() {
I2Cdev::readBitW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_OS_BIT, buffer);
return buffer[0];
}
/** Trigger a new conversion.
* Writing to this bit will only have effect while in power-down mode (no conversions active).
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_OS_BIT
*/
void ADS1115::triggerConversion() {
I2Cdev::writeBitW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_OS_BIT, 1);
}
/** Get multiplexer connection.
* @return Current multiplexer connection setting
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_MUX_BIT
* @see ADS1115_CFG_MUX_LENGTH
*/
uint8_t ADS1115::getMultiplexer() {
I2Cdev::readBitsW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_MUX_BIT, ADS1115_CFG_MUX_LENGTH, buffer);
muxMode = (uint8_t)buffer[0];
return muxMode;
}
/** Set multiplexer connection. Continous mode may fill the conversion register
* with data before the MUX setting has taken effect. A stop/start of the conversion
* is done to reset the values.
* @param mux New multiplexer connection setting
* @see ADS1115_MUX_P0_N1
* @see ADS1115_MUX_P0_N3
* @see ADS1115_MUX_P1_N3
* @see ADS1115_MUX_P2_N3
* @see ADS1115_MUX_P0_NG
* @see ADS1115_MUX_P1_NG
* @see ADS1115_MUX_P2_NG
* @see ADS1115_MUX_P3_NG
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_MUX_BIT
* @see ADS1115_CFG_MUX_LENGTH
*/
void ADS1115::setMultiplexer(uint8_t mux) {
if (I2Cdev::writeBitsW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_MUX_BIT, ADS1115_CFG_MUX_LENGTH, mux)) {
muxMode = mux;
if (devMode == ADS1115_MODE_CONTINUOUS) {
// Force a stop/start
setMode(ADS1115_MODE_SINGLESHOT);
getConversion();
setMode(ADS1115_MODE_CONTINUOUS);
}
}
}
/** Get programmable gain amplifier level.
* @return Current programmable gain amplifier level
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_PGA_BIT
* @see ADS1115_CFG_PGA_LENGTH
*/
uint8_t ADS1115::getGain() {
I2Cdev::readBitsW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_PGA_BIT, ADS1115_CFG_PGA_LENGTH, buffer);
pgaMode=(uint8_t)buffer[0];
return pgaMode;
}
/** Set programmable gain amplifier level.
* Continous mode may fill the conversion register
* with data before the gain setting has taken effect. A stop/start of the conversion
* is done to reset the values.
* @param gain New programmable gain amplifier level
* @see ADS1115_PGA_6P144
* @see ADS1115_PGA_4P096
* @see ADS1115_PGA_2P048
* @see ADS1115_PGA_1P024
* @see ADS1115_PGA_0P512
* @see ADS1115_PGA_0P256
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_PGA_BIT
* @see ADS1115_CFG_PGA_LENGTH
*/
void ADS1115::setGain(uint8_t gain) {
if (I2Cdev::writeBitsW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_PGA_BIT, ADS1115_CFG_PGA_LENGTH, gain)) {
pgaMode = gain;
if (devMode == ADS1115_MODE_CONTINUOUS) {
// Force a stop/start
setMode(ADS1115_MODE_SINGLESHOT);
getConversion();
setMode(ADS1115_MODE_CONTINUOUS);
}
}
}
/** Get device mode.
* @return Current device mode
* @see ADS1115_MODE_CONTINUOUS
* @see ADS1115_MODE_SINGLESHOT
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_MODE_BIT
*/
bool ADS1115::getMode() {
I2Cdev::readBitW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_MODE_BIT, buffer);
devMode = buffer[0];
return devMode;
}
/** Set device mode.
* @param mode New device mode
* @see ADS1115_MODE_CONTINUOUS
* @see ADS1115_MODE_SINGLESHOT
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_MODE_BIT
*/
void ADS1115::setMode(bool mode) {
if (I2Cdev::writeBitW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_MODE_BIT, mode)) {
devMode = mode;
}
}
/** Get data rate.
* @return Current data rate
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_DR_BIT
* @see ADS1115_CFG_DR_LENGTH
*/
uint8_t ADS1115::getRate() {
I2Cdev::readBitsW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_DR_BIT, ADS1115_CFG_DR_LENGTH, buffer);
return (uint8_t)buffer[0];
}
/** Set data rate.
* @param rate New data rate
* @see ADS1115_RATE_8
* @see ADS1115_RATE_16
* @see ADS1115_RATE_32
* @see ADS1115_RATE_64
* @see ADS1115_RATE_128
* @see ADS1115_RATE_250
* @see ADS1115_RATE_475
* @see ADS1115_RATE_860
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_DR_BIT
* @see ADS1115_CFG_DR_LENGTH
*/
void ADS1115::setRate(uint8_t rate) {
I2Cdev::writeBitsW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_DR_BIT, ADS1115_CFG_DR_LENGTH, rate);
}
/** Get comparator mode.
* @return Current comparator mode
* @see ADS1115_COMP_MODE_HYSTERESIS
* @see ADS1115_COMP_MODE_WINDOW
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_COMP_MODE_BIT
*/
bool ADS1115::getComparatorMode() {
I2Cdev::readBitW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_COMP_MODE_BIT, buffer);
return buffer[0];
}
/** Set comparator mode.
* @param mode New comparator mode
* @see ADS1115_COMP_MODE_HYSTERESIS
* @see ADS1115_COMP_MODE_WINDOW
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_COMP_MODE_BIT
*/
void ADS1115::setComparatorMode(bool mode) {
I2Cdev::writeBitW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_COMP_MODE_BIT, mode);
}
/** Get comparator polarity setting.
* @return Current comparator polarity setting
* @see ADS1115_COMP_POL_ACTIVE_LOW
* @see ADS1115_COMP_POL_ACTIVE_HIGH
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_COMP_POL_BIT
*/
bool ADS1115::getComparatorPolarity() {
I2Cdev::readBitW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_COMP_POL_BIT, buffer);
return buffer[0];
}
/** Set comparator polarity setting.
* @param polarity New comparator polarity setting
* @see ADS1115_COMP_POL_ACTIVE_LOW
* @see ADS1115_COMP_POL_ACTIVE_HIGH
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_COMP_POL_BIT
*/
void ADS1115::setComparatorPolarity(bool polarity) {
I2Cdev::writeBitW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_COMP_POL_BIT, polarity);
}
/** Get comparator latch enabled value.
* @return Current comparator latch enabled value
* @see ADS1115_COMP_LAT_NON_LATCHING
* @see ADS1115_COMP_LAT_LATCHING
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_COMP_LAT_BIT
*/
bool ADS1115::getComparatorLatchEnabled() {
I2Cdev::readBitW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_COMP_LAT_BIT, buffer);
return buffer[0];
}
/** Set comparator latch enabled value.
* @param enabled New comparator latch enabled value
* @see ADS1115_COMP_LAT_NON_LATCHING
* @see ADS1115_COMP_LAT_LATCHING
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_COMP_LAT_BIT
*/
void ADS1115::setComparatorLatchEnabled(bool enabled) {
I2Cdev::writeBitW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_COMP_LAT_BIT, enabled);
}
/** Get comparator queue mode.
* @return Current comparator queue mode
* @see ADS1115_COMP_QUE_ASSERT1
* @see ADS1115_COMP_QUE_ASSERT2
* @see ADS1115_COMP_QUE_ASSERT4
* @see ADS1115_COMP_QUE_DISABLE
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_COMP_QUE_BIT
* @see ADS1115_CFG_COMP_QUE_LENGTH
*/
uint8_t ADS1115::getComparatorQueueMode() {
I2Cdev::readBitsW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_COMP_QUE_BIT, ADS1115_CFG_COMP_QUE_LENGTH, buffer);
return (uint8_t)buffer[0];
}
/** Set comparator queue mode.
* @param mode New comparator queue mode
* @see ADS1115_COMP_QUE_ASSERT1
* @see ADS1115_COMP_QUE_ASSERT2
* @see ADS1115_COMP_QUE_ASSERT4
* @see ADS1115_COMP_QUE_DISABLE
* @see ADS1115_RA_CONFIG
* @see ADS1115_CFG_COMP_QUE_BIT
* @see ADS1115_CFG_COMP_QUE_LENGTH
*/
void ADS1115::setComparatorQueueMode(uint8_t mode) {
I2Cdev::writeBitsW(devAddr, ADS1115_RA_CONFIG, ADS1115_CFG_COMP_QUE_BIT, ADS1115_CFG_COMP_QUE_LENGTH, mode);
}
// *_THRESH registers
/** Get low threshold value.
* @return Current low threshold value
* @see ADS1115_RA_LO_THRESH
*/
int16_t ADS1115::getLowThreshold() {
I2Cdev::readWord(devAddr, ADS1115_RA_LO_THRESH, buffer);
return buffer[0];
}
/** Set low threshold value.
* @param threshold New low threshold value
* @see ADS1115_RA_LO_THRESH
*/
void ADS1115::setLowThreshold(int16_t threshold) {
I2Cdev::writeWord(devAddr, ADS1115_RA_LO_THRESH, threshold);
}
/** Get high threshold value.
* @return Current high threshold value
* @see ADS1115_RA_HI_THRESH
*/
int16_t ADS1115::getHighThreshold() {
I2Cdev::readWord(devAddr, ADS1115_RA_HI_THRESH, buffer);
return buffer[0];
}
/** Set high threshold value.
* @param threshold New high threshold value
* @see ADS1115_RA_HI_THRESH
*/
void ADS1115::setHighThreshold(int16_t threshold) {
I2Cdev::writeWord(devAddr, ADS1115_RA_HI_THRESH, threshold);
}
/** Configures ALERT/RDY pin as a conversion ready pin.
* It does this by setting the MSB of the high threshold register to '1' and the MSB
* of the low threshold register to '0'. COMP_POL and COMP_QUE bits will be set to '0'.
* Note: ALERT/RDY pin requires a pull up resistor.
*/
void ADS1115::setConversionReadyPinMode() {
I2Cdev::writeBitW(devAddr, ADS1115_RA_HI_THRESH, 15, 1);
I2Cdev::writeBitW(devAddr, ADS1115_RA_LO_THRESH, 15, 0);
setComparatorPolarity(0);
setComparatorQueueMode(0);
}
// Create a mask between two bits
unsigned createMask(unsigned a, unsigned b) {
unsigned mask = 0;
for (unsigned i=a; i<=b; i++)
mask |= 1 << i;
return mask;
}
uint16_t shiftDown(uint16_t extractFrom, int places) {
return (extractFrom >> places);
}
uint16_t getValueFromBits(uint16_t extractFrom, int high, int length) {
int low= high-length +1;
uint16_t mask = createMask(low ,high);
return shiftDown(extractFrom & mask, low);
}
/** Show all the config register settings
*/
void ADS1115::showConfigRegister() {
I2Cdev::readWord(devAddr, ADS1115_RA_CONFIG, buffer);
uint16_t configRegister =buffer[0];
#ifdef ADS1115_SERIAL_DEBUG
Serial.print("Register is:");
Serial.println(configRegister,BIN);
Serial.print("OS:\t");
Serial.println(getValueFromBits(configRegister,
ADS1115_CFG_OS_BIT,1), BIN);
Serial.print("MUX:\t");
Serial.println(getValueFromBits(configRegister,
ADS1115_CFG_MUX_BIT,ADS1115_CFG_MUX_LENGTH), BIN);
Serial.print("PGA:\t");
Serial.println(getValueFromBits(configRegister,
ADS1115_CFG_PGA_BIT,ADS1115_CFG_PGA_LENGTH), BIN);
Serial.print("MODE:\t");
Serial.println(getValueFromBits(configRegister,
ADS1115_CFG_MODE_BIT,1), BIN);
Serial.print("DR:\t");
Serial.println(getValueFromBits(configRegister,
ADS1115_CFG_DR_BIT,ADS1115_CFG_DR_LENGTH), BIN);
Serial.print("CMP_MODE:\t");
Serial.println(getValueFromBits(configRegister,
ADS1115_CFG_COMP_MODE_BIT,1), BIN);
Serial.print("CMP_POL:\t");
Serial.println(getValueFromBits(configRegister,
ADS1115_CFG_COMP_POL_BIT,1), BIN);
Serial.print("CMP_LAT:\t");
Serial.println(getValueFromBits(configRegister,
ADS1115_CFG_COMP_LAT_BIT,1), BIN);
Serial.print("CMP_QUE:\t");
Serial.println(getValueFromBits(configRegister,
ADS1115_CFG_COMP_QUE_BIT,ADS1115_CFG_COMP_QUE_LENGTH), BIN);
#endif
};

200
libraries/ADS1115/ADS1115.h Normal file
View File

@ -0,0 +1,200 @@
// I2Cdev library collection - ADS1115 I2C device class header file
// Based on Texas Instruments ADS1113/4/5 datasheet, May 2009 (SBAS444B, revised October 2009)
// Note that the ADS1115 uses 16-bit registers, not 8-bit registers.
// 8/2/2011 by Jeff Rowberg <jeff@rowberg.net>
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Changelog:
// 2013-05-05 - Add debug information. Clean up Single Shot implementation
// 2011-10-29 - added getDifferentialx() methods, F. Farzanegan
// 2011-08-02 - initial release
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2011 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
#ifndef _ADS1115_H_
#define _ADS1115_H_
#include "I2Cdev.h"
// -----------------------------------------------------------------------------
// Arduino-style "Serial.print" debug constant (uncomment to enable)
// -----------------------------------------------------------------------------
//#define ADS1115_SERIAL_DEBUG
#define ADS1115_ADDRESS_ADDR_GND 0x48 // address pin low (GND)
#define ADS1115_ADDRESS_ADDR_VDD 0x49 // address pin high (VCC)
#define ADS1115_ADDRESS_ADDR_SDA 0x4A // address pin tied to SDA pin
#define ADS1115_ADDRESS_ADDR_SCL 0x4B // address pin tied to SCL pin
#define ADS1115_DEFAULT_ADDRESS ADS1115_ADDRESS_ADDR_GND
#define ADS1115_RA_CONVERSION 0x00
#define ADS1115_RA_CONFIG 0x01
#define ADS1115_RA_LO_THRESH 0x02
#define ADS1115_RA_HI_THRESH 0x03
#define ADS1115_CFG_OS_BIT 15
#define ADS1115_CFG_MUX_BIT 14
#define ADS1115_CFG_MUX_LENGTH 3
#define ADS1115_CFG_PGA_BIT 11
#define ADS1115_CFG_PGA_LENGTH 3
#define ADS1115_CFG_MODE_BIT 8
#define ADS1115_CFG_DR_BIT 7
#define ADS1115_CFG_DR_LENGTH 3
#define ADS1115_CFG_COMP_MODE_BIT 4
#define ADS1115_CFG_COMP_POL_BIT 3
#define ADS1115_CFG_COMP_LAT_BIT 2
#define ADS1115_CFG_COMP_QUE_BIT 1
#define ADS1115_CFG_COMP_QUE_LENGTH 2
#define ADS1115_MUX_P0_N1 0x00 // default
#define ADS1115_MUX_P0_N3 0x01
#define ADS1115_MUX_P1_N3 0x02
#define ADS1115_MUX_P2_N3 0x03
#define ADS1115_MUX_P0_NG 0x04
#define ADS1115_MUX_P1_NG 0x05
#define ADS1115_MUX_P2_NG 0x06
#define ADS1115_MUX_P3_NG 0x07
#define ADS1115_PGA_6P144 0x00
#define ADS1115_PGA_4P096 0x01
#define ADS1115_PGA_2P048 0x02 // default
#define ADS1115_PGA_1P024 0x03
#define ADS1115_PGA_0P512 0x04
#define ADS1115_PGA_0P256 0x05
#define ADS1115_PGA_0P256B 0x06
#define ADS1115_PGA_0P256C 0x07
#define ADS1115_MV_6P144 0.187500
#define ADS1115_MV_4P096 0.125000
#define ADS1115_MV_2P048 0.062500 // default
#define ADS1115_MV_1P024 0.031250
#define ADS1115_MV_0P512 0.015625
#define ADS1115_MV_0P256 0.007813
#define ADS1115_MV_0P256B 0.007813
#define ADS1115_MV_0P256C 0.007813
#define ADS1115_MODE_CONTINUOUS 0x00
#define ADS1115_MODE_SINGLESHOT 0x01 // default
#define ADS1115_RATE_8 0x00
#define ADS1115_RATE_16 0x01
#define ADS1115_RATE_32 0x02
#define ADS1115_RATE_64 0x03
#define ADS1115_RATE_128 0x04 // default
#define ADS1115_RATE_250 0x05
#define ADS1115_RATE_475 0x06
#define ADS1115_RATE_860 0x07
#define ADS1115_COMP_MODE_HYSTERESIS 0x00 // default
#define ADS1115_COMP_MODE_WINDOW 0x01
#define ADS1115_COMP_POL_ACTIVE_LOW 0x00 // default
#define ADS1115_COMP_POL_ACTIVE_HIGH 0x01
#define ADS1115_COMP_LAT_NON_LATCHING 0x00 // default
#define ADS1115_COMP_LAT_LATCHING 0x01
#define ADS1115_COMP_QUE_ASSERT1 0x00
#define ADS1115_COMP_QUE_ASSERT2 0x01
#define ADS1115_COMP_QUE_ASSERT4 0x02
#define ADS1115_COMP_QUE_DISABLE 0x03 // default
// -----------------------------------------------------------------------------
// Arduino-style "Serial.print" debug constant (uncomment to enable)
// -----------------------------------------------------------------------------
//#define ADS1115_SERIAL_DEBUG
class ADS1115 {
public:
ADS1115();
ADS1115(uint8_t address);
void initialize();
bool testConnection();
// SINGLE SHOT utilities
bool pollConversion(uint16_t max_retries);
void triggerConversion();
// Read the current CONVERSION register
int16_t getConversion(bool triggerAndPoll=true);
// Differential
int16_t getConversionP0N1();
int16_t getConversionP0N3();
int16_t getConversionP1N3();
int16_t getConversionP2N3();
// Single-ended
int16_t getConversionP0GND();
int16_t getConversionP1GND();
int16_t getConversionP2GND();
int16_t getConversionP3GND();
// Utility
float getMilliVolts(bool triggerAndPoll=true);
float getMvPerCount();
// CONFIG register
bool isConversionReady();
uint8_t getMultiplexer();
void setMultiplexer(uint8_t mux);
uint8_t getGain();
void setGain(uint8_t gain);
bool getMode();
void setMode(bool mode);
uint8_t getRate();
void setRate(uint8_t rate);
bool getComparatorMode();
void setComparatorMode(bool mode);
bool getComparatorPolarity();
void setComparatorPolarity(bool polarity);
bool getComparatorLatchEnabled();
void setComparatorLatchEnabled(bool enabled);
uint8_t getComparatorQueueMode();
void setComparatorQueueMode(uint8_t mode);
void setConversionReadyPinMode();
// *_THRESH registers
int16_t getLowThreshold();
void setLowThreshold(int16_t threshold);
int16_t getHighThreshold();
void setHighThreshold(int16_t threshold);
// DEBUG
void showConfigRegister();
private:
uint8_t devAddr;
uint16_t buffer[2];
bool devMode;
uint8_t muxMode;
uint8_t pgaMode;
};
#endif /* _ADS1115_H_ */

View File

@ -0,0 +1,91 @@
// I2C device class (I2Cdev) demonstration Arduino sketch for ADS1115 class
// Example of reading two differential inputs of the ADS1115 and showing the value in mV
// 06 May 2013 by Frederick Farzanegan (frederick1@farzanegan.org)
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Changelog:
// 2013-05-13 - initial release
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2011 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
#include "ADS1115.h"
ADS1115 adc0(ADS1115_DEFAULT_ADDRESS);
void setup() {
Wire.begin(); // join I2C bus
Serial.begin(19200); // initialize serial communication
Serial.println("Initializing I2C devices...");
adc0.initialize(); // initialize ADS1115 16 bit A/D chip
Serial.println("Testing device connections...");
Serial.println(adc0.testConnection() ? "ADS1115 connection successful" : "ADS1115 connection failed");
// To get output from this method, you'll need to turn on the
//#define ADS1115_SERIAL_DEBUG // in the ADS1115.h file
adc0.showConfigRegister();
// We're going to do continuous sampling
adc0.setMode(ADS1115_MODE_CONTINUOUS);
}
void loop() {
// Sensor is on P0/N1 (pins 4/5)
Serial.println("Sensor 1 ************************");
// Set the gain (PGA) +/- 1.024v
adc0.setGain(ADS1115_PGA_1P024);
// Get the number of counts of the accumulator
Serial.print("Counts for sensor 1 is:");
// The below method sets the mux and gets a reading.
int sensorOneCounts=adc0.getConversionP0N1(); // counts up to 16-bits
Serial.println(sensorOneCounts);
// To turn the counts into a voltage, we can use
Serial.print("Voltage for sensor 1 is:");
Serial.println(sensorOneCounts*adc0.getMvPerCount());
Serial.println();
// 2nd sensor is on P2/N3 (pins 6/7)
Serial.println("Sensor 2 ************************");
// Set the gain (PGA) +/- 0.256v
adc0.setGain(ADS1115_PGA_0P256);
// Manually set the MUX // could have used the getConversionP* above
adc0.setMultiplexer(ADS1115_MUX_P2_N3);
Serial.print("Counts for sensor 2 is:");
Serial.println(adc0.getConversion());
Serial.print("mVoltage sensor 2 is:");
Serial.println(adc0.getMilliVolts()); // Convenience method to calculate voltage
Serial.println();
delay(500);
}

View File

@ -0,0 +1,110 @@
// I2C device class (I2Cdev) demonstration Arduino sketch for ADS1115 class
// Example of reading two differential inputs of the ADS1115 and showing the value in mV
// 2016-03-22 by Eadf (https://github.com/eadf)
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Changelog:
// 2016-03-22 - initial release
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2011 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
#include "ADS1115.h"
ADS1115 adc0(ADS1115_DEFAULT_ADDRESS);
// Wire ADS1115 ALERT/RDY pin to Arduino pin 2
const int alertReadyPin = 2;
void setup() {
//I2Cdev::begin(); // join I2C bus
Wire.begin();
Serial.begin(115200); // initialize serial communication
Serial.println("Testing device connections...");
Serial.println(adc0.testConnection() ? "ADS1115 connection successful" : "ADS1115 connection failed");
adc0.initialize(); // initialize ADS1115 16 bit A/D chip
// We're going to do single shot sampling
adc0.setMode(ADS1115_MODE_SINGLESHOT);
// Slow things down so that we can see that the "poll for conversion" code works
adc0.setRate(ADS1115_RATE_8);
// Set the gain (PGA) +/- 6.144v
// Note that any analog input must be higher than 0.3V and less than VDD +0.3
adc0.setGain(ADS1115_PGA_6P144);
// ALERT/RDY pin will indicate when conversion is ready
pinMode(alertReadyPin,INPUT_PULLUP);
adc0.setConversionReadyPinMode();
// To get output from this method, you'll need to turn on the
//#define ADS1115_SERIAL_DEBUG // in the ADS1115.h file
#ifdef ADS1115_SERIAL_DEBUG
adc0.showConfigRegister();
Serial.print("HighThreshold="); Serial.println(adc0.getHighThreshold(),BIN);
Serial.print("LowThreshold="); Serial.println(adc0.getLowThreshold(),BIN);
#endif
}
/** Poll the assigned pin for conversion status
*/
void pollAlertReadyPin() {
for (uint32_t i = 0; i<100000; i++)
if (!digitalRead(alertReadyPin)) return;
Serial.println("Failed to wait for AlertReadyPin, it's stuck high!");
}
void loop() {
// The below method sets the mux and gets a reading.
adc0.setMultiplexer(ADS1115_MUX_P0_NG);
adc0.triggerConversion();
pollAlertReadyPin();
Serial.print("A0: "); Serial.print(adc0.getMilliVolts(false)); Serial.print("mV\t");
adc0.setMultiplexer(ADS1115_MUX_P1_NG);
adc0.triggerConversion();
pollAlertReadyPin();
Serial.print("A1: "); Serial.print(adc0.getMilliVolts(false)); Serial.print("mV\t");
adc0.setMultiplexer(ADS1115_MUX_P2_NG);
adc0.triggerConversion();
pollAlertReadyPin();
Serial.print("A2: "); Serial.print(adc0.getMilliVolts(false)); Serial.print("mV\t");
adc0.setMultiplexer(ADS1115_MUX_P3_NG);
// Do conversion polling via I2C on this last reading:
Serial.print("A3: "); Serial.print(adc0.getMilliVolts(true)); Serial.print("mV");
Serial.println(digitalRead(alertReadyPin));
delay(500);
}

View File

@ -0,0 +1,18 @@
{
"name": "I2Cdevlib-ADS1115",
"keywords": "MUX, PGA, comparator, oscillator, reference, i2cdevlib, i2c",
"description": "ADS1115 is 16-Bit ADC with Integrated MUX, PGA, Comparator, Oscillator, and Reference",
"include": "Arduino/ADS1115",
"repository":
{
"type": "git",
"url": "https://github.com/jrowberg/i2cdevlib.git"
},
"dependencies":
{
"name": "I2Cdevlib-Core",
"frameworks": "arduino"
},
"frameworks": "arduino",
"platforms": "atmelavr"
}

File diff suppressed because it is too large Load Diff

361
libraries/ADXL345/ADXL345.h Normal file
View File

@ -0,0 +1,361 @@
// I2Cdev library collection - ADXL345 I2C device class header file
// Based on Analog Devices ADXL345 datasheet rev. C, 5/2011
// 7/31/2011 by Jeff Rowberg <jeff@rowberg.net>
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Changelog:
// 2011-07-31 - initial release
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2011 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
#ifndef _ADXL345_H_
#define _ADXL345_H_
#include "I2Cdev.h"
#define ADXL345_ADDRESS_ALT_LOW 0x53 // alt address pin low (GND)
#define ADXL345_ADDRESS_ALT_HIGH 0x1D // alt address pin high (VCC)
#define ADXL345_DEFAULT_ADDRESS ADXL345_ADDRESS_ALT_LOW
#define ADXL345_RA_DEVID 0x00
#define ADXL345_RA_RESERVED1 0x01
#define ADXL345_RA_THRESH_TAP 0x1D
#define ADXL345_RA_OFSX 0x1E
#define ADXL345_RA_OFSY 0x1F
#define ADXL345_RA_OFSZ 0x20
#define ADXL345_RA_DUR 0x21
#define ADXL345_RA_LATENT 0x22
#define ADXL345_RA_WINDOW 0x23
#define ADXL345_RA_THRESH_ACT 0x24
#define ADXL345_RA_THRESH_INACT 0x25
#define ADXL345_RA_TIME_INACT 0x26
#define ADXL345_RA_ACT_INACT_CTL 0x27
#define ADXL345_RA_THRESH_FF 0x28
#define ADXL345_RA_TIME_FF 0x29
#define ADXL345_RA_TAP_AXES 0x2A
#define ADXL345_RA_ACT_TAP_STATUS 0x2B
#define ADXL345_RA_BW_RATE 0x2C
#define ADXL345_RA_POWER_CTL 0x2D
#define ADXL345_RA_INT_ENABLE 0x2E
#define ADXL345_RA_INT_MAP 0x2F
#define ADXL345_RA_INT_SOURCE 0x30
#define ADXL345_RA_DATA_FORMAT 0x31
#define ADXL345_RA_DATAX0 0x32
#define ADXL345_RA_DATAX1 0x33
#define ADXL345_RA_DATAY0 0x34
#define ADXL345_RA_DATAY1 0x35
#define ADXL345_RA_DATAZ0 0x36
#define ADXL345_RA_DATAZ1 0x37
#define ADXL345_RA_FIFO_CTL 0x38
#define ADXL345_RA_FIFO_STATUS 0x39
#define ADXL345_AIC_ACT_AC_BIT 7
#define ADXL345_AIC_ACT_X_BIT 6
#define ADXL345_AIC_ACT_Y_BIT 5
#define ADXL345_AIC_ACT_Z_BIT 4
#define ADXL345_AIC_INACT_AC_BIT 3
#define ADXL345_AIC_INACT_X_BIT 2
#define ADXL345_AIC_INACT_Y_BIT 1
#define ADXL345_AIC_INACT_Z_BIT 0
#define ADXL345_TAPAXIS_SUP_BIT 3
#define ADXL345_TAPAXIS_X_BIT 2
#define ADXL345_TAPAXIS_Y_BIT 1
#define ADXL345_TAPAXIS_Z_BIT 0
#define ADXL345_TAPSTAT_ACTX_BIT 6
#define ADXL345_TAPSTAT_ACTY_BIT 5
#define ADXL345_TAPSTAT_ACTZ_BIT 4
#define ADXL345_TAPSTAT_ASLEEP_BIT 3
#define ADXL345_TAPSTAT_TAPX_BIT 2
#define ADXL345_TAPSTAT_TAPY_BIT 1
#define ADXL345_TAPSTAT_TAPZ_BIT 0
#define ADXL345_BW_LOWPOWER_BIT 4
#define ADXL345_BW_RATE_BIT 3
#define ADXL345_BW_RATE_LENGTH 4
#define ADXL345_RATE_3200 0b1111
#define ADXL345_RATE_1600 0b1110
#define ADXL345_RATE_800 0b1101
#define ADXL345_RATE_400 0b1100
#define ADXL345_RATE_200 0b1011
#define ADXL345_RATE_100 0b1010
#define ADXL345_RATE_50 0b1001
#define ADXL345_RATE_25 0b1000
#define ADXL345_RATE_12P5 0b0111
#define ADXL345_RATE_6P25 0b0110
#define ADXL345_RATE_3P13 0b0101
#define ADXL345_RATE_1P56 0b0100
#define ADXL345_RATE_0P78 0b0011
#define ADXL345_RATE_0P39 0b0010
#define ADXL345_RATE_0P20 0b0001
#define ADXL345_RATE_0P10 0b0000
#define ADXL345_PCTL_LINK_BIT 5
#define ADXL345_PCTL_AUTOSLEEP_BIT 4
#define ADXL345_PCTL_MEASURE_BIT 3
#define ADXL345_PCTL_SLEEP_BIT 2
#define ADXL345_PCTL_WAKEUP_BIT 1
#define ADXL345_PCTL_WAKEUP_LENGTH 2
#define ADXL345_WAKEUP_8HZ 0b00
#define ADXL345_WAKEUP_4HZ 0b01
#define ADXL345_WAKEUP_2HZ 0b10
#define ADXL345_WAKEUP_1HZ 0b11
#define ADXL345_INT_DATA_READY_BIT 7
#define ADXL345_INT_SINGLE_TAP_BIT 6
#define ADXL345_INT_DOUBLE_TAP_BIT 5
#define ADXL345_INT_ACTIVITY_BIT 4
#define ADXL345_INT_INACTIVITY_BIT 3
#define ADXL345_INT_FREE_FALL_BIT 2
#define ADXL345_INT_WATERMARK_BIT 1
#define ADXL345_INT_OVERRUN_BIT 0
#define ADXL345_FORMAT_SELFTEST_BIT 7
#define ADXL345_FORMAT_SPIMODE_BIT 6
#define ADXL345_FORMAT_INTMODE_BIT 5
#define ADXL345_FORMAT_FULL_RES_BIT 3
#define ADXL345_FORMAT_JUSTIFY_BIT 2
#define ADXL345_FORMAT_RANGE_BIT 1
#define ADXL345_FORMAT_RANGE_LENGTH 2
#define ADXL345_RANGE_2G 0b00
#define ADXL345_RANGE_4G 0b01
#define ADXL345_RANGE_8G 0b10
#define ADXL345_RANGE_16G 0b11
#define ADXL345_FIFO_MODE_BIT 7
#define ADXL345_FIFO_MODE_LENGTH 2
#define ADXL345_FIFO_TRIGGER_BIT 5
#define ADXL345_FIFO_SAMPLES_BIT 4
#define ADXL345_FIFO_SAMPLES_LENGTH 5
#define ADXL345_FIFO_MODE_BYPASS 0b00
#define ADXL345_FIFO_MODE_FIFO 0b01
#define ADXL345_FIFO_MODE_STREAM 0b10
#define ADXL345_FIFO_MODE_TRIGGER 0b11
#define ADXL345_FIFOSTAT_TRIGGER_BIT 7
#define ADXL345_FIFOSTAT_LENGTH_BIT 5
#define ADXL345_FIFOSTAT_LENGTH_LENGTH 6
class ADXL345 {
public:
ADXL345();
ADXL345(uint8_t address);
void initialize();
bool testConnection();
// DEVID register
uint8_t getDeviceID();
// THRESH_TAP register
uint8_t getTapThreshold();
void setTapThreshold(uint8_t threshold);
// OFS* registers
void getOffset(int8_t* x, int8_t* y, int8_t* z);
void setOffset(int8_t x, int8_t y, int8_t z);
int8_t getOffsetX();
void setOffsetX(int8_t x);
int8_t getOffsetY();
void setOffsetY(int8_t y);
int8_t getOffsetZ();
void setOffsetZ(int8_t z);
// DUR register
uint8_t getTapDuration();
void setTapDuration(uint8_t duration);
// LATENT register
uint8_t getDoubleTapLatency();
void setDoubleTapLatency(uint8_t latency);
// WINDOW register
uint8_t getDoubleTapWindow();
void setDoubleTapWindow(uint8_t window);
// THRESH_ACT register
uint8_t getActivityThreshold();
void setActivityThreshold(uint8_t threshold);
// THRESH_INACT register
uint8_t getInactivityThreshold();
void setInactivityThreshold(uint8_t threshold);
// TIME_INACT register
uint8_t getInactivityTime();
void setInactivityTime(uint8_t time);
// ACT_INACT_CTL register
bool getActivityAC();
void setActivityAC(bool enabled);
bool getActivityXEnabled();
void setActivityXEnabled(bool enabled);
bool getActivityYEnabled();
void setActivityYEnabled(bool enabled);
bool getActivityZEnabled();
void setActivityZEnabled(bool enabled);
bool getInactivityAC();
void setInactivityAC(bool enabled);
bool getInactivityXEnabled();
void setInactivityXEnabled(bool enabled);
bool getInactivityYEnabled();
void setInactivityYEnabled(bool enabled);
bool getInactivityZEnabled();
void setInactivityZEnabled(bool enabled);
// THRESH_FF register
uint8_t getFreefallThreshold();
void setFreefallThreshold(uint8_t threshold);
// TIME_FF register
uint8_t getFreefallTime();
void setFreefallTime(uint8_t time);
// TAP_AXES register
bool getTapAxisSuppress();
void setTapAxisSuppress(bool enabled);
bool getTapAxisXEnabled();
void setTapAxisXEnabled(bool enabled);
bool getTapAxisYEnabled();
void setTapAxisYEnabled(bool enabled);
bool getTapAxisZEnabled();
void setTapAxisZEnabled(bool enabled);
// ACT_TAP_STATUS register
bool getActivitySourceX();
bool getActivitySourceY();
bool getActivitySourceZ();
bool getAsleep();
bool getTapSourceX();
bool getTapSourceY();
bool getTapSourceZ();
// BW_RATE register
bool getLowPowerEnabled();
void setLowPowerEnabled(bool enabled);
uint8_t getRate();
void setRate(uint8_t rate);
// POWER_CTL register
bool getLinkEnabled();
void setLinkEnabled(bool enabled);
bool getAutoSleepEnabled();
void setAutoSleepEnabled(bool enabled);
bool getMeasureEnabled();
void setMeasureEnabled(bool enabled);
bool getSleepEnabled();
void setSleepEnabled(bool enabled);
uint8_t getWakeupFrequency();
void setWakeupFrequency(uint8_t frequency);
// INT_ENABLE register
bool getIntDataReadyEnabled();
void setIntDataReadyEnabled(bool enabled);
bool getIntSingleTapEnabled();
void setIntSingleTapEnabled(bool enabled);
bool getIntDoubleTapEnabled();
void setIntDoubleTapEnabled(bool enabled);
bool getIntActivityEnabled();
void setIntActivityEnabled(bool enabled);
bool getIntInactivityEnabled();
void setIntInactivityEnabled(bool enabled);
bool getIntFreefallEnabled();
void setIntFreefallEnabled(bool enabled);
bool getIntWatermarkEnabled();
void setIntWatermarkEnabled(bool enabled);
bool getIntOverrunEnabled();
void setIntOverrunEnabled(bool enabled);
// INT_MAP register
uint8_t getIntDataReadyPin();
void setIntDataReadyPin(uint8_t pin);
uint8_t getIntSingleTapPin();
void setIntSingleTapPin(uint8_t pin);
uint8_t getIntDoubleTapPin();
void setIntDoubleTapPin(uint8_t pin);
uint8_t getIntActivityPin();
void setIntActivityPin(uint8_t pin);
uint8_t getIntInactivityPin();
void setIntInactivityPin(uint8_t pin);
uint8_t getIntFreefallPin();
void setIntFreefallPin(uint8_t pin);
uint8_t getIntWatermarkPin();
void setIntWatermarkPin(uint8_t pin);
uint8_t getIntOverrunPin();
void setIntOverrunPin(uint8_t pin);
// INT_SOURCE register
uint8_t getIntDataReadySource();
uint8_t getIntSingleTapSource();
uint8_t getIntDoubleTapSource();
uint8_t getIntActivitySource();
uint8_t getIntInactivitySource();
uint8_t getIntFreefallSource();
uint8_t getIntWatermarkSource();
uint8_t getIntOverrunSource();
// DATA_FORMAT register
uint8_t getSelfTestEnabled();
void setSelfTestEnabled(uint8_t enabled);
uint8_t getSPIMode();
void setSPIMode(uint8_t mode);
uint8_t getInterruptMode();
void setInterruptMode(uint8_t mode);
uint8_t getFullResolution();
void setFullResolution(uint8_t resolution);
uint8_t getDataJustification();
void setDataJustification(uint8_t justification);
uint8_t getRange();
void setRange(uint8_t range);
// DATA* registers
void getAcceleration(int16_t* x, int16_t* y, int16_t* z);
int16_t getAccelerationX();
int16_t getAccelerationY();
int16_t getAccelerationZ();
// FIFO_CTL register
uint8_t getFIFOMode();
void setFIFOMode(uint8_t mode);
uint8_t getFIFOTriggerInterruptPin();
void setFIFOTriggerInterruptPin(uint8_t interrupt);
uint8_t getFIFOSamples();
void setFIFOSamples(uint8_t size);
// FIFO_STATUS register
bool getFIFOTriggerOccurred();
uint8_t getFIFOLength();
private:
uint8_t devAddr;
uint8_t buffer[6];
};
#endif /* _ADXL345_H_ */

View File

@ -0,0 +1,86 @@
// I2C device class (I2Cdev) demonstration Arduino sketch for ADXL345 class
// 10/7/2011 by Jeff Rowberg <jeff@rowberg.net>
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Changelog:
// 2011-10-07 - initial release
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2011 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
// Arduino Wire library is required if I2Cdev I2CDEV_ARDUINO_WIRE implementation
// is used in I2Cdev.h
#include "Wire.h"
// I2Cdev and ADXL345 must be installed as libraries, or else the .cpp/.h files
// for both classes must be in the include path of your project
#include "I2Cdev.h"
#include "ADXL345.h"
// class default I2C address is 0x53
// specific I2C addresses may be passed as a parameter here
// ALT low = 0x53 (default for SparkFun 6DOF board)
// ALT high = 0x1D
ADXL345 accel;
int16_t ax, ay, az;
#define LED_PIN 13 // (Arduino is 13, Teensy is 6)
bool blinkState = false;
void setup() {
// join I2C bus (I2Cdev library doesn't do this automatically)
Wire.begin();
// initialize serial communication
// (38400 chosen because it works as well at 8MHz as it does at 16MHz, but
// it's really up to you depending on your project)
Serial.begin(38400);
// initialize device
Serial.println("Initializing I2C devices...");
accel.initialize();
// verify connection
Serial.println("Testing device connections...");
Serial.println(accel.testConnection() ? "ADXL345 connection successful" : "ADXL345 connection failed");
// configure LED for output
pinMode(LED_PIN, OUTPUT);
}
void loop() {
// read raw accel measurements from device
accel.getAcceleration(&ax, &ay, &az);
// display tab-separated accel x/y/z values
Serial.print("accel:\t");
Serial.print(ax); Serial.print("\t");
Serial.print(ay); Serial.print("\t");
Serial.println(az);
// blink LED to indicate activity
blinkState = !blinkState;
digitalWrite(LED_PIN, blinkState);
}

View File

@ -0,0 +1,18 @@
{
"name": "I2Cdevlib-ADXL345",
"keywords": "accelerometer, sensor, i2cdevlib, i2c",
"description": "The ADXL345 is a small, thin, ultralow power, 3-axis accelerometer with high resolution (13-bit) measurement",
"include": "Arduino/ADXL345",
"repository":
{
"type": "git",
"url": "https://github.com/jrowberg/i2cdevlib.git"
},
"dependencies":
{
"name": "I2Cdevlib-Core",
"frameworks": "arduino"
},
"frameworks": "arduino",
"platforms": "atmelavr"
}

189
libraries/AK8963/AK8963.cpp Normal file
View File

@ -0,0 +1,189 @@
// I2Cdev library collection - AK8963 I2C device class header file
// Based on AKM AK8963 datasheet, 10/2013
// 8/27/2011 by Jeff Rowberg <jeff@rowberg.net>
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Changelog:
// 2016-01-02 - initial release based on AK8975 code
//
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2011 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
#include "AK8963.h"
/** Default constructor, uses default I2C address.
* @see AK8963_DEFAULT_ADDRESS
*/
AK8963::AK8963() {
devAddr = AK8963_DEFAULT_ADDRESS;
}
/** Specific address constructor.
* @param address I2C address
* @see AK8963_DEFAULT_ADDRESS
* @see AK8963_ADDRESS_00
*/
AK8963::AK8963(uint8_t address) {
devAddr = address;
}
/** Power on and prepare for general usage.
* No specific pre-configuration is necessary for this device.
*/
void AK8963::initialize() {
}
/** Verify the I2C connection.
* Make sure the device is connected and responds as expected.
* @return True if connection is valid, false otherwise
*/
bool AK8963::testConnection() {
if (I2Cdev::readByte(devAddr, AK8963_RA_WIA, buffer) == 1) {
return (buffer[0] == 0x48);
}
return false;
}
// WIA register
uint8_t AK8963::getDeviceID() {
I2Cdev::readByte(devAddr, AK8963_RA_WIA, buffer);
return buffer[0];
}
// INFO register
uint8_t AK8963::getInfo() {
I2Cdev::readByte(devAddr, AK8963_RA_INFO, buffer);
return buffer[0];
}
// ST1 register
bool AK8963::getDataReady() {
I2Cdev::readBit(devAddr, AK8963_RA_ST1, AK8963_ST1_DRDY_BIT, buffer);
return buffer[0];
}
bool AK8963::getDataOverrun() {
I2Cdev::readBit(devAddr, AK8963_RA_ST1, AK8963_ST1_DOR_BIT, buffer);
return buffer[0];
}
// H* registers
void AK8963::getHeading(int16_t *x, int16_t *y, int16_t *z) {
I2Cdev::readBytes(devAddr, AK8963_RA_HXL, 6, buffer);
*x = (((int16_t)buffer[1]) << 8) | buffer[0];
*y = (((int16_t)buffer[3]) << 8) | buffer[2];
*z = (((int16_t)buffer[5]) << 8) | buffer[4];
}
int16_t AK8963::getHeadingX() {
I2Cdev::readBytes(devAddr, AK8963_RA_HXL, 2, buffer);
return (((int16_t)buffer[1]) << 8) | buffer[0];
}
int16_t AK8963::getHeadingY() {
I2Cdev::readBytes(devAddr, AK8963_RA_HYL, 2, buffer);
return (((int16_t)buffer[1]) << 8) | buffer[0];
}
int16_t AK8963::getHeadingZ() {
I2Cdev::readBytes(devAddr, AK8963_RA_HZL, 2, buffer);
return (((int16_t)buffer[1]) << 8) | buffer[0];
}
// ST2 register
bool AK8963::getOverflowStatus() {
I2Cdev::readBit(devAddr, AK8963_RA_ST2, AK8963_ST2_HOFL_BIT, buffer);
return buffer[0];
}
bool AK8963::getOutputBit() {
I2Cdev::readBit(devAddr, AK8963_RA_ST2, AK8963_ST2_BITM_BIT, buffer);
return buffer[0];
}
// CNTL1 register
uint8_t AK8963::getMode() {
I2Cdev::readBits(devAddr, AK8963_RA_CNTL1, AK8963_CNTL1_MODE_BIT, AK8963_CNTL1_MODE_LENGTH, buffer);
return buffer[0];
}
void AK8963::setMode(uint8_t mode) {
I2Cdev::writeBits(devAddr, AK8963_RA_CNTL1, AK8963_CNTL1_MODE_BIT, AK8963_CNTL1_MODE_LENGTH, mode);
}
uint8_t AK8963::getResolution() {
I2Cdev::readBit(devAddr, AK8963_RA_CNTL1, AK8963_CNTL1_RES_BIT, buffer);
return buffer[0];
}
void AK8963::setResolution(uint8_t res) {
I2Cdev::writeBit(devAddr, AK8963_RA_CNTL1, AK8963_CNTL1_RES_BIT, res);
}
// CNTL2 register
void AK8963::reset() {
I2Cdev::writeByte(devAddr, AK8963_RA_CNTL2, AK8963_CNTL2_RESET);
}
// ASTC register
void AK8963::setSelfTest(bool enabled) {
I2Cdev::writeBit(devAddr, AK8963_RA_ASTC, AK8963_ASTC_SELF_BIT, enabled);
}
// I2CDIS
void AK8963::disableI2C() {
I2Cdev::writeByte(devAddr, AK8963_RA_I2CDIS, AK8963_I2CDIS_DISABLE);
}
// ASA* registers
void AK8963::getAdjustment(int8_t *x, int8_t *y, int8_t *z) {
I2Cdev::readBytes(devAddr, AK8963_RA_ASAX, 3, buffer);
*x = buffer[0];
*y = buffer[1];
*z = buffer[2];
}
void AK8963::setAdjustment(int8_t x, int8_t y, int8_t z) {
buffer[0] = x;
buffer[1] = y;
buffer[2] = z;
I2Cdev::writeBytes(devAddr, AK8963_RA_ASAX, 3, buffer);
}
uint8_t AK8963::getAdjustmentX() {
I2Cdev::readByte(devAddr, AK8963_RA_ASAX, buffer);
return buffer[0];
}
void AK8963::setAdjustmentX(uint8_t x) {
I2Cdev::writeByte(devAddr, AK8963_RA_ASAX, x);
}
uint8_t AK8963::getAdjustmentY() {
I2Cdev::readByte(devAddr, AK8963_RA_ASAY, buffer);
return buffer[0];
}
void AK8963::setAdjustmentY(uint8_t y) {
I2Cdev::writeByte(devAddr, AK8963_RA_ASAY, y);
}
uint8_t AK8963::getAdjustmentZ() {
I2Cdev::readByte(devAddr, AK8963_RA_ASAZ, buffer);
return buffer[0];
}
void AK8963::setAdjustmentZ(uint8_t z) {
I2Cdev::writeByte(devAddr, AK8963_RA_ASAZ, z);
}

151
libraries/AK8963/AK8963.h Normal file
View File

@ -0,0 +1,151 @@
// I2Cdev library collection - AK8963 I2C device class header file
// Based on AKM AK8963 datasheet, 10/2013
// 8/27/2011 by Jeff Rowberg <jeff@rowberg.net>
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Changelog:
// 2016-01-02 - initial release based on AK8975 code
//
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2011 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
#ifndef _AK8963_H_
#define _AK8963_H_
#include "I2Cdev.h"
#define AK8963_ADDRESS_00 0x0C
#define AK8963_ADDRESS_01 0x0D
#define AK8963_ADDRESS_10 0x0E
#define AK8963_ADDRESS_11 0x0F
#define AK8963_DEFAULT_ADDRESS AK8963_ADDRESS_00
#define AK8963_RA_WIA 0x00
#define AK8963_RA_INFO 0x01
#define AK8963_RA_ST1 0x02
#define AK8963_RA_HXL 0x03
#define AK8963_RA_HXH 0x04
#define AK8963_RA_HYL 0x05
#define AK8963_RA_HYH 0x06
#define AK8963_RA_HZL 0x07
#define AK8963_RA_HZH 0x08
#define AK8963_RA_ST2 0x09
#define AK8963_RA_CNTL1 0x0A
#define AK8963_RA_CNTL2 0x0B
#define AK8963_RA_ASTC 0x0C
#define AK8963_RA_TS1 0x0D // SHIPMENT TEST, DO NOT USE
#define AK8963_RA_TS2 0x0E // SHIPMENT TEST, DO NOT USE
#define AK8963_RA_I2CDIS 0x0F
#define AK8963_RA_ASAX 0x10
#define AK8963_RA_ASAY 0x11
#define AK8963_RA_ASAZ 0x12
#define AK8963_ST1_DRDY_BIT 0
#define AK8963_ST1_DOR_BIT 1
#define AK8963_ST2_HOFL_BIT 3
#define AK8963_ST2_BITM_BIT 4
#define AK8963_CNTL1_MODE_BIT 3
#define AK8963_CNTL1_MODE_LENGTH 4
#define AK8963_CNTL1_RES_BIT 4
#define AK8963_CNTL2_RESET 0x01
#define AK8963_MODE_POWERDOWN 0x0
#define AK8963_MODE_SINGLE 0x1
#define AK8963_MODE_CONTINUOUS_8HZ 0x2
#define AK8963_MODE_EXTERNAL 0x4
#define AK8963_MODE_CONTINUOUS_100HZ 0x6
#define AK8963_MODE_SELFTEST 0x8
#define AK8963_MODE_FUSEROM 0xF
#define AK8963_RES_14_BIT 0
#define AK8963_RES_16_BIT 1
#define AK8963_CNTL2_SRST_BIT 0
#define AK8963_ASTC_SELF_BIT 6
#define AK8963_I2CDIS_DISABLE 0x1B
class AK8963 {
public:
AK8963();
AK8963(uint8_t address);
void initialize();
bool testConnection();
// WIA register
uint8_t getDeviceID();
// INFO register
uint8_t getInfo();
// ST1 register
bool getDataReady();
bool getDataOverrun();
// H* registers
void getHeading(int16_t *x, int16_t *y, int16_t *z);
int16_t getHeadingX();
int16_t getHeadingY();
int16_t getHeadingZ();
// ST2 register
bool getOverflowStatus();
bool getOutputBit();
// CNTL1 register
uint8_t getMode();
void setMode(uint8_t mode);
uint8_t getResolution();
void setResolution(uint8_t resolution);
void reset();
// ASTC register
void setSelfTest(bool enabled);
// I2CDIS
void disableI2C(); // um, why...?
// ASA* registers
void getAdjustment(int8_t *x, int8_t *y, int8_t *z);
void setAdjustment(int8_t x, int8_t y, int8_t z);
uint8_t getAdjustmentX();
void setAdjustmentX(uint8_t x);
uint8_t getAdjustmentY();
void setAdjustmentY(uint8_t y);
uint8_t getAdjustmentZ();
void setAdjustmentZ(uint8_t z);
private:
uint8_t devAddr;
uint8_t buffer[6];
uint8_t mode;
};
#endif /* _AK8963_H_ */

View File

@ -0,0 +1,20 @@
{
"name": "I2Cdevlib-AK8963",
"keywords": "compass, sensor, i2cdevlib, i2c",
"description": "AK8963 is 3-axis electronic compass IC with high sensitive Hall sensor technology",
"include": "Arduino/AK8963",
"repository":
{
"type": "git",
"url": "https://github.com/jrowberg/i2cdevlib.git"
},
"dependencies":
[
{
"name": "I2Cdevlib-Core",
"frameworks": "arduino"
}
],
"frameworks": "arduino",
"platforms": "atmelavr"
}

Binary file not shown.

182
libraries/AK8975/AK8975.cpp Normal file
View File

@ -0,0 +1,182 @@
// I2Cdev library collection - AK8975 I2C device class header file
// Based on AKM AK8975/B datasheet, 12/2009
// 8/27/2011 by Jeff Rowberg <jeff@rowberg.net>
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Changelog:
// 2011-08-27 - initial release
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2011 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
#include "AK8975.h"
/** Default constructor, uses default I2C address.
* @see AK8975_DEFAULT_ADDRESS
*/
AK8975::AK8975() {
devAddr = AK8975_DEFAULT_ADDRESS;
}
/** Specific address constructor.
* @param address I2C address
* @see AK8975_DEFAULT_ADDRESS
* @see AK8975_ADDRESS_00
*/
AK8975::AK8975(uint8_t address) {
devAddr = address;
}
/** Power on and prepare for general usage.
* No specific pre-configuration is necessary for this device.
*/
void AK8975::initialize() {
}
/** Verify the I2C connection.
* Make sure the device is connected and responds as expected.
* @return True if connection is valid, false otherwise
*/
bool AK8975::testConnection() {
if (I2Cdev::readByte(devAddr, AK8975_RA_WIA, buffer) == 1) {
return (buffer[0] == 0x48);
}
return false;
}
// WIA register
uint8_t AK8975::getDeviceID() {
I2Cdev::readByte(devAddr, AK8975_RA_WIA, buffer);
return buffer[0];
}
// INFO register
uint8_t AK8975::getInfo() {
I2Cdev::readByte(devAddr, AK8975_RA_INFO, buffer);
return buffer[0];
}
// ST1 register
bool AK8975::getDataReady() {
I2Cdev::readBit(devAddr, AK8975_RA_ST1, AK8975_ST1_DRDY_BIT, buffer);
return buffer[0];
}
// H* registers
void AK8975::getHeading(int16_t *x, int16_t *y, int16_t *z) {
I2Cdev::writeByte(devAddr, AK8975_RA_CNTL, AK8975_MODE_SINGLE);
delay(10);
I2Cdev::readBytes(devAddr, AK8975_RA_HXL, 6, buffer);
*x = (((int16_t)buffer[1]) << 8) | buffer[0];
*y = (((int16_t)buffer[3]) << 8) | buffer[2];
*z = (((int16_t)buffer[5]) << 8) | buffer[4];
}
int16_t AK8975::getHeadingX() {
I2Cdev::writeByte(devAddr, AK8975_RA_CNTL, AK8975_MODE_SINGLE);
delay(10);
I2Cdev::readBytes(devAddr, AK8975_RA_HXL, 2, buffer);
return (((int16_t)buffer[1]) << 8) | buffer[0];
}
int16_t AK8975::getHeadingY() {
I2Cdev::writeByte(devAddr, AK8975_RA_CNTL, AK8975_MODE_SINGLE);
delay(10);
I2Cdev::readBytes(devAddr, AK8975_RA_HYL, 2, buffer);
return (((int16_t)buffer[1]) << 8) | buffer[0];
}
int16_t AK8975::getHeadingZ() {
I2Cdev::writeByte(devAddr, AK8975_RA_CNTL, AK8975_MODE_SINGLE);
delay(10);
I2Cdev::readBytes(devAddr, AK8975_RA_HZL, 2, buffer);
return (((int16_t)buffer[1]) << 8) | buffer[0];
}
// ST2 register
bool AK8975::getOverflowStatus() {
I2Cdev::readBit(devAddr, AK8975_RA_ST2, AK8975_ST2_HOFL_BIT, buffer);
return buffer[0];
}
bool AK8975::getDataError() {
I2Cdev::readBit(devAddr, AK8975_RA_ST2, AK8975_ST2_DERR_BIT, buffer);
return buffer[0];
}
// CNTL register
uint8_t AK8975::getMode() {
I2Cdev::readBits(devAddr, AK8975_RA_CNTL, AK8975_CNTL_MODE_BIT, AK8975_CNTL_MODE_LENGTH, buffer);
return buffer[0];
}
void AK8975::setMode(uint8_t mode) {
I2Cdev::writeBits(devAddr, AK8975_RA_CNTL, AK8975_CNTL_MODE_BIT, AK8975_CNTL_MODE_LENGTH, mode);
}
void AK8975::reset() {
I2Cdev::writeBits(devAddr, AK8975_RA_CNTL, AK8975_CNTL_MODE_BIT, AK8975_CNTL_MODE_LENGTH, AK8975_MODE_POWERDOWN);
}
// ASTC register
void AK8975::setSelfTest(bool enabled) {
I2Cdev::writeBit(devAddr, AK8975_RA_ASTC, AK8975_ASTC_SELF_BIT, enabled);
}
// I2CDIS
void AK8975::disableI2C() {
I2Cdev::writeBit(devAddr, AK8975_RA_I2CDIS, AK8975_I2CDIS_BIT, true);
}
// ASA* registers
void AK8975::getAdjustment(int8_t *x, int8_t *y, int8_t *z) {
I2Cdev::readBytes(devAddr, AK8975_RA_ASAX, 3, buffer);
*x = buffer[0];
*y = buffer[1];
*z = buffer[2];
}
void AK8975::setAdjustment(int8_t x, int8_t y, int8_t z) {
buffer[0] = x;
buffer[1] = y;
buffer[2] = z;
I2Cdev::writeBytes(devAddr, AK8975_RA_ASAX, 3, buffer);
}
uint8_t AK8975::getAdjustmentX() {
I2Cdev::readByte(devAddr, AK8975_RA_ASAX, buffer);
return buffer[0];
}
void AK8975::setAdjustmentX(uint8_t x) {
I2Cdev::writeByte(devAddr, AK8975_RA_ASAX, x);
}
uint8_t AK8975::getAdjustmentY() {
I2Cdev::readByte(devAddr, AK8975_RA_ASAY, buffer);
return buffer[0];
}
void AK8975::setAdjustmentY(uint8_t y) {
I2Cdev::writeByte(devAddr, AK8975_RA_ASAY, y);
}
uint8_t AK8975::getAdjustmentZ() {
I2Cdev::readByte(devAddr, AK8975_RA_ASAZ, buffer);
return buffer[0];
}
void AK8975::setAdjustmentZ(uint8_t z) {
I2Cdev::writeByte(devAddr, AK8975_RA_ASAZ, z);
}

View File

@ -0,0 +1,182 @@
// I2Cdev library collection - AK8975 I2C device class header file
// Based on AKM AK8975/B datasheet, 12/2009
// 8/27/2011 by Jeff Rowberg <jeff@rowberg.net>
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Changelog:
// 2011-08-27 - initial release
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2011 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
#include "AK8975.h"
/** Default constructor, uses default I2C address.
* @see AK8975_DEFAULT_ADDRESS
*/
AK8975::AK8975() {
devAddr = AK8975_DEFAULT_ADDRESS;
}
/** Specific address constructor.
* @param address I2C address
* @see AK8975_DEFAULT_ADDRESS
* @see AK8975_ADDRESS_00
*/
AK8975::AK8975(uint8_t address) {
devAddr = address;
}
/** Power on and prepare for general usage.
* No specific pre-configuration is necessary for this device.
*/
void AK8975::initialize() {
}
/** Verify the I2C connection.
* Make sure the device is connected and responds as expected.
* @return True if connection is valid, false otherwise
*/
bool AK8975::testConnection() {
if (I2Cdev::readByte(devAddr, AK8975_RA_WIA, buffer) == 1) {
return (buffer[0] == 0x48);
}
return false;
}
// WIA register
uint8_t AK8975::getDeviceID() {
I2Cdev::readByte(devAddr, AK8975_RA_WIA, buffer);
return buffer[0];
}
// INFO register
uint8_t AK8975::getInfo() {
I2Cdev::readByte(devAddr, AK8975_RA_INFO, buffer);
return buffer[0];
}
// ST1 register
bool AK8975::getDataReady() {
I2Cdev::readBit(devAddr, AK8975_RA_ST1, AK8975_ST1_DRDY_BIT, buffer);
return buffer[0];
}
// H* registers
void AK8975::getHeading(int16_t *x, int16_t *y, int16_t *z) {
I2Cdev::writeByte(devAddr, AK8975_RA_CNTL, AK8975_MODE_SINGLE);
delay(8);
I2Cdev::readBytes(devAddr, AK8975_RA_HXL, 6, buffer);
*x = (((int16_t)buffer[1]) << 8) | buffer[0];
*y = (((int16_t)buffer[3]) << 8) | buffer[2];
*z = (((int16_t)buffer[5]) << 8) | buffer[4];
}
int16_t AK8975::getHeadingX() {
I2Cdev::writeByte(devAddr, AK8975_RA_CNTL, AK8975_MODE_SINGLE);
delay(10);
I2Cdev::readBytes(devAddr, AK8975_RA_HXL, 2, buffer);
return (((int16_t)buffer[1]) << 8) | buffer[0];
}
int16_t AK8975::getHeadingY() {
I2Cdev::writeByte(devAddr, AK8975_RA_CNTL, AK8975_MODE_SINGLE);
delay(10);
I2Cdev::readBytes(devAddr, AK8975_RA_HYL, 2, buffer);
return (((int16_t)buffer[1]) << 8) | buffer[0];
}
int16_t AK8975::getHeadingZ() {
I2Cdev::writeByte(devAddr, AK8975_RA_CNTL, AK8975_MODE_SINGLE);
delay(10);
I2Cdev::readBytes(devAddr, AK8975_RA_HZL, 2, buffer);
return (((int16_t)buffer[1]) << 8) | buffer[0];
}
// ST2 register
bool AK8975::getOverflowStatus() {
I2Cdev::readBit(devAddr, AK8975_RA_ST2, AK8975_ST2_HOFL_BIT, buffer);
return buffer[0];
}
bool AK8975::getDataError() {
I2Cdev::readBit(devAddr, AK8975_RA_ST2, AK8975_ST2_DERR_BIT, buffer);
return buffer[0];
}
// CNTL register
uint8_t AK8975::getMode() {
I2Cdev::readBits(devAddr, AK8975_RA_CNTL, AK8975_CNTL_MODE_BIT, AK8975_CNTL_MODE_LENGTH, buffer);
return buffer[0];
}
void AK8975::setMode(uint8_t mode) {
I2Cdev::writeBits(devAddr, AK8975_RA_CNTL, AK8975_CNTL_MODE_BIT, AK8975_CNTL_MODE_LENGTH, mode);
}
void AK8975::reset() {
I2Cdev::writeBits(devAddr, AK8975_RA_CNTL, AK8975_CNTL_MODE_BIT, AK8975_CNTL_MODE_LENGTH, AK8975_MODE_POWERDOWN);
}
// ASTC register
void AK8975::setSelfTest(bool enabled) {
I2Cdev::writeBit(devAddr, AK8975_RA_ASTC, AK8975_ASTC_SELF_BIT, enabled);
}
// I2CDIS
void AK8975::disableI2C() {
I2Cdev::writeBit(devAddr, AK8975_RA_I2CDIS, AK8975_I2CDIS_BIT, true);
}
// ASA* registers
void AK8975::getAdjustment(int8_t *x, int8_t *y, int8_t *z) {
I2Cdev::readBytes(devAddr, AK8975_RA_ASAX, 3, buffer);
*x = buffer[0];
*y = buffer[1];
*z = buffer[2];
}
void AK8975::setAdjustment(int8_t x, int8_t y, int8_t z) {
buffer[0] = x;
buffer[1] = y;
buffer[2] = z;
I2Cdev::writeBytes(devAddr, AK8975_RA_ASAX, 3, buffer);
}
uint8_t AK8975::getAdjustmentX() {
I2Cdev::readByte(devAddr, AK8975_RA_ASAX, buffer);
return buffer[0];
}
void AK8975::setAdjustmentX(uint8_t x) {
I2Cdev::writeByte(devAddr, AK8975_RA_ASAX, x);
}
uint8_t AK8975::getAdjustmentY() {
I2Cdev::readByte(devAddr, AK8975_RA_ASAY, buffer);
return buffer[0];
}
void AK8975::setAdjustmentY(uint8_t y) {
I2Cdev::writeByte(devAddr, AK8975_RA_ASAY, y);
}
uint8_t AK8975::getAdjustmentZ() {
I2Cdev::readByte(devAddr, AK8975_RA_ASAZ, buffer);
return buffer[0];
}
void AK8975::setAdjustmentZ(uint8_t z) {
I2Cdev::writeByte(devAddr, AK8975_RA_ASAZ, z);
}

135
libraries/AK8975/AK8975.h Normal file
View File

@ -0,0 +1,135 @@
// I2Cdev library collection - AK8975 I2C device class header file
// Based on AKM AK8975/B datasheet, 12/2009
// 8/27/2011 by Jeff Rowberg <jeff@rowberg.net>
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Changelog:
// 2011-08-27 - initial release
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2011 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
#ifndef _AK8975_H_
#define _AK8975_H_
#include "I2Cdev.h"
#define AK8975_ADDRESS_00 0x0C
#define AK8975_ADDRESS_01 0x0D
#define AK8975_ADDRESS_10 0x0E // default for InvenSense MPU-6050 evaluation board
#define AK8975_ADDRESS_11 0x0F
#define AK8975_DEFAULT_ADDRESS AK8975_ADDRESS_00
#define AK8975_RA_WIA 0x00
#define AK8975_RA_INFO 0x01
#define AK8975_RA_ST1 0x02
#define AK8975_RA_HXL 0x03
#define AK8975_RA_HXH 0x04
#define AK8975_RA_HYL 0x05
#define AK8975_RA_HYH 0x06
#define AK8975_RA_HZL 0x07
#define AK8975_RA_HZH 0x08
#define AK8975_RA_ST2 0x09
#define AK8975_RA_CNTL 0x0A
#define AK8975_RA_RSV 0x0B // RESERVED, DO NOT USE
#define AK8975_RA_ASTC 0x0C
#define AK8975_RA_TS1 0x0D // SHIPMENT TEST, DO NOT USE
#define AK8975_RA_TS2 0x0E // SHIPMENT TEST, DO NOT USE
#define AK8975_RA_I2CDIS 0x0F
#define AK8975_RA_ASAX 0x10
#define AK8975_RA_ASAY 0x11
#define AK8975_RA_ASAZ 0x12
#define AK8975_ST1_DRDY_BIT 0
#define AK8975_ST2_HOFL_BIT 3
#define AK8975_ST2_DERR_BIT 2
#define AK8975_CNTL_MODE_BIT 3
#define AK8975_CNTL_MODE_LENGTH 4
#define AK8975_MODE_POWERDOWN 0x0
#define AK8975_MODE_SINGLE 0x1
#define AK8975_MODE_SELFTEST 0x8
#define AK8975_MODE_FUSEROM 0xF
#define AK8975_ASTC_SELF_BIT 6
#define AK8975_I2CDIS_BIT 0
class AK8975 {
public:
AK8975();
AK8975(uint8_t address);
void initialize();
bool testConnection();
// WIA register
uint8_t getDeviceID();
// INFO register
uint8_t getInfo();
// ST1 register
bool getDataReady();
// H* registers
void getHeading(int16_t *x, int16_t *y, int16_t *z);
int16_t getHeadingX();
int16_t getHeadingY();
int16_t getHeadingZ();
// ST2 register
bool getOverflowStatus();
bool getDataError();
// CNTL register
uint8_t getMode();
void setMode(uint8_t mode);
void reset();
// ASTC register
void setSelfTest(bool enabled);
// I2CDIS
void disableI2C(); // um, why...?
// ASA* registers
void getAdjustment(int8_t *x, int8_t *y, int8_t *z);
void setAdjustment(int8_t x, int8_t y, int8_t z);
uint8_t getAdjustmentX();
void setAdjustmentX(uint8_t x);
uint8_t getAdjustmentY();
void setAdjustmentY(uint8_t y);
uint8_t getAdjustmentZ();
void setAdjustmentZ(uint8_t z);
private:
uint8_t devAddr;
uint8_t buffer[6];
uint8_t mode;
};
#endif /* _AK8975_H_ */

View File

@ -0,0 +1,118 @@
// I2C device class (I2Cdev) demonstration Arduino sketch for AK8975 class
// 6/11/2012 by Jeff Rowberg <jeff@rowberg.net>
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// This example uses the AK8975 as mounted on the InvenSense MPU-6050 Evaluation
// Board, and as such also depends (minimally) on the MPU6050 library from the
// I2Cdevlib collection. It initializes the MPU6050 and immediately enables its
// "I2C Bypass" mode, which allows the sketch to communicate with the AK8975
// that is attached to the MPU's AUX SDA/SCL lines. The AK8975 is configured on
// this board to use the 0x0E address.
//
// Note that this small demo does not make use of any of the MPU's amazing
// motion processing capabilities (the DMP); it only provides raw sensor access
// to the compass as mounted on that particular evaluation board.
//
// For more info on the MPU-6050 and some more impressive demos, check out the
// device page on the I2Cdevlib website:
// http://www.i2cdevlib.com/devices/mpu6050
//
// Changelog:
// 2012-06-11 - initial release
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2012 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
// Arduino Wire library is required if I2Cdev I2CDEV_ARDUINO_WIRE implementation
// is used in I2Cdev.h
#include "Wire.h"
// I2Cdev, AK8975, and MPU6050 must be installed as libraries, or else the
// .cpp/.h files for all classes must be in the include path of your project
#include "I2Cdev.h"
#include "AK8975.h"
#include "MPU6050.h"
// class default I2C address is 0x0C
// specific I2C addresses may be passed as a parameter here
// Addr pins low/low = 0x0C
// Addr pins low/high = 0x0D
// Addr pins high/low = 0x0E (default for InvenSense MPU6050 evaluation board)
// Addr pins high/high = 0x0F
AK8975 mag(0x0C);
MPU6050 accelgyro; // address = 0x68, the default, on MPU6050 EVB
int16_t mx, my, mz;
float heading;
#define LED_PIN 13
bool blinkState = false;
void setup() {
// join I2C bus (I2Cdev library doesn't do this automatically)
Wire.begin();
// initialize serial communication
// (38400 chosen because it works as well at 8MHz as it does at 16MHz, but
// it's really up to you depending on your project)
Serial.begin(38400);
// initialize devices
Serial.println("Initializing I2C devices...");
// initialize MPU first so we can connect the AUX lines
accelgyro.initialize();
accelgyro.setI2CBypassEnabled(true);
mag.initialize();
// verify connection
Serial.println("Testing device connections...");
Serial.println(mag.testConnection() ? "AK8975 connection successful" : "AK8975 connection failed");
// configure Arduino LED for
pinMode(LED_PIN, OUTPUT);
}
void loop() {
// read raw heading measurements from device
mag.getHeading(&mx, &my, &mz);
// display tab-separated magnetometer x/y/z values
Serial.print("mag:\t");
Serial.print(mx); Serial.print("\t");
Serial.print(my); Serial.print("\t");
Serial.print(mz); Serial.print("\t\t");
heading = atan2((double)my, (double)mx) * 180.0/3.14159265 + 180;
while (heading < 0) heading += 360;
while (heading > 360) heading -= 360;
Serial.print(heading);
Serial.println(" degrees");
// blink LED to indicate activity
blinkState = !blinkState;
digitalWrite(LED_PIN, blinkState);
delay(100); // run at ~10 Hz
}

View File

@ -0,0 +1,109 @@
// I2C device class (I2Cdev) demonstration Arduino sketch for AK8975 class
// 10/7/2011 by Jeff Rowberg <jeff@rowberg.net>
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// This example uses the AK8975 as mounted on the InvenSense MPU-6050 Evaluation
// Board, and as such also depends (minimally) on the MPU6050 library from the
// I2Cdevlib collection. It initializes the MPU6050 and immediately enables its
// "I2C Bypass" mode, which allows the sketch to communicate with the AK8975
// that is attached to the MPU's AUX SDA/SCL lines. The AK8975 is configured on
// this board to use the 0x0E address.
//
// Note that this small demo does not make use of any of the MPU's amazing
// motion processing capabilities (the DMP); it only provides raw sensor access
// to the compass as mounted on that particular evaluation board.
//
// For more info on the MPU-6050 and some more impressive demos, check out the
// device page on the I2Cdevlib website:
// http://www.i2cdevlib.com/devices/mpu6050
//
// Changelog:
// 2011-10-07 - initial release
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2011 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
// Arduino Wire library is required if I2Cdev I2CDEV_ARDUINO_WIRE implementation
// is used in I2Cdev.h
#include "Wire.h"
// I2Cdev, AK8975, and MPU6050 must be installed as libraries, or else the
// .cpp/.h files for all classes must be in the include path of your project
#include "I2Cdev.h"
#include "AK8975.h"
#include "MPU6050.h"
// class default I2C address is 0x0C
// specific I2C addresses may be passed as a parameter here
// Addr pins low/low = 0x0C
// Addr pins low/high = 0x0D
// Addr pins high/low = 0x0E (default for InvenSense MPU6050 evaluation board)
// Addr pins high/high = 0x0F
AK8975 mag(0x0E);
MPU6050 accelgyro; // address = 0x68, the default, on MPU6050 EVB
int16_t mx, my, mz;
#define LED_PIN 13
bool blinkState = false;
void setup() {
// join I2C bus (I2Cdev library doesn't do this automatically)
Wire.begin();
// initialize serial communication
// (38400 chosen because it works as well at 8MHz as it does at 16MHz, but
// it's really up to you depending on your project)
Serial.begin(38400);
// initialize devices
Serial.println("Initializing I2C devices...");
// initialize MPU first so we can switch to the AUX lines
accelgyro.initialize();
accelgyro.setI2CBypassEnabled(true);
mag.initialize();
// verify connection
Serial.println("Testing device connections...");
Serial.println(mag.testConnection() ? "AK8975 connection successful" : "AK8975 connection failed");
// configure Arduino LED for
pinMode(LED_PIN, OUTPUT);
}
void loop() {
// read raw heading measurements from device
mag.getHeading(&mx, &my, &mz);
// display tab-separated gyro x/y/z values
Serial.print("mag:\t");
Serial.print(mx); Serial.print("\t");
Serial.print(my); Serial.print("\t");
Serial.println(mz);
// blink LED to indicate activity
blinkState = !blinkState;
digitalWrite(LED_PIN, blinkState);
}

View File

@ -0,0 +1,88 @@
// I2C device class (I2Cdev) demonstration Arduino sketch for AK8975 class
// 10/7/2011 by Jeff Rowberg <jeff@rowberg.net>
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Changelog:
// 2011-10-07 - initial release
/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2011 Jeff Rowberg
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
===============================================
*/
// Arduino Wire library is required if I2Cdev I2CDEV_ARDUINO_WIRE implementation
// is used in I2Cdev.h
#include "Wire.h"
// I2Cdev and AK8975 must be installed as libraries, or else the .cpp/.h files
// for both classes must be in the include path of your project
#include "I2Cdev.h"
#include "AK8975.h"
// class default I2C address is 0x0C
// specific I2C addresses may be passed as a parameter here
// Addr pins low/low = 0x0C
// Addr pins low/high = 0x0D
// Addr pins high/low = 0x0E (default for InvenSense MPU6050 evaluation board)
// Addr pins high/high = 0x0F
AK8975 mag;
int16_t mx, my, mz;
#define LED_PIN 13
bool blinkState = false;
void setup() {
// join I2C bus (I2Cdev library doesn't do this automatically)
Wire.begin();
// initialize serial communication
// (38400 chosen because it works as well at 8MHz as it does at 16MHz, but
// it's really up to you depending on your project)
Serial.begin(38400);
// initialize device
Serial.println("Initializing I2C devices...");
mag.initialize();
// verify connection
Serial.println("Testing device connections...");
Serial.println(mag.testConnection() ? "AK8975 connection successful" : "AK8975 connection failed");
// configure Arduino LED for
pinMode(LED_PIN, OUTPUT);
}
void loop() {
// read raw heading measurements from device
mag.getHeading(&mx, &my, &mz);
// display tab-separated gyro x/y/z values
Serial.print("mag:\t");
Serial.print(mx); Serial.print("\t");
Serial.print(my); Serial.print("\t");
Serial.println(mz);
// blink LED to indicate activity
blinkState = !blinkState;
digitalWrite(LED_PIN, blinkState);
}

View File

@ -0,0 +1,24 @@
{
"name": "I2Cdevlib-AK8975",
"keywords": "compass, sensor, i2cdevlib, i2c",
"description": "AK8975 is 3-axis electronic compass IC with high sensitive Hall sensor technology",
"include": "Arduino/AK8975",
"repository":
{
"type": "git",
"url": "https://github.com/jrowberg/i2cdevlib.git"
},
"dependencies":
[
{
"name": "I2Cdevlib-Core",
"frameworks": "arduino"
},
{
"name": "I2Cdevlib-MPU6050",
"frameworks": "arduino"
}
],
"frameworks": "arduino",
"platforms": "atmelavr"
}

View File

@ -0,0 +1,46 @@
Thank you for opening an issue on an Adafruit Arduino library repository. To
improve the speed of resolution please review the following guidelines and
common troubleshooting steps below before creating the issue:
- **Do not use GitHub issues for troubleshooting projects and issues.** Instead use
the forums at http://forums.adafruit.com to ask questions and troubleshoot why
something isn't working as expected. In many cases the problem is a common issue
that you will more quickly receive help from the forum community. GitHub issues
are meant for known defects in the code. If you don't know if there is a defect
in the code then start with troubleshooting on the forum first.
- **If following a tutorial or guide be sure you didn't miss a step.** Carefully
check all of the steps and commands to run have been followed. Consult the
forum if you're unsure or have questions about steps in a guide/tutorial.
- **For Arduino projects check these very common issues to ensure they don't apply**:
- For uploading sketches or communicating with the board make sure you're using
a **USB data cable** and **not** a **USB charge-only cable**. It is sometimes
very hard to tell the difference between a data and charge cable! Try using the
cable with other devices or swapping to another cable to confirm it is not
the problem.
- **Be sure you are supplying adequate power to the board.** Check the specs of
your board and plug in an external power supply. In many cases just
plugging a board into your computer is not enough to power it and other
peripherals.
- **Double check all soldering joints and connections.** Flakey connections
cause many mysterious problems. See the [guide to excellent soldering](https://learn.adafruit.com/adafruit-guide-excellent-soldering/tools) for examples of good solder joints.
- **Ensure you are using an official Arduino or Adafruit board.** We can't
guarantee a clone board will have the same functionality and work as expected
with this code and don't support them.
If you're sure this issue is a defect in the code and checked the steps above
please fill in the following fields to provide enough troubleshooting information.
You may delete the guideline and text above to just leave the following details:
- Arduino board: **INSERT ARDUINO BOARD NAME/TYPE HERE**
- Arduino IDE version (found in Arduino -> About Arduino menu): **INSERT ARDUINO
VERSION HERE**
- List the steps to reproduce the problem below (if possible attach a sketch or
copy the sketch code in too): **LIST REPRO STEPS BELOW**

View File

@ -0,0 +1,26 @@
Thank you for creating a pull request to contribute to Adafruit's GitHub code!
Before you open the request please review the following guidelines and tips to
help it be more easily integrated:
- **Describe the scope of your change--i.e. what the change does and what parts
of the code were modified.** This will help us understand any risks of integrating
the code.
- **Describe any known limitations with your change.** For example if the change
doesn't apply to a supported platform of the library please mention it.
- **Please run any tests or examples that can exercise your modified code.** We
strive to not break users of the code and running tests/examples helps with this
process.
Thank you again for contributing! We will try to test and integrate the change
as soon as we can, but be aware we have many GitHub repositories to manage and
can't immediately respond to every request. There is no need to bump or check in
on a pull request (it will clutter the discussion of the request).
Also don't be worried if the request is closed or not integrated--sometimes the
priorities of Adafruit's GitHub code (education, ease of use) might not match the
priorities of the pull request. Don't fret, the open source community thrives on
forks and GitHub makes it easy to keep your changes in a forked repo.
After reviewing the guidelines above you can delete this text from the pull request.

View File

@ -0,0 +1,350 @@
// AccelStepper.cpp
//
// Copyright (C) 2009 Mike McCauley
// $Id: AccelStepper.cpp,v 1.2 2010/10/24 07:46:18 mikem Exp mikem $
#include "AccelStepper.h"
void AccelStepper::moveTo(long absolute)
{
_targetPos = absolute;
computeNewSpeed();
}
void AccelStepper::move(long relative)
{
moveTo(_currentPos + relative);
}
// Implements steps according to the current speed
// You must call this at least once per step
// returns true if a step occurred
boolean AccelStepper::runSpeed()
{
unsigned long time = millis();
if (time > _lastStepTime + _stepInterval)
{
if (_speed > 0)
{
// Clockwise
_currentPos += 1;
}
else if (_speed < 0)
{
// Anticlockwise
_currentPos -= 1;
}
step(_currentPos & 0x3); // Bottom 2 bits (same as mod 4, but works with + and - numbers)
_lastStepTime = time;
return true;
}
else
return false;
}
long AccelStepper::distanceToGo()
{
return _targetPos - _currentPos;
}
long AccelStepper::targetPosition()
{
return _targetPos;
}
long AccelStepper::currentPosition()
{
return _currentPos;
}
// Useful during initialisations or after initial positioning
void AccelStepper::setCurrentPosition(long position)
{
_currentPos = position;
}
void AccelStepper::computeNewSpeed()
{
setSpeed(desiredSpeed());
}
// Work out and return a new speed.
// Subclasses can override if they want
// Implement acceleration, deceleration and max speed
// Negative speed is anticlockwise
// This is called:
// after each step
// after user changes:
// maxSpeed
// acceleration
// target position (relative or absolute)
float AccelStepper::desiredSpeed()
{
long distanceTo = distanceToGo();
// Max possible speed that can still decelerate in the available distance
float requiredSpeed;
if (distanceTo == 0)
return 0.0; // Were there
else if (distanceTo > 0) // Clockwise
requiredSpeed = sqrt(2.0 * distanceTo * _acceleration);
else // Anticlockwise
requiredSpeed = -sqrt(2.0 * -distanceTo * _acceleration);
if (requiredSpeed > _speed)
{
// Need to accelerate in clockwise direction
if (_speed == 0)
requiredSpeed = sqrt(2.0 * _acceleration);
else
requiredSpeed = _speed + abs(_acceleration / _speed);
if (requiredSpeed > _maxSpeed)
requiredSpeed = _maxSpeed;
}
else if (requiredSpeed < _speed)
{
// Need to accelerate in anticlockwise direction
if (_speed == 0)
requiredSpeed = -sqrt(2.0 * _acceleration);
else
requiredSpeed = _speed - abs(_acceleration / _speed);
if (requiredSpeed < -_maxSpeed)
requiredSpeed = -_maxSpeed;
}
// Serial.println(requiredSpeed);
return requiredSpeed;
}
// Run the motor to implement speed and acceleration in order to proceed to the target position
// You must call this at least once per step, preferably in your main loop
// If the motor is in the desired position, the cost is very small
// returns true if we are still running to position
boolean AccelStepper::run()
{
if (_targetPos == _currentPos)
return false;
if (runSpeed())
computeNewSpeed();
return true;
}
AccelStepper::AccelStepper(uint8_t pins, uint8_t pin1, uint8_t pin2, uint8_t pin3, uint8_t pin4)
{
_pins = pins;
_currentPos = 0;
_targetPos = 0;
_speed = 0.0;
_maxSpeed = 1.0;
_acceleration = 1.0;
_stepInterval = 0;
_lastStepTime = 0;
_pin1 = pin1;
_pin2 = pin2;
_pin3 = pin3;
_pin4 = pin4;
enableOutputs();
}
AccelStepper::AccelStepper(void (*forward)(), void (*backward)())
{
_pins = 0;
_currentPos = 0;
_targetPos = 0;
_speed = 0.0;
_maxSpeed = 1.0;
_acceleration = 1.0;
_stepInterval = 0;
_lastStepTime = 0;
_pin1 = 0;
_pin2 = 0;
_pin3 = 0;
_pin4 = 0;
_forward = forward;
_backward = backward;
}
void AccelStepper::setMaxSpeed(float speed)
{
_maxSpeed = speed;
computeNewSpeed();
}
void AccelStepper::setAcceleration(float acceleration)
{
_acceleration = acceleration;
computeNewSpeed();
}
void AccelStepper::setSpeed(float speed)
{
_speed = speed;
_stepInterval = abs(1000.0 / _speed);
}
float AccelStepper::speed()
{
return _speed;
}
// Subclasses can override
void AccelStepper::step(uint8_t step)
{
switch (_pins)
{
case 0:
step0();
break;
case 1:
step1(step);
break;
case 2:
step2(step);
break;
case 4:
step4(step);
break;
}
}
// 0 pin step function (ie for functional usage)
void AccelStepper::step0()
{
if (_speed > 0) {
_forward();
} else {
_backward();
}
}
// 1 pin step function (ie for stepper drivers)
// This is passed the current step number (0 to 3)
// Subclasses can override
void AccelStepper::step1(uint8_t step)
{
digitalWrite(_pin2, _speed > 0); // Direction
// Caution 200ns setup time
digitalWrite(_pin1, HIGH);
// Caution, min Step pulse width for 3967 is 1microsec
// Delay 1microsec
delayMicroseconds(1);
digitalWrite(_pin1, LOW);
}
// 2 pin step function
// This is passed the current step number (0 to 3)
// Subclasses can override
void AccelStepper::step2(uint8_t step)
{
switch (step)
{
case 0: /* 01 */
digitalWrite(_pin1, LOW);
digitalWrite(_pin2, HIGH);
break;
case 1: /* 11 */
digitalWrite(_pin1, HIGH);
digitalWrite(_pin2, HIGH);
break;
case 2: /* 10 */
digitalWrite(_pin1, HIGH);
digitalWrite(_pin2, LOW);
break;
case 3: /* 00 */
digitalWrite(_pin1, LOW);
digitalWrite(_pin2, LOW);
break;
}
}
// 4 pin step function
// This is passed the current step number (0 to 3)
// Subclasses can override
void AccelStepper::step4(uint8_t step)
{
switch (step)
{
case 0: // 1010
digitalWrite(_pin1, HIGH);
digitalWrite(_pin2, LOW);
digitalWrite(_pin3, HIGH);
digitalWrite(_pin4, LOW);
break;
case 1: // 0110
digitalWrite(_pin1, LOW);
digitalWrite(_pin2, HIGH);
digitalWrite(_pin3, HIGH);
digitalWrite(_pin4, LOW);
break;
case 2: //0101
digitalWrite(_pin1, LOW);
digitalWrite(_pin2, HIGH);
digitalWrite(_pin3, LOW);
digitalWrite(_pin4, HIGH);
break;
case 3: //1001
digitalWrite(_pin1, HIGH);
digitalWrite(_pin2, LOW);
digitalWrite(_pin3, LOW);
digitalWrite(_pin4, HIGH);
break;
}
}
// Prevents power consumption on the outputs
void AccelStepper::disableOutputs()
{
if (! _pins) return;
digitalWrite(_pin1, LOW);
digitalWrite(_pin2, LOW);
if (_pins == 4)
{
digitalWrite(_pin3, LOW);
digitalWrite(_pin4, LOW);
}
}
void AccelStepper::enableOutputs()
{
if (! _pins) return;
pinMode(_pin1, OUTPUT);
pinMode(_pin2, OUTPUT);
if (_pins == 4)
{
pinMode(_pin3, OUTPUT);
pinMode(_pin4, OUTPUT);
}
}
// Blocks until the target position is reached
void AccelStepper::runToPosition()
{
while (run())
;
}
boolean AccelStepper::runSpeedToPosition()
{
return _targetPos!=_currentPos ? AccelStepper::runSpeed() : false;
}
// Blocks until the new target position is reached
void AccelStepper::runToNewPosition(long position)
{
moveTo(position);
runToPosition();
}

View File

@ -0,0 +1,339 @@
// AccelStepper.h
//
/// \mainpage AccelStepper library for Arduino
///
/// This is the Arduino AccelStepper 1.2 library.
/// It provides an object-oriented interface for 2 or 4 pin stepper motors.
///
/// The standard Arduino IDE includes the Stepper library
/// (http://arduino.cc/en/Reference/Stepper) for stepper motors. It is
/// perfectly adequate for simple, single motor applications.
///
/// AccelStepper significantly improves on the standard Arduino Stepper library in several ways:
/// \li Supports acceleration and deceleration
/// \li Supports multiple simultaneous steppers, with independent concurrent stepping on each stepper
/// \li API functions never delay() or block
/// \li Supports 2 and 4 wire steppers
/// \li Supports stepper drivers such as the Sparkfun EasyDriver (based on 3967 driver chip)
/// \li Very slow speeds are supported
/// \li Extensive API
/// \li Subclass support
///
/// The latest version of this documentation can be downloaded from
/// http://www.open.com.au/mikem/arduino/AccelStepper
///
/// Example Arduino programs are included to show the main modes of use.
///
/// The version of the package that this documentation refers to can be downloaded
/// from http://www.open.com.au/mikem/arduino/AccelStepper/AccelStepper-1.3.zip
/// You can find the latest version at http://www.open.com.au/mikem/arduino/AccelStepper
///
/// Tested on Arduino Diecimila and Mega with arduino-0018 on OpenSuSE 11.1 and avr-libc-1.6.1-1.15,
/// cross-avr-binutils-2.19-9.1, cross-avr-gcc-4.1.3_20080612-26.5.
///
/// \par Installation
/// Install in the usual way: unzip the distribution zip file to the libraries
/// sub-folder of your sketchbook.
///
/// This software is Copyright (C) 2010 Mike McCauley. Use is subject to license
/// conditions. The main licensing options available are GPL V2 or Commercial:
///
/// \par Open Source Licensing GPL V2
/// This is the appropriate option if you want to share the source code of your
/// application with everyone you distribute it to, and you also want to give them
/// the right to share who uses it. If you wish to use this software under Open
/// Source Licensing, you must contribute all your source code to the open source
/// community in accordance with the GPL Version 2 when your application is
/// distributed. See http://www.gnu.org/copyleft/gpl.html
///
/// \par Commercial Licensing
/// This is the appropriate option if you are creating proprietary applications
/// and you are not prepared to distribute and share the source code of your
/// application. Contact info@open.com.au for details.
///
/// \par Revision History
/// \version 1.0 Initial release
///
/// \version 1.1 Added speed() function to get the current speed.
/// \version 1.2 Added runSpeedToPosition() submitted by Gunnar Arndt.
/// \version 1.3 Added support for stepper drivers (ie with Step and Direction inputs) with _pins == 1
///
///
/// \author Mike McCauley (mikem@open.com.au)
// Copyright (C) 2009 Mike McCauley
// $Id: AccelStepper.h,v 1.2 2010/10/24 07:46:18 mikem Exp mikem $
#ifndef AccelStepper_h
#define AccelStepper_h
#if ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#include "stdlib.h"
#include "wiring.h"
#endif
// These defs cause trouble on some versions of Arduino
#undef round
/////////////////////////////////////////////////////////////////////
/// \class AccelStepper AccelStepper.h <AccelStepper.h>
/// \brief Support for stepper motors with acceleration etc.
///
/// This defines a single 2 or 4 pin stepper motor, or stepper moter with fdriver chip, with optional
/// acceleration, deceleration, absolute positioning commands etc. Multiple
/// simultaneous steppers are supported, all moving
/// at different speeds and accelerations.
///
/// \par Operation
/// This module operates by computing a step time in milliseconds. The step
/// time is recomputed after each step and after speed and acceleration
/// parameters are changed by the caller. The time of each step is recorded in
/// milliseconds. The run() function steps the motor if a new step is due.
/// The run() function must be called frequently until the motor is in the
/// desired position, after which time run() will do nothing.
///
/// \par Positioning
/// Positions are specified by a signed long integer. At
/// construction time, the current position of the motor is consider to be 0. Positive
/// positions are clockwise from the initial position; negative positions are
/// anticlockwise. The curent position can be altered for instance after
/// initialization positioning.
///
/// \par Caveats
/// This is an open loop controller: If the motor stalls or is oversped,
/// AccelStepper will not have a correct
/// idea of where the motor really is (since there is no feedback of the motor's
/// real position. We only know where we _think_ it is, relative to the
/// initial starting point).
///
/// The fastest motor speed that can be reliably supported is 1000 steps per
/// second (1 step every millisecond). However any speed less than that down
/// to very slow speeds (much less than one per second) are supported,
/// provided the run() function is called frequently enough to step the
/// motor whenever required.
class AccelStepper
{
public:
/// Constructor. You can have multiple simultaneous steppers, all moving
/// at different speeds and accelerations, provided you call their run()
/// functions at frequent enough intervals. Current Position is set to 0, target
/// position is set to 0. MaxSpeed and Acceleration default to 1.0.
/// The motor pins will be initialised to OUTPUT mode during the
/// constructor by a call to enableOutputs().
/// \param[in] pins Number of pins to interface to. 1, 2 or 4 are
/// supported. 1 means a stepper driver (with Step and Direction pins)
/// 2 means a 2 wire stepper. 4 means a 4 wire stepper.
/// Defaults to 4 pins.
/// \param[in] pin1 Arduino digital pin number for motor pin 1. Defaults
/// to pin 2. For a driver (pins==1), this is the Step input to the driver. Low to high transition means to step)
/// \param[in] pin2 Arduino digital pin number for motor pin 2. Defaults
/// to pin 3. For a driver (pins==1), this is the Direction input the driver. High means forward.
/// \param[in] pin3 Arduino digital pin number for motor pin 3. Defaults
/// to pin 4.
/// \param[in] pin4 Arduino digital pin number for motor pin 4. Defaults
/// to pin 5.
AccelStepper(uint8_t pins = 4, uint8_t pin1 = 2, uint8_t pin2 = 3, uint8_t pin3 = 4, uint8_t pin4 = 5);
/// Constructor. You can have multiple simultaneous steppers, all moving
/// at different speeds and accelerations, provided you call their run()
/// functions at frequent enough intervals. Current Position is set to 0, target
/// position is set to 0. MaxSpeed and Acceleration default to 1.0.
/// Any motor initialization should happen before hand, no pins are used or initialized.
/// \param[in] forward void-returning procedure that will make a forward step
/// \param[in] backward void-returning procedure that will make a backward step
AccelStepper(void (*forward)(), void (*backward)());
/// Set the target position. The run() function will try to move the motor
/// from the current position to the target position set by the most
/// recent call to this function.
/// \param[in] absolute The desired absolute position. Negative is
/// anticlockwise from the 0 position.
void moveTo(long absolute);
/// Set the target position relative to the current position
/// \param[in] relative The desired position relative to the current position. Negative is
/// anticlockwise from the current position.
void move(long relative);
/// Poll the motor and step it if a step is due, implementing
/// accelerations and decelerations to achive the ratget position. You must call this as
/// fequently as possible, but at least once per minimum step interval,
/// preferably in your main loop.
/// \return true if the motor is at the target position.
boolean run();
/// Poll the motor and step it if a step is due, implmenting a constant
/// speed as set by the most recent call to setSpeed().
/// \return true if the motor was stepped.
boolean runSpeed();
/// Sets the maximum permitted speed. the run() function will accelerate
/// up to the speed set by this function.
/// \param[in] speed The desired maximum speed in steps per second. Must
/// be > 0. Speeds of more than 1000 steps per second are unreliable.
void setMaxSpeed(float speed);
/// Sets the acceleration and deceleration parameter.
/// \param[in] acceleration The desired acceleration in steps per second
/// per second. Must be > 0.
void setAcceleration(float acceleration);
/// Sets the desired constant speed for use with runSpeed().
/// \param[in] speed The desired constant speed in steps per
/// second. Positive is clockwise. Speeds of more than 1000 steps per
/// second are unreliable. Very slow speeds may be set (eg 0.00027777 for
/// once per hour, approximately. Speed accuracy depends on the Arduino
/// crystal. Jitter depends on how frequently you call the runSpeed() function.
void setSpeed(float speed);
/// The most recently set speed
/// \return the most recent speed in steps per second
float speed();
/// The distance from the current position to the target position.
/// \return the distance from the current position to the target position
/// in steps. Positive is clockwise from the current position.
long distanceToGo();
/// The most recently set target position.
/// \return the target position
/// in steps. Positive is clockwise from the 0 position.
long targetPosition();
/// The currently motor position.
/// \return the current motor position
/// in steps. Positive is clockwise from the 0 position.
long currentPosition();
/// Resets the current position of the motor, so that wherever the mottor
/// happens to be right now is considered to be the new position. Useful
/// for setting a zero position on a stepper after an initial hardware
/// positioning move.
/// \param[in] position The position in steps of wherever the motor
/// happens to be right now.
void setCurrentPosition(long position);
/// Moves the motor to the target position and blocks until it is at
/// position. Dont use this in event loops, since it blocks.
void runToPosition();
/// Runs at the currently selected speed until the target position is reached
/// Does not implement accelerations.
boolean runSpeedToPosition();
/// Moves the motor to the new target position and blocks until it is at
/// position. Dont use this in event loops, since it blocks.
/// \param[in] position The new target position.
void runToNewPosition(long position);
/// Disable motor pin outputs by setting them all LOW
/// Depending on the design of your electronics this may turn off
/// the power to the motor coils, saving power.
/// This is useful to support Arduino low power modes: disable the outputs
/// during sleep and then reenable with enableOutputs() before stepping
/// again.
void disableOutputs();
/// Enable motor pin outputs by setting the motor pins to OUTPUT
/// mode. Called automatically by the constructor.
void enableOutputs();
protected:
/// Forces the library to compute a new instantaneous speed and set that as
/// the current speed. Calls
/// desiredSpeed(), which can be overridden by subclasses. It is called by
/// the library:
/// \li after each step
/// \li after change to maxSpeed through setMaxSpeed()
/// \li after change to acceleration through setAcceleration()
/// \li after change to target position (relative or absolute) through
/// move() or moveTo()
void computeNewSpeed();
/// Called to execute a step. Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default calls step1(), step2() or step4() depending on the
/// number of pins defined for the stepper.
/// \param[in] step The current step phase number (0 to 3)
virtual void step(uint8_t step);
/// Called to execute a step using stepper functions (pins = 0) Only called when a new step is
/// required. Calls _forward() or _backward() to perform the step
virtual void step0(void);
/// Called to execute a step on a stepper drover (ie where pins == 1). Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default sets or clears the outputs of Step pin1 to step,
/// and sets the output of _pin2 to the desired direction. The Step pin (_pin1) is pulsed for 1 microsecond
/// which is the minimum STEP pulse width for the 3967 driver.
/// \param[in] step The current step phase number (0 to 3)
virtual void step1(uint8_t step);
/// Called to execute a step on a 2 pin motor. Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default sets or clears the outputs of pin1 and pin2
/// \param[in] step The current step phase number (0 to 3)
virtual void step2(uint8_t step);
/// Called to execute a step on a 4 pin motor. Only called when a new step is
/// required. Subclasses may override to implement new stepping
/// interfaces. The default sets or clears the outputs of pin1, pin2,
/// pin3, pin4.
/// \param[in] step The current step phase number (0 to 3)
virtual void step4(uint8_t step);
/// Compute and return the desired speed. The default algorithm uses
/// maxSpeed, acceleration and the current speed to set a new speed to
/// move the motor from teh current position to the target
/// position. Subclasses may override this to provide an alternate
/// algorithm (but do not block). Called by computeNewSpeed whenever a new speed neds to be
/// computed.
virtual float desiredSpeed();
private:
/// Number of pins on the stepper motor. Permits 2 or 4. 2 pins is a
/// bipolar, and 4 pins is a unipolar.
uint8_t _pins; // 2 or 4
/// Arduino pin number for the 2 or 4 pins required to interface to the
/// stepper motor.
uint8_t _pin1, _pin2, _pin3, _pin4;
/// The current absolution position in steps.
long _currentPos; // Steps
/// The target position in steps. The AccelStepper library will move the
/// motor from teh _currentPos to the _targetPos, taking into account the
/// max speed, acceleration and deceleration
long _targetPos; // Steps
/// The current motos speed in steps per second
/// Positive is clockwise
float _speed; // Steps per second
/// The maximum permitted speed in steps per second. Must be > 0.
float _maxSpeed;
/// The acceleration to use to accelerate or decelerate the motor in steps
/// per second per second. Must be > 0
float _acceleration;
/// The current interval between steps in milliseconds.
unsigned long _stepInterval;
/// The last step time in milliseconds
unsigned long _lastStepTime;
// The pointer to a forward-step procedure
void (*_forward)();
// The pointer to a backward-step procedure
void (*_backward)();
};
#endif

View File

@ -0,0 +1,17 @@
This software is Copyright (C) 2008 Mike McCauley. Use is subject to license
conditions. The main licensing options available are GPL V2 or Commercial:
Open Source Licensing GPL V2
This is the appropriate option if you want to share the source code of your
application with everyone you distribute it to, and you also want to give them
the right to share who uses it. If you wish to use this software under Open
Source Licensing, you must contribute all your source code to the open source
community in accordance with the GPL Version 2 when your application is
distributed. See http://www.gnu.org/copyleft/gpl.html
Commercial Licensing
This is the appropriate option if you are creating proprietary applications
and you are not prepared to distribute and share the source code of your
application. Contact info@open.com.au for details.

View File

@ -0,0 +1,27 @@
AccelStepper/Makefile
AccelStepper/AccelStepper.h
AccelStepper/AccelStepper.cpp
AccelStepper/MANIFEST
AccelStepper/LICENSE
AccelStepper/project.cfg
AccelStepper/doc
AccelStepper/examples/Blocking/Blocking.pde
AccelStepper/examples/MultiStepper/MultiStepper.pde
AccelStepper/examples/Overshoot/Overshoot.pde
AccelStepper/examples/ConstantSpeed/ConstantSpeed.pde
AccelStepper/examples/Random/Random.pde
AccelStepper/doc
AccelStepper/doc/index.html
AccelStepper/doc/functions.html
AccelStepper/doc/annotated.html
AccelStepper/doc/tab_l.gif
AccelStepper/doc/tabs.css
AccelStepper/doc/files.html
AccelStepper/doc/classAccelStepper-members.html
AccelStepper/doc/doxygen.css
AccelStepper/doc/AccelStepper_8h-source.html
AccelStepper/doc/tab_r.gif
AccelStepper/doc/doxygen.png
AccelStepper/doc/tab_b.gif
AccelStepper/doc/functions_func.html
AccelStepper/doc/classAccelStepper.html

View File

@ -0,0 +1,26 @@
# Makefile
#
# Makefile for the Arduino AccelStepper project
#
# Author: Mike McCauley (mikem@open.com.au)
# Copyright (C) 2010 Mike McCauley
# $Id: Makefile,v 1.1 2010/04/25 02:21:18 mikem Exp mikem $
PROJNAME = AccelStepper
# Dont forget to also change the version at the top of AccelStepper.h:
DISTFILE = $(PROJNAME)-1.3.zip
all: doxygen dist upload
doxygen:
doxygen project.cfg
ci:
ci -l `cat MANIFEST`
dist:
(cd ..; zip $(PROJNAME)/$(DISTFILE) `cat $(PROJNAME)/MANIFEST`)
upload:
scp $(DISTFILE) doc/*.html doc/*.gif doc/*.png doc/*.css doc/*.pdf server2:/var/www/html/mikem/arduino/$(PROJNAME)

View File

@ -0,0 +1 @@
TO INSTALL: Download zip by clicking "DOWNLOADS" in top right corner. Then uncompress folder and rename to AccelStepper. Make sure that folder contains this README. Then copy to sketchfolder/libraries (see also http://www.ladyada.net/library/arduino/libraries.html)

View File

@ -0,0 +1,336 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
<html><head><meta http-equiv="Content-Type" content="text/html;charset=UTF-8">
<title>AccelStepper: AccelStepper.h Source File</title>
<link href="doxygen.css" rel="stylesheet" type="text/css">
<link href="tabs.css" rel="stylesheet" type="text/css">
</head><body>
<!-- Generated by Doxygen 1.5.6 -->
<div class="navigation" id="top">
<div class="tabs">
<ul>
<li><a href="index.html"><span>Main&nbsp;Page</span></a></li>
<li><a href="annotated.html"><span>Classes</span></a></li>
<li class="current"><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<h1>AccelStepper.h</h1><div class="fragment"><pre class="fragment"><a name="l00001"></a>00001 <span class="comment">// AccelStepper.h</span>
<a name="l00002"></a>00002 <span class="comment">//</span><span class="comment"></span>
<a name="l00003"></a>00003 <span class="comment">/// \mainpage AccelStepper library for Arduino</span>
<a name="l00004"></a>00004 <span class="comment">///</span>
<a name="l00005"></a>00005 <span class="comment">/// This is the Arduino AccelStepper 1.2 library.</span>
<a name="l00006"></a>00006 <span class="comment">/// It provides an object-oriented interface for 2 or 4 pin stepper motors.</span>
<a name="l00007"></a>00007 <span class="comment">///</span>
<a name="l00008"></a>00008 <span class="comment">/// The standard Arduino IDE includes the Stepper library</span>
<a name="l00009"></a>00009 <span class="comment">/// (http://arduino.cc/en/Reference/Stepper) for stepper motors. It is</span>
<a name="l00010"></a>00010 <span class="comment">/// perfectly adequate for simple, single motor applications.</span>
<a name="l00011"></a>00011 <span class="comment">///</span>
<a name="l00012"></a>00012 <span class="comment">/// AccelStepper significantly improves on the standard Arduino Stepper library in several ways:</span>
<a name="l00013"></a>00013 <span class="comment">/// \li Supports acceleration and deceleration</span>
<a name="l00014"></a>00014 <span class="comment">/// \li Supports multiple simultaneous steppers, with independent concurrent stepping on each stepper</span>
<a name="l00015"></a>00015 <span class="comment">/// \li API functions never delay() or block</span>
<a name="l00016"></a>00016 <span class="comment">/// \li Supports 2 and 4 wire steppers</span>
<a name="l00017"></a>00017 <span class="comment">/// \li Supports stepper drivers such as the Sparkfun EasyDriver (based on 3967 driver chip)</span>
<a name="l00018"></a>00018 <span class="comment">/// \li Very slow speeds are supported</span>
<a name="l00019"></a>00019 <span class="comment">/// \li Extensive API</span>
<a name="l00020"></a>00020 <span class="comment">/// \li Subclass support</span>
<a name="l00021"></a>00021 <span class="comment">///</span>
<a name="l00022"></a>00022 <span class="comment">/// The latest version of this documentation can be downloaded from </span>
<a name="l00023"></a>00023 <span class="comment">/// http://www.open.com.au/mikem/arduino/AccelStepper</span>
<a name="l00024"></a>00024 <span class="comment">///</span>
<a name="l00025"></a>00025 <span class="comment">/// Example Arduino programs are included to show the main modes of use.</span>
<a name="l00026"></a>00026 <span class="comment">///</span>
<a name="l00027"></a>00027 <span class="comment">/// The version of the package that this documentation refers to can be downloaded </span>
<a name="l00028"></a>00028 <span class="comment">/// from http://www.open.com.au/mikem/arduino/AccelStepper/AccelStepper-1.3.zip</span>
<a name="l00029"></a>00029 <span class="comment">/// You can find the latest version at http://www.open.com.au/mikem/arduino/AccelStepper</span>
<a name="l00030"></a>00030 <span class="comment">///</span>
<a name="l00031"></a>00031 <span class="comment">/// Tested on Arduino Diecimila and Mega with arduino-0018 on OpenSuSE 11.1 and avr-libc-1.6.1-1.15,</span>
<a name="l00032"></a>00032 <span class="comment">/// cross-avr-binutils-2.19-9.1, cross-avr-gcc-4.1.3_20080612-26.5.</span>
<a name="l00033"></a>00033 <span class="comment">///</span>
<a name="l00034"></a>00034 <span class="comment">/// \par Installation</span>
<a name="l00035"></a>00035 <span class="comment">/// Install in the usual way: unzip the distribution zip file to the libraries</span>
<a name="l00036"></a>00036 <span class="comment">/// sub-folder of your sketchbook. </span>
<a name="l00037"></a>00037 <span class="comment">///</span>
<a name="l00038"></a>00038 <span class="comment">/// This software is Copyright (C) 2010 Mike McCauley. Use is subject to license</span>
<a name="l00039"></a>00039 <span class="comment">/// conditions. The main licensing options available are GPL V2 or Commercial:</span>
<a name="l00040"></a>00040 <span class="comment">/// </span>
<a name="l00041"></a>00041 <span class="comment">/// \par Open Source Licensing GPL V2</span>
<a name="l00042"></a>00042 <span class="comment">/// This is the appropriate option if you want to share the source code of your</span>
<a name="l00043"></a>00043 <span class="comment">/// application with everyone you distribute it to, and you also want to give them</span>
<a name="l00044"></a>00044 <span class="comment">/// the right to share who uses it. If you wish to use this software under Open</span>
<a name="l00045"></a>00045 <span class="comment">/// Source Licensing, you must contribute all your source code to the open source</span>
<a name="l00046"></a>00046 <span class="comment">/// community in accordance with the GPL Version 2 when your application is</span>
<a name="l00047"></a>00047 <span class="comment">/// distributed. See http://www.gnu.org/copyleft/gpl.html</span>
<a name="l00048"></a>00048 <span class="comment">/// </span>
<a name="l00049"></a>00049 <span class="comment">/// \par Commercial Licensing</span>
<a name="l00050"></a>00050 <span class="comment">/// This is the appropriate option if you are creating proprietary applications</span>
<a name="l00051"></a>00051 <span class="comment">/// and you are not prepared to distribute and share the source code of your</span>
<a name="l00052"></a>00052 <span class="comment">/// application. Contact info@open.com.au for details.</span>
<a name="l00053"></a>00053 <span class="comment">///</span>
<a name="l00054"></a>00054 <span class="comment">/// \par Revision History</span>
<a name="l00055"></a>00055 <span class="comment">/// \version 1.0 Initial release</span>
<a name="l00056"></a>00056 <span class="comment">///</span>
<a name="l00057"></a>00057 <span class="comment">/// \version 1.1 Added speed() function to get the current speed.</span>
<a name="l00058"></a>00058 <span class="comment">/// \version 1.2 Added runSpeedToPosition() submitted by Gunnar Arndt.</span>
<a name="l00059"></a>00059 <span class="comment">/// \version 1.3 Added support for stepper drivers (ie with Step and Direction inputs) with _pins == 1</span>
<a name="l00060"></a>00060 <span class="comment">/// </span>
<a name="l00061"></a>00061 <span class="comment">///</span>
<a name="l00062"></a>00062 <span class="comment">/// \author Mike McCauley (mikem@open.com.au)</span>
<a name="l00063"></a>00063 <span class="comment"></span><span class="comment">// Copyright (C) 2009 Mike McCauley</span>
<a name="l00064"></a>00064 <span class="comment">// $Id: AccelStepper.h,v 1.2 2010/10/24 07:46:18 mikem Exp mikem $</span>
<a name="l00065"></a>00065
<a name="l00066"></a>00066 <span class="preprocessor">#ifndef AccelStepper_h</span>
<a name="l00067"></a>00067 <span class="preprocessor"></span><span class="preprocessor">#define AccelStepper_h</span>
<a name="l00068"></a>00068 <span class="preprocessor"></span>
<a name="l00069"></a>00069 <span class="preprocessor">#include &lt;stdlib.h&gt;</span>
<a name="l00070"></a>00070 <span class="preprocessor">#include &lt;wiring.h&gt;</span>
<a name="l00071"></a>00071
<a name="l00072"></a>00072 <span class="comment">// These defs cause trouble on some versions of Arduino</span>
<a name="l00073"></a>00073 <span class="preprocessor">#undef round</span>
<a name="l00074"></a>00074 <span class="preprocessor"></span><span class="comment"></span>
<a name="l00075"></a>00075 <span class="comment">/////////////////////////////////////////////////////////////////////</span>
<a name="l00076"></a>00076 <span class="comment">/// \class AccelStepper AccelStepper.h &lt;AccelStepper.h&gt;</span>
<a name="l00077"></a>00077 <span class="comment">/// \brief Support for stepper motors with acceleration etc.</span>
<a name="l00078"></a>00078 <span class="comment">///</span>
<a name="l00079"></a>00079 <span class="comment">/// This defines a single 2 or 4 pin stepper motor, or stepper moter with fdriver chip, with optional</span>
<a name="l00080"></a>00080 <span class="comment">/// acceleration, deceleration, absolute positioning commands etc. Multiple</span>
<a name="l00081"></a>00081 <span class="comment">/// simultaneous steppers are supported, all moving </span>
<a name="l00082"></a>00082 <span class="comment">/// at different speeds and accelerations. </span>
<a name="l00083"></a>00083 <span class="comment">///</span>
<a name="l00084"></a>00084 <span class="comment">/// \par Operation</span>
<a name="l00085"></a>00085 <span class="comment">/// This module operates by computing a step time in milliseconds. The step</span>
<a name="l00086"></a>00086 <span class="comment">/// time is recomputed after each step and after speed and acceleration</span>
<a name="l00087"></a>00087 <span class="comment">/// parameters are changed by the caller. The time of each step is recorded in</span>
<a name="l00088"></a>00088 <span class="comment">/// milliseconds. The run() function steps the motor if a new step is due.</span>
<a name="l00089"></a>00089 <span class="comment">/// The run() function must be called frequently until the motor is in the</span>
<a name="l00090"></a>00090 <span class="comment">/// desired position, after which time run() will do nothing.</span>
<a name="l00091"></a>00091 <span class="comment">///</span>
<a name="l00092"></a>00092 <span class="comment">/// \par Positioning</span>
<a name="l00093"></a>00093 <span class="comment">/// Positions are specified by a signed long integer. At</span>
<a name="l00094"></a>00094 <span class="comment">/// construction time, the current position of the motor is consider to be 0. Positive</span>
<a name="l00095"></a>00095 <span class="comment">/// positions are clockwise from the initial position; negative positions are</span>
<a name="l00096"></a>00096 <span class="comment">/// anticlockwise. The curent position can be altered for instance after</span>
<a name="l00097"></a>00097 <span class="comment">/// initialization positioning.</span>
<a name="l00098"></a>00098 <span class="comment">///</span>
<a name="l00099"></a>00099 <span class="comment">/// \par Caveats</span>
<a name="l00100"></a>00100 <span class="comment">/// This is an open loop controller: If the motor stalls or is oversped,</span>
<a name="l00101"></a>00101 <span class="comment">/// AccelStepper will not have a correct </span>
<a name="l00102"></a>00102 <span class="comment">/// idea of where the motor really is (since there is no feedback of the motor's</span>
<a name="l00103"></a>00103 <span class="comment">/// real position. We only know where we _think_ it is, relative to the</span>
<a name="l00104"></a>00104 <span class="comment">/// initial starting point).</span>
<a name="l00105"></a>00105 <span class="comment">///</span>
<a name="l00106"></a>00106 <span class="comment">/// The fastest motor speed that can be reliably supported is 1000 steps per</span>
<a name="l00107"></a>00107 <span class="comment">/// second (1 step every millisecond). However any speed less than that down</span>
<a name="l00108"></a>00108 <span class="comment">/// to very slow speeds (much less than one per second) are supported,</span>
<a name="l00109"></a>00109 <span class="comment">/// provided the run() function is called frequently enough to step the</span>
<a name="l00110"></a>00110 <span class="comment">/// motor whenever required.</span>
<a name="l00111"></a><a class="code" href="classAccelStepper.html">00111</a> <span class="comment"></span><span class="keyword">class </span><a class="code" href="classAccelStepper.html" title="Support for stepper motors with acceleration etc.">AccelStepper</a>
<a name="l00112"></a>00112 {
<a name="l00113"></a>00113 <span class="keyword">public</span>:<span class="comment"></span>
<a name="l00114"></a>00114 <span class="comment"> /// Constructor. You can have multiple simultaneous steppers, all moving</span>
<a name="l00115"></a>00115 <span class="comment"> /// at different speeds and accelerations, provided you call their run()</span>
<a name="l00116"></a>00116 <span class="comment"> /// functions at frequent enough intervals. Current Position is set to 0, target</span>
<a name="l00117"></a>00117 <span class="comment"> /// position is set to 0. MaxSpeed and Acceleration default to 1.0.</span>
<a name="l00118"></a>00118 <span class="comment"> /// The motor pins will be initialised to OUTPUT mode during the</span>
<a name="l00119"></a>00119 <span class="comment"> /// constructor by a call to enableOutputs().</span>
<a name="l00120"></a>00120 <span class="comment"> /// \param[in] pins Number of pins to interface to. 1, 2 or 4 are</span>
<a name="l00121"></a>00121 <span class="comment"> /// supported. 1 means a stepper driver (with Step and Direction pins)</span>
<a name="l00122"></a>00122 <span class="comment"> /// 2 means a 2 wire stepper. 4 means a 4 wire stepper.</span>
<a name="l00123"></a>00123 <span class="comment"> /// Defaults to 4 pins.</span>
<a name="l00124"></a>00124 <span class="comment"> /// \param[in] pin1 Arduino digital pin number for motor pin 1. Defaults</span>
<a name="l00125"></a>00125 <span class="comment"> /// to pin 2. For a driver (pins==1), this is the Step input to the driver. Low to high transition means to step)</span>
<a name="l00126"></a>00126 <span class="comment"> /// \param[in] pin2 Arduino digital pin number for motor pin 2. Defaults</span>
<a name="l00127"></a>00127 <span class="comment"> /// to pin 3. For a driver (pins==1), this is the Direction input the driver. High means forward.</span>
<a name="l00128"></a>00128 <span class="comment"> /// \param[in] pin3 Arduino digital pin number for motor pin 3. Defaults</span>
<a name="l00129"></a>00129 <span class="comment"> /// to pin 4.</span>
<a name="l00130"></a>00130 <span class="comment"> /// \param[in] pin4 Arduino digital pin number for motor pin 4. Defaults</span>
<a name="l00131"></a>00131 <span class="comment"> /// to pin 5.</span>
<a name="l00132"></a>00132 <span class="comment"></span> <a class="code" href="classAccelStepper.html#a1290897df35915069e5eca9d034038c">AccelStepper</a>(uint8_t pins = 4, uint8_t pin1 = 2, uint8_t pin2 = 3, uint8_t pin3 = 4, uint8_t pin4 = 5);
<a name="l00133"></a>00133 <span class="comment"></span>
<a name="l00134"></a>00134 <span class="comment"> /// Set the target position. The run() function will try to move the motor</span>
<a name="l00135"></a>00135 <span class="comment"> /// from the current position to the target position set by the most</span>
<a name="l00136"></a>00136 <span class="comment"> /// recent call to this function.</span>
<a name="l00137"></a>00137 <span class="comment"> /// \param[in] absolute The desired absolute position. Negative is</span>
<a name="l00138"></a>00138 <span class="comment"> /// anticlockwise from the 0 position.</span>
<a name="l00139"></a>00139 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#ce236ede35f87c63d18da25810ec9736">moveTo</a>(<span class="keywordtype">long</span> absolute);
<a name="l00140"></a>00140 <span class="comment"></span>
<a name="l00141"></a>00141 <span class="comment"> /// Set the target position relative to the current position</span>
<a name="l00142"></a>00142 <span class="comment"> /// \param[in] relative The desired position relative to the current position. Negative is</span>
<a name="l00143"></a>00143 <span class="comment"> /// anticlockwise from the current position.</span>
<a name="l00144"></a>00144 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#68942c66e78fb7f7b5f0cdade6eb7f06">move</a>(<span class="keywordtype">long</span> relative);
<a name="l00145"></a>00145 <span class="comment"></span>
<a name="l00146"></a>00146 <span class="comment"> /// Poll the motor and step it if a step is due, implementing</span>
<a name="l00147"></a>00147 <span class="comment"> /// accelerations and decelerations to achive the ratget position. You must call this as</span>
<a name="l00148"></a>00148 <span class="comment"> /// fequently as possible, but at least once per minimum step interval,</span>
<a name="l00149"></a>00149 <span class="comment"> /// preferably in your main loop.</span>
<a name="l00150"></a>00150 <span class="comment"> /// \return true if the motor is at the target position.</span>
<a name="l00151"></a>00151 <span class="comment"></span> <span class="keywordtype">boolean</span> <a class="code" href="classAccelStepper.html#608b2395b64ac15451d16d0371fe13ce">run</a>();
<a name="l00152"></a>00152 <span class="comment"></span>
<a name="l00153"></a>00153 <span class="comment"> /// Poll the motor and step it if a step is due, implmenting a constant</span>
<a name="l00154"></a>00154 <span class="comment"> /// speed as set by the most recent call to setSpeed().</span>
<a name="l00155"></a>00155 <span class="comment"> /// \return true if the motor was stepped.</span>
<a name="l00156"></a>00156 <span class="comment"></span> <span class="keywordtype">boolean</span> <a class="code" href="classAccelStepper.html#a4a6bdf99f698284faaeb5542b0b7514">runSpeed</a>();
<a name="l00157"></a>00157 <span class="comment"></span>
<a name="l00158"></a>00158 <span class="comment"> /// Sets the maximum permitted speed. the run() function will accelerate</span>
<a name="l00159"></a>00159 <span class="comment"> /// up to the speed set by this function.</span>
<a name="l00160"></a>00160 <span class="comment"> /// \param[in] speed The desired maximum speed in steps per second. Must</span>
<a name="l00161"></a>00161 <span class="comment"> /// be &gt; 0. Speeds of more than 1000 steps per second are unreliable. </span>
<a name="l00162"></a>00162 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#bee8d466229b87accba33d6ec929c18f">setMaxSpeed</a>(<span class="keywordtype">float</span> <a class="code" href="classAccelStepper.html#4f0989d0ae264e7eadfe1fa720769fb6">speed</a>);
<a name="l00163"></a>00163 <span class="comment"></span>
<a name="l00164"></a>00164 <span class="comment"> /// Sets the acceleration and deceleration parameter.</span>
<a name="l00165"></a>00165 <span class="comment"> /// \param[in] acceleration The desired acceleration in steps per second</span>
<a name="l00166"></a>00166 <span class="comment"> /// per second. Must be &gt; 0.</span>
<a name="l00167"></a>00167 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#dfb19e3cd2a028a1fe78131787604fd1">setAcceleration</a>(<span class="keywordtype">float</span> acceleration);
<a name="l00168"></a>00168 <span class="comment"></span>
<a name="l00169"></a>00169 <span class="comment"> /// Sets the desired constant speed for use with runSpeed().</span>
<a name="l00170"></a>00170 <span class="comment"> /// \param[in] speed The desired constant speed in steps per</span>
<a name="l00171"></a>00171 <span class="comment"> /// second. Positive is clockwise. Speeds of more than 1000 steps per</span>
<a name="l00172"></a>00172 <span class="comment"> /// second are unreliable. Very slow speeds may be set (eg 0.00027777 for</span>
<a name="l00173"></a>00173 <span class="comment"> /// once per hour, approximately. Speed accuracy depends on the Arduino</span>
<a name="l00174"></a>00174 <span class="comment"> /// crystal. Jitter depends on how frequently you call the runSpeed() function.</span>
<a name="l00175"></a>00175 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#e79c49ad69d5ccc9da0ee691fa4ca235">setSpeed</a>(<span class="keywordtype">float</span> speed);
<a name="l00176"></a>00176 <span class="comment"></span>
<a name="l00177"></a>00177 <span class="comment"> /// The most recently set speed</span>
<a name="l00178"></a>00178 <span class="comment"> /// \return the most recent speed in steps per second</span>
<a name="l00179"></a>00179 <span class="comment"></span> <span class="keywordtype">float</span> <a class="code" href="classAccelStepper.html#4f0989d0ae264e7eadfe1fa720769fb6">speed</a>();
<a name="l00180"></a>00180 <span class="comment"></span>
<a name="l00181"></a>00181 <span class="comment"> /// The distance from the current position to the target position.</span>
<a name="l00182"></a>00182 <span class="comment"> /// \return the distance from the current position to the target position</span>
<a name="l00183"></a>00183 <span class="comment"> /// in steps. Positive is clockwise from the current position.</span>
<a name="l00184"></a>00184 <span class="comment"></span> <span class="keywordtype">long</span> <a class="code" href="classAccelStepper.html#748665c3962e66fbc0e9373eb14c69c1">distanceToGo</a>();
<a name="l00185"></a>00185 <span class="comment"></span>
<a name="l00186"></a>00186 <span class="comment"> /// The most recently set target position.</span>
<a name="l00187"></a>00187 <span class="comment"> /// \return the target position</span>
<a name="l00188"></a>00188 <span class="comment"> /// in steps. Positive is clockwise from the 0 position.</span>
<a name="l00189"></a>00189 <span class="comment"></span> <span class="keywordtype">long</span> <a class="code" href="classAccelStepper.html#96685e0945b7cf75d5959da679cd911e">targetPosition</a>();
<a name="l00190"></a>00190
<a name="l00191"></a>00191 <span class="comment"></span>
<a name="l00192"></a>00192 <span class="comment"> /// The currently motor position.</span>
<a name="l00193"></a>00193 <span class="comment"> /// \return the current motor position</span>
<a name="l00194"></a>00194 <span class="comment"> /// in steps. Positive is clockwise from the 0 position.</span>
<a name="l00195"></a>00195 <span class="comment"></span> <span class="keywordtype">long</span> <a class="code" href="classAccelStepper.html#5dce13ab2a1b02b8f443318886bf6fc5">currentPosition</a>();
<a name="l00196"></a>00196 <span class="comment"></span>
<a name="l00197"></a>00197 <span class="comment"> /// Resets the current position of the motor, so that wherever the mottor</span>
<a name="l00198"></a>00198 <span class="comment"> /// happens to be right now is considered to be the new position. Useful</span>
<a name="l00199"></a>00199 <span class="comment"> /// for setting a zero position on a stepper after an initial hardware</span>
<a name="l00200"></a>00200 <span class="comment"> /// positioning move.</span>
<a name="l00201"></a>00201 <span class="comment"> /// \param[in] position The position in steps of wherever the motor</span>
<a name="l00202"></a>00202 <span class="comment"> /// happens to be right now.</span>
<a name="l00203"></a>00203 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#9d917f014317fb9d3b5dc14e66f6c689">setCurrentPosition</a>(<span class="keywordtype">long</span> position);
<a name="l00204"></a>00204 <span class="comment"></span>
<a name="l00205"></a>00205 <span class="comment"> /// Moves the motor to the target position and blocks until it is at</span>
<a name="l00206"></a>00206 <span class="comment"> /// position. Dont use this in event loops, since it blocks.</span>
<a name="l00207"></a>00207 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#344f58fef8cc34ac5aa75ba4b665d21c">runToPosition</a>();
<a name="l00208"></a>00208 <span class="comment"></span>
<a name="l00209"></a>00209 <span class="comment"> /// Runs at the currently selected speed until the target position is reached</span>
<a name="l00210"></a>00210 <span class="comment"> /// Does not implement accelerations.</span>
<a name="l00211"></a>00211 <span class="comment"></span> <span class="keywordtype">boolean</span> <a class="code" href="classAccelStepper.html#9270d20336e76ac1fd5bcd5b9c34f301">runSpeedToPosition</a>();
<a name="l00212"></a>00212 <span class="comment"></span>
<a name="l00213"></a>00213 <span class="comment"> /// Moves the motor to the new target position and blocks until it is at</span>
<a name="l00214"></a>00214 <span class="comment"> /// position. Dont use this in event loops, since it blocks.</span>
<a name="l00215"></a>00215 <span class="comment"> /// \param[in] position The new target position.</span>
<a name="l00216"></a>00216 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#176c5d2e4c2f21e9e92b12e39a6f0e67">runToNewPosition</a>(<span class="keywordtype">long</span> position);
<a name="l00217"></a>00217 <span class="comment"></span>
<a name="l00218"></a>00218 <span class="comment"> /// Disable motor pin outputs by setting them all LOW</span>
<a name="l00219"></a>00219 <span class="comment"> /// Depending on the design of your electronics this may turn off</span>
<a name="l00220"></a>00220 <span class="comment"> /// the power to the motor coils, saving power.</span>
<a name="l00221"></a>00221 <span class="comment"> /// This is useful to support Arduino low power modes: disable the outputs</span>
<a name="l00222"></a>00222 <span class="comment"> /// during sleep and then reenable with enableOutputs() before stepping</span>
<a name="l00223"></a>00223 <span class="comment"> /// again.</span>
<a name="l00224"></a>00224 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#3591e29a236e2935afd7f64ff6c22006">disableOutputs</a>();
<a name="l00225"></a>00225 <span class="comment"></span>
<a name="l00226"></a>00226 <span class="comment"> /// Enable motor pin outputs by setting the motor pins to OUTPUT</span>
<a name="l00227"></a>00227 <span class="comment"> /// mode. Called automatically by the constructor.</span>
<a name="l00228"></a>00228 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#a279a50d30d0413f570c692cff071643">enableOutputs</a>();
<a name="l00229"></a>00229
<a name="l00230"></a>00230 <span class="keyword">protected</span>:
<a name="l00231"></a>00231 <span class="comment"></span>
<a name="l00232"></a>00232 <span class="comment"> /// Forces the library to compute a new instantaneous speed and set that as</span>
<a name="l00233"></a>00233 <span class="comment"> /// the current speed. Calls</span>
<a name="l00234"></a>00234 <span class="comment"> /// desiredSpeed(), which can be overridden by subclasses. It is called by</span>
<a name="l00235"></a>00235 <span class="comment"> /// the library:</span>
<a name="l00236"></a>00236 <span class="comment"> /// \li after each step</span>
<a name="l00237"></a>00237 <span class="comment"> /// \li after change to maxSpeed through setMaxSpeed()</span>
<a name="l00238"></a>00238 <span class="comment"> /// \li after change to acceleration through setAcceleration()</span>
<a name="l00239"></a>00239 <span class="comment"> /// \li after change to target position (relative or absolute) through</span>
<a name="l00240"></a>00240 <span class="comment"> /// move() or moveTo()</span>
<a name="l00241"></a>00241 <span class="comment"></span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#ffbee789b5c19165846cf0409860ae79">computeNewSpeed</a>();
<a name="l00242"></a>00242 <span class="comment"></span>
<a name="l00243"></a>00243 <span class="comment"> /// Called to execute a step. Only called when a new step is</span>
<a name="l00244"></a>00244 <span class="comment"> /// required. Subclasses may override to implement new stepping</span>
<a name="l00245"></a>00245 <span class="comment"> /// interfaces. The default calls step1(), step2() or step4() depending on the</span>
<a name="l00246"></a>00246 <span class="comment"> /// number of pins defined for the stepper.</span>
<a name="l00247"></a>00247 <span class="comment"> /// \param[in] step The current step phase number (0 to 3)</span>
<a name="l00248"></a>00248 <span class="comment"></span> <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#3c9a220819d2451f79ff8a0c0a395b9f">step</a>(uint8_t <a class="code" href="classAccelStepper.html#3c9a220819d2451f79ff8a0c0a395b9f">step</a>);
<a name="l00249"></a>00249
<a name="l00250"></a>00250 <span class="comment"></span>
<a name="l00251"></a>00251 <span class="comment"> /// Called to execute a step on a stepper drover (ie where pins == 1). Only called when a new step is</span>
<a name="l00252"></a>00252 <span class="comment"> /// required. Subclasses may override to implement new stepping</span>
<a name="l00253"></a>00253 <span class="comment"> /// interfaces. The default sets or clears the outputs of Step pin1 to step, </span>
<a name="l00254"></a>00254 <span class="comment"> /// and sets the output of _pin2 to the desired direction. The Step pin (_pin1) is pulsed for 1 microsecond</span>
<a name="l00255"></a>00255 <span class="comment"> /// which is the minimum STEP pulse width for the 3967 driver.</span>
<a name="l00256"></a>00256 <span class="comment"> /// \param[in] step The current step phase number (0 to 3)</span>
<a name="l00257"></a>00257 <span class="comment"></span> <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#cc64254ea242b53588e948335fd9305f">step1</a>(uint8_t step);
<a name="l00258"></a>00258 <span class="comment"></span>
<a name="l00259"></a>00259 <span class="comment"> /// Called to execute a step on a 2 pin motor. Only called when a new step is</span>
<a name="l00260"></a>00260 <span class="comment"> /// required. Subclasses may override to implement new stepping</span>
<a name="l00261"></a>00261 <span class="comment"> /// interfaces. The default sets or clears the outputs of pin1 and pin2</span>
<a name="l00262"></a>00262 <span class="comment"> /// \param[in] step The current step phase number (0 to 3)</span>
<a name="l00263"></a>00263 <span class="comment"></span> <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#88f11bf6361fe002585f731d34fe2e8b">step2</a>(uint8_t step);
<a name="l00264"></a>00264 <span class="comment"></span>
<a name="l00265"></a>00265 <span class="comment"> /// Called to execute a step on a 4 pin motor. Only called when a new step is</span>
<a name="l00266"></a>00266 <span class="comment"> /// required. Subclasses may override to implement new stepping</span>
<a name="l00267"></a>00267 <span class="comment"> /// interfaces. The default sets or clears the outputs of pin1, pin2,</span>
<a name="l00268"></a>00268 <span class="comment"> /// pin3, pin4.</span>
<a name="l00269"></a>00269 <span class="comment"> /// \param[in] step The current step phase number (0 to 3)</span>
<a name="l00270"></a>00270 <span class="comment"></span> <span class="keyword">virtual</span> <span class="keywordtype">void</span> <a class="code" href="classAccelStepper.html#49e448d179bbe4e0f8003a3f9993789d">step4</a>(uint8_t step);
<a name="l00271"></a>00271 <span class="comment"></span>
<a name="l00272"></a>00272 <span class="comment"> /// Compute and return the desired speed. The default algorithm uses</span>
<a name="l00273"></a>00273 <span class="comment"> /// maxSpeed, acceleration and the current speed to set a new speed to</span>
<a name="l00274"></a>00274 <span class="comment"> /// move the motor from teh current position to the target</span>
<a name="l00275"></a>00275 <span class="comment"> /// position. Subclasses may override this to provide an alternate</span>
<a name="l00276"></a>00276 <span class="comment"> /// algorithm (but do not block). Called by computeNewSpeed whenever a new speed neds to be</span>
<a name="l00277"></a>00277 <span class="comment"> /// computed. </span>
<a name="l00278"></a>00278 <span class="comment"></span> <span class="keyword">virtual</span> <span class="keywordtype">float</span> <a class="code" href="classAccelStepper.html#6e4bd79c395e69beee31d76d0d3287e4">desiredSpeed</a>();
<a name="l00279"></a>00279
<a name="l00280"></a>00280 <span class="keyword">private</span>:<span class="comment"></span>
<a name="l00281"></a>00281 <span class="comment"> /// Number of pins on the stepper motor. Permits 2 or 4. 2 pins is a</span>
<a name="l00282"></a>00282 <span class="comment"> /// bipolar, and 4 pins is a unipolar.</span>
<a name="l00283"></a>00283 <span class="comment"></span> uint8_t _pins; <span class="comment">// 2 or 4</span>
<a name="l00284"></a>00284 <span class="comment"></span>
<a name="l00285"></a>00285 <span class="comment"> /// Arduino pin number for the 2 or 4 pins required to interface to the</span>
<a name="l00286"></a>00286 <span class="comment"> /// stepper motor.</span>
<a name="l00287"></a>00287 <span class="comment"></span> uint8_t _pin1, _pin2, _pin3, _pin4;
<a name="l00288"></a>00288 <span class="comment"></span>
<a name="l00289"></a>00289 <span class="comment"> /// The current absolution position in steps.</span>
<a name="l00290"></a>00290 <span class="comment"></span> <span class="keywordtype">long</span> _currentPos; <span class="comment">// Steps</span>
<a name="l00291"></a>00291 <span class="comment"></span>
<a name="l00292"></a>00292 <span class="comment"> /// The target position in steps. The AccelStepper library will move the</span>
<a name="l00293"></a>00293 <span class="comment"> /// motor from teh _currentPos to the _targetPos, taking into account the</span>
<a name="l00294"></a>00294 <span class="comment"> /// max speed, acceleration and deceleration</span>
<a name="l00295"></a>00295 <span class="comment"></span> <span class="keywordtype">long</span> _targetPos; <span class="comment">// Steps</span>
<a name="l00296"></a>00296 <span class="comment"></span>
<a name="l00297"></a>00297 <span class="comment"> /// The current motos speed in steps per second</span>
<a name="l00298"></a>00298 <span class="comment"> /// Positive is clockwise</span>
<a name="l00299"></a>00299 <span class="comment"></span> <span class="keywordtype">float</span> _speed; <span class="comment">// Steps per second</span>
<a name="l00300"></a>00300 <span class="comment"></span>
<a name="l00301"></a>00301 <span class="comment"> /// The maximum permitted speed in steps per second. Must be &gt; 0.</span>
<a name="l00302"></a>00302 <span class="comment"></span> <span class="keywordtype">float</span> _maxSpeed;
<a name="l00303"></a>00303 <span class="comment"></span>
<a name="l00304"></a>00304 <span class="comment"> /// The acceleration to use to accelerate or decelerate the motor in steps</span>
<a name="l00305"></a>00305 <span class="comment"> /// per second per second. Must be &gt; 0</span>
<a name="l00306"></a>00306 <span class="comment"></span> <span class="keywordtype">float</span> _acceleration;
<a name="l00307"></a>00307 <span class="comment"></span>
<a name="l00308"></a>00308 <span class="comment"> /// The current interval between steps in milliseconds.</span>
<a name="l00309"></a>00309 <span class="comment"></span> <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> _stepInterval;
<a name="l00310"></a>00310 <span class="comment"></span>
<a name="l00311"></a>00311 <span class="comment"> /// The last step time in milliseconds</span>
<a name="l00312"></a>00312 <span class="comment"></span> <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> _lastStepTime;
<a name="l00313"></a>00313 };
<a name="l00314"></a>00314
<a name="l00315"></a>00315 <span class="preprocessor">#endif </span>
</pre></div></div>
<hr size="1"><address style="text-align: right;"><small>Generated on Sun Oct 24 18:22:50 2010 for AccelStepper by&nbsp;
<a href="http://www.doxygen.org/index.html">
<img src="doxygen.png" alt="doxygen" align="middle" border="0"></a> 1.5.6 </small></address>
</body>
</html>

View File

@ -0,0 +1,32 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
<html><head><meta http-equiv="Content-Type" content="text/html;charset=UTF-8">
<title>AccelStepper: Class List</title>
<link href="doxygen.css" rel="stylesheet" type="text/css">
<link href="tabs.css" rel="stylesheet" type="text/css">
</head><body>
<!-- Generated by Doxygen 1.5.6 -->
<div class="navigation" id="top">
<div class="tabs">
<ul>
<li><a href="index.html"><span>Main&nbsp;Page</span></a></li>
<li class="current"><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div class="tabs">
<ul>
<li class="current"><a href="annotated.html"><span>Class&nbsp;List</span></a></li>
<li><a href="functions.html"><span>Class&nbsp;Members</span></a></li>
</ul>
</div>
</div>
<div class="contents">
<h1>Class List</h1>Here are the classes, structs, unions and interfaces with brief descriptions:<table>
<tr><td class="indexkey"><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td class="indexvalue">Support for stepper motors with acceleration etc </td></tr>
</table>
</div>
<hr size="1"><address style="text-align: right;"><small>Generated on Sun Oct 24 18:22:50 2010 for AccelStepper by&nbsp;
<a href="http://www.doxygen.org/index.html">
<img src="doxygen.png" alt="doxygen" align="middle" border="0"></a> 1.5.6 </small></address>
</body>
</html>

View File

@ -0,0 +1,54 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
<html><head><meta http-equiv="Content-Type" content="text/html;charset=UTF-8">
<title>AccelStepper: Member List</title>
<link href="doxygen.css" rel="stylesheet" type="text/css">
<link href="tabs.css" rel="stylesheet" type="text/css">
</head><body>
<!-- Generated by Doxygen 1.5.6 -->
<div class="navigation" id="top">
<div class="tabs">
<ul>
<li><a href="index.html"><span>Main&nbsp;Page</span></a></li>
<li class="current"><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div class="tabs">
<ul>
<li><a href="annotated.html"><span>Class&nbsp;List</span></a></li>
<li><a href="functions.html"><span>Class&nbsp;Members</span></a></li>
</ul>
</div>
</div>
<div class="contents">
<h1>AccelStepper Member List</h1>This is the complete list of members for <a class="el" href="classAccelStepper.html">AccelStepper</a>, including all inherited members.<p><table>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#a1290897df35915069e5eca9d034038c">AccelStepper</a>(uint8_t pins=4, uint8_t pin1=2, uint8_t pin2=3, uint8_t pin3=4, uint8_t pin4=5)</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#ffbee789b5c19165846cf0409860ae79">computeNewSpeed</a>()</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td><code> [protected]</code></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#5dce13ab2a1b02b8f443318886bf6fc5">currentPosition</a>()</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#6e4bd79c395e69beee31d76d0d3287e4">desiredSpeed</a>()</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td><code> [protected, virtual]</code></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#3591e29a236e2935afd7f64ff6c22006">disableOutputs</a>()</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#748665c3962e66fbc0e9373eb14c69c1">distanceToGo</a>()</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#a279a50d30d0413f570c692cff071643">enableOutputs</a>()</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#68942c66e78fb7f7b5f0cdade6eb7f06">move</a>(long relative)</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#ce236ede35f87c63d18da25810ec9736">moveTo</a>(long absolute)</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#608b2395b64ac15451d16d0371fe13ce">run</a>()</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#a4a6bdf99f698284faaeb5542b0b7514">runSpeed</a>()</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#9270d20336e76ac1fd5bcd5b9c34f301">runSpeedToPosition</a>()</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#176c5d2e4c2f21e9e92b12e39a6f0e67">runToNewPosition</a>(long position)</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#344f58fef8cc34ac5aa75ba4b665d21c">runToPosition</a>()</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#dfb19e3cd2a028a1fe78131787604fd1">setAcceleration</a>(float acceleration)</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#9d917f014317fb9d3b5dc14e66f6c689">setCurrentPosition</a>(long position)</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#bee8d466229b87accba33d6ec929c18f">setMaxSpeed</a>(float speed)</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#e79c49ad69d5ccc9da0ee691fa4ca235">setSpeed</a>(float speed)</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#4f0989d0ae264e7eadfe1fa720769fb6">speed</a>()</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#3c9a220819d2451f79ff8a0c0a395b9f">step</a>(uint8_t step)</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td><code> [protected, virtual]</code></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#cc64254ea242b53588e948335fd9305f">step1</a>(uint8_t step)</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td><code> [protected, virtual]</code></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#88f11bf6361fe002585f731d34fe2e8b">step2</a>(uint8_t step)</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td><code> [protected, virtual]</code></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#49e448d179bbe4e0f8003a3f9993789d">step4</a>(uint8_t step)</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td><code> [protected, virtual]</code></td></tr>
<tr class="memlist"><td><a class="el" href="classAccelStepper.html#96685e0945b7cf75d5959da679cd911e">targetPosition</a>()</td><td><a class="el" href="classAccelStepper.html">AccelStepper</a></td><td></td></tr>
</table></div>
<hr size="1"><address style="text-align: right;"><small>Generated on Sun Oct 24 18:22:50 2010 for AccelStepper by&nbsp;
<a href="http://www.doxygen.org/index.html">
<img src="doxygen.png" alt="doxygen" align="middle" border="0"></a> 1.5.6 </small></address>
</body>
</html>

View File

@ -0,0 +1,723 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
<html><head><meta http-equiv="Content-Type" content="text/html;charset=UTF-8">
<title>AccelStepper: AccelStepper Class Reference</title>
<link href="doxygen.css" rel="stylesheet" type="text/css">
<link href="tabs.css" rel="stylesheet" type="text/css">
</head><body>
<!-- Generated by Doxygen 1.5.6 -->
<div class="navigation" id="top">
<div class="tabs">
<ul>
<li><a href="index.html"><span>Main&nbsp;Page</span></a></li>
<li class="current"><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div class="tabs">
<ul>
<li><a href="annotated.html"><span>Class&nbsp;List</span></a></li>
<li><a href="functions.html"><span>Class&nbsp;Members</span></a></li>
</ul>
</div>
</div>
<div class="contents">
<h1>AccelStepper Class Reference</h1><!-- doxytag: class="AccelStepper" -->Support for stepper motors with acceleration etc.
<a href="#_details">More...</a>
<p>
<code>#include &lt;<a class="el" href="AccelStepper_8h-source.html">AccelStepper.h</a>&gt;</code>
<p>
<p>
<a href="classAccelStepper-members.html">List of all members.</a><table border="0" cellpadding="0" cellspacing="0">
<tr><td></td></tr>
<tr><td colspan="2"><br><h2>Public Member Functions</h2></td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#a1290897df35915069e5eca9d034038c">AccelStepper</a> (uint8_t pins=4, uint8_t pin1=2, uint8_t pin2=3, uint8_t pin3=4, uint8_t pin4=5)</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#ce236ede35f87c63d18da25810ec9736">moveTo</a> (long absolute)</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#68942c66e78fb7f7b5f0cdade6eb7f06">move</a> (long relative)</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">boolean&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#608b2395b64ac15451d16d0371fe13ce">run</a> ()</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">boolean&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#a4a6bdf99f698284faaeb5542b0b7514">runSpeed</a> ()</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#bee8d466229b87accba33d6ec929c18f">setMaxSpeed</a> (float speed)</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#dfb19e3cd2a028a1fe78131787604fd1">setAcceleration</a> (float acceleration)</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#e79c49ad69d5ccc9da0ee691fa4ca235">setSpeed</a> (float speed)</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">float&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#4f0989d0ae264e7eadfe1fa720769fb6">speed</a> ()</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">long&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#748665c3962e66fbc0e9373eb14c69c1">distanceToGo</a> ()</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">long&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#96685e0945b7cf75d5959da679cd911e">targetPosition</a> ()</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">long&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#5dce13ab2a1b02b8f443318886bf6fc5">currentPosition</a> ()</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#9d917f014317fb9d3b5dc14e66f6c689">setCurrentPosition</a> (long position)</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#344f58fef8cc34ac5aa75ba4b665d21c">runToPosition</a> ()</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">boolean&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#9270d20336e76ac1fd5bcd5b9c34f301">runSpeedToPosition</a> ()</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#176c5d2e4c2f21e9e92b12e39a6f0e67">runToNewPosition</a> (long position)</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#3591e29a236e2935afd7f64ff6c22006">disableOutputs</a> ()</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#a279a50d30d0413f570c692cff071643">enableOutputs</a> ()</td></tr>
<tr><td colspan="2"><br><h2>Protected Member Functions</h2></td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#ffbee789b5c19165846cf0409860ae79">computeNewSpeed</a> ()</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">virtual void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#3c9a220819d2451f79ff8a0c0a395b9f">step</a> (uint8_t step)</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">virtual void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#cc64254ea242b53588e948335fd9305f">step1</a> (uint8_t step)</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">virtual void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#88f11bf6361fe002585f731d34fe2e8b">step2</a> (uint8_t step)</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">virtual void&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#49e448d179bbe4e0f8003a3f9993789d">step4</a> (uint8_t step)</td></tr>
<tr><td class="memItemLeft" nowrap align="right" valign="top">virtual float&nbsp;</td><td class="memItemRight" valign="bottom"><a class="el" href="classAccelStepper.html#6e4bd79c395e69beee31d76d0d3287e4">desiredSpeed</a> ()</td></tr>
</table>
<hr><a name="_details"></a><h2>Detailed Description</h2>
Support for stepper motors with acceleration etc.
<p>
This defines a single 2 or 4 pin stepper motor, or stepper moter with fdriver chip, with optional acceleration, deceleration, absolute positioning commands etc. Multiple simultaneous steppers are supported, all moving at different speeds and accelerations.<p>
<dl class="user" compact><dt><b>Operation</b></dt><dd>This module operates by computing a step time in milliseconds. The step time is recomputed after each step and after speed and acceleration parameters are changed by the caller. The time of each step is recorded in milliseconds. The <a class="el" href="classAccelStepper.html#608b2395b64ac15451d16d0371fe13ce">run()</a> function steps the motor if a new step is due. The <a class="el" href="classAccelStepper.html#608b2395b64ac15451d16d0371fe13ce">run()</a> function must be called frequently until the motor is in the desired position, after which time <a class="el" href="classAccelStepper.html#608b2395b64ac15451d16d0371fe13ce">run()</a> will do nothing.</dd></dl>
<dl class="user" compact><dt><b>Positioning</b></dt><dd>Positions are specified by a signed long integer. At construction time, the current position of the motor is consider to be 0. Positive positions are clockwise from the initial position; negative positions are anticlockwise. The curent position can be altered for instance after initialization positioning.</dd></dl>
<dl class="user" compact><dt><b>Caveats</b></dt><dd>This is an open loop controller: If the motor stalls or is oversped, <a class="el" href="classAccelStepper.html" title="Support for stepper motors with acceleration etc.">AccelStepper</a> will not have a correct idea of where the motor really is (since there is no feedback of the motor's real position. We only know where we _think_ it is, relative to the initial starting point).</dd></dl>
The fastest motor speed that can be reliably supported is 1000 steps per second (1 step every millisecond). However any speed less than that down to very slow speeds (much less than one per second) are supported, provided the <a class="el" href="classAccelStepper.html#608b2395b64ac15451d16d0371fe13ce">run()</a> function is called frequently enough to step the motor whenever required. <hr><h2>Constructor &amp; Destructor Documentation</h2>
<a class="anchor" name="a1290897df35915069e5eca9d034038c"></a><!-- doxytag: member="AccelStepper::AccelStepper" ref="a1290897df35915069e5eca9d034038c" args="(uint8_t pins=4, uint8_t pin1=2, uint8_t pin2=3, uint8_t pin3=4, uint8_t pin4=5)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">AccelStepper::AccelStepper </td>
<td>(</td>
<td class="paramtype">uint8_t&nbsp;</td>
<td class="paramname"> <em>pins</em> = <code>4</code>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">uint8_t&nbsp;</td>
<td class="paramname"> <em>pin1</em> = <code>2</code>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">uint8_t&nbsp;</td>
<td class="paramname"> <em>pin2</em> = <code>3</code>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">uint8_t&nbsp;</td>
<td class="paramname"> <em>pin3</em> = <code>4</code>, </td>
</tr>
<tr>
<td class="paramkey"></td>
<td></td>
<td class="paramtype">uint8_t&nbsp;</td>
<td class="paramname"> <em>pin4</em> = <code>5</code></td><td>&nbsp;</td>
</tr>
<tr>
<td></td>
<td>)</td>
<td></td><td></td><td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Constructor. You can have multiple simultaneous steppers, all moving at different speeds and accelerations, provided you call their <a class="el" href="classAccelStepper.html#608b2395b64ac15451d16d0371fe13ce">run()</a> functions at frequent enough intervals. Current Position is set to 0, target position is set to 0. MaxSpeed and Acceleration default to 1.0. The motor pins will be initialised to OUTPUT mode during the constructor by a call to <a class="el" href="classAccelStepper.html#a279a50d30d0413f570c692cff071643">enableOutputs()</a>. <dl compact><dt><b>Parameters:</b></dt><dd>
<table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"><tt>[in]</tt>&nbsp;</td><td valign="top"><em>pins</em>&nbsp;</td><td>Number of pins to interface to. 1, 2 or 4 are supported. 1 means a stepper driver (with Step and Direction pins) 2 means a 2 wire stepper. 4 means a 4 wire stepper. Defaults to 4 pins. </td></tr>
<tr><td valign="top"><tt>[in]</tt>&nbsp;</td><td valign="top"><em>pin1</em>&nbsp;</td><td>Arduino digital pin number for motor pin 1. Defaults to pin 2. For a driver (pins==1), this is the Step input to the driver. Low to high transition means to step) </td></tr>
<tr><td valign="top"><tt>[in]</tt>&nbsp;</td><td valign="top"><em>pin2</em>&nbsp;</td><td>Arduino digital pin number for motor pin 2. Defaults to pin 3. For a driver (pins==1), this is the Direction input the driver. High means forward. </td></tr>
<tr><td valign="top"><tt>[in]</tt>&nbsp;</td><td valign="top"><em>pin3</em>&nbsp;</td><td>Arduino digital pin number for motor pin 3. Defaults to pin 4. </td></tr>
<tr><td valign="top"><tt>[in]</tt>&nbsp;</td><td valign="top"><em>pin4</em>&nbsp;</td><td>Arduino digital pin number for motor pin 4. Defaults to pin 5. </td></tr>
</table>
</dl>
<p>References <a class="el" href="AccelStepper_8cpp-source.html#l00287">enableOutputs()</a>.</p>
</div>
</div><p>
<hr><h2>Member Function Documentation</h2>
<a class="anchor" name="ce236ede35f87c63d18da25810ec9736"></a><!-- doxytag: member="AccelStepper::moveTo" ref="ce236ede35f87c63d18da25810ec9736" args="(long absolute)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void AccelStepper::moveTo </td>
<td>(</td>
<td class="paramtype">long&nbsp;</td>
<td class="paramname"> <em>absolute</em> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Set the target position. The <a class="el" href="classAccelStepper.html#608b2395b64ac15451d16d0371fe13ce">run()</a> function will try to move the motor from the current position to the target position set by the most recent call to this function. <dl compact><dt><b>Parameters:</b></dt><dd>
<table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"><tt>[in]</tt>&nbsp;</td><td valign="top"><em>absolute</em>&nbsp;</td><td>The desired absolute position. Negative is anticlockwise from the 0 position. </td></tr>
</table>
</dl>
<p>References <a class="el" href="AccelStepper_8cpp-source.html#l00069">computeNewSpeed()</a>.</p>
<p>Referenced by <a class="el" href="AccelStepper_8cpp-source.html#l00015">move()</a>, and <a class="el" href="AccelStepper_8cpp-source.html#l00311">runToNewPosition()</a>.</p>
</div>
</div><p>
<a class="anchor" name="68942c66e78fb7f7b5f0cdade6eb7f06"></a><!-- doxytag: member="AccelStepper::move" ref="68942c66e78fb7f7b5f0cdade6eb7f06" args="(long relative)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void AccelStepper::move </td>
<td>(</td>
<td class="paramtype">long&nbsp;</td>
<td class="paramname"> <em>relative</em> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Set the target position relative to the current position <dl compact><dt><b>Parameters:</b></dt><dd>
<table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"><tt>[in]</tt>&nbsp;</td><td valign="top"><em>relative</em>&nbsp;</td><td>The desired position relative to the current position. Negative is anticlockwise from the current position. </td></tr>
</table>
</dl>
<p>References <a class="el" href="AccelStepper_8cpp-source.html#l00009">moveTo()</a>.</p>
</div>
</div><p>
<a class="anchor" name="608b2395b64ac15451d16d0371fe13ce"></a><!-- doxytag: member="AccelStepper::run" ref="608b2395b64ac15451d16d0371fe13ce" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">boolean AccelStepper::run </td>
<td>(</td>
<td class="paramname"> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Poll the motor and step it if a step is due, implementing accelerations and decelerations to achive the ratget position. You must call this as fequently as possible, but at least once per minimum step interval, preferably in your main loop. <dl class="return" compact><dt><b>Returns:</b></dt><dd>true if the motor is at the target position. </dd></dl>
<p>References <a class="el" href="AccelStepper_8cpp-source.html#l00069">computeNewSpeed()</a>, and <a class="el" href="AccelStepper_8cpp-source.html#l00023">runSpeed()</a>.</p>
<p>Referenced by <a class="el" href="AccelStepper_8cpp-source.html#l00299">runToPosition()</a>.</p>
</div>
</div><p>
<a class="anchor" name="a4a6bdf99f698284faaeb5542b0b7514"></a><!-- doxytag: member="AccelStepper::runSpeed" ref="a4a6bdf99f698284faaeb5542b0b7514" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">boolean AccelStepper::runSpeed </td>
<td>(</td>
<td class="paramname"> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Poll the motor and step it if a step is due, implmenting a constant speed as set by the most recent call to <a class="el" href="classAccelStepper.html#e79c49ad69d5ccc9da0ee691fa4ca235">setSpeed()</a>. <dl class="return" compact><dt><b>Returns:</b></dt><dd>true if the motor was stepped. </dd></dl>
<p>References <a class="el" href="AccelStepper_8cpp-source.html#l00176">step()</a>.</p>
<p>Referenced by <a class="el" href="AccelStepper_8cpp-source.html#l00125">run()</a>, and <a class="el" href="AccelStepper_8cpp-source.html#l00305">runSpeedToPosition()</a>.</p>
</div>
</div><p>
<a class="anchor" name="bee8d466229b87accba33d6ec929c18f"></a><!-- doxytag: member="AccelStepper::setMaxSpeed" ref="bee8d466229b87accba33d6ec929c18f" args="(float speed)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void AccelStepper::setMaxSpeed </td>
<td>(</td>
<td class="paramtype">float&nbsp;</td>
<td class="paramname"> <em>speed</em> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Sets the maximum permitted speed. the <a class="el" href="classAccelStepper.html#608b2395b64ac15451d16d0371fe13ce">run()</a> function will accelerate up to the speed set by this function. <dl compact><dt><b>Parameters:</b></dt><dd>
<table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"><tt>[in]</tt>&nbsp;</td><td valign="top"><em>speed</em>&nbsp;</td><td>The desired maximum speed in steps per second. Must be &gt; 0. Speeds of more than 1000 steps per second are unreliable. </td></tr>
</table>
</dl>
<p>References <a class="el" href="AccelStepper_8cpp-source.html#l00069">computeNewSpeed()</a>.</p>
</div>
</div><p>
<a class="anchor" name="dfb19e3cd2a028a1fe78131787604fd1"></a><!-- doxytag: member="AccelStepper::setAcceleration" ref="dfb19e3cd2a028a1fe78131787604fd1" args="(float acceleration)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void AccelStepper::setAcceleration </td>
<td>(</td>
<td class="paramtype">float&nbsp;</td>
<td class="paramname"> <em>acceleration</em> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Sets the acceleration and deceleration parameter. <dl compact><dt><b>Parameters:</b></dt><dd>
<table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"><tt>[in]</tt>&nbsp;</td><td valign="top"><em>acceleration</em>&nbsp;</td><td>The desired acceleration in steps per second per second. Must be &gt; 0. </td></tr>
</table>
</dl>
<p>References <a class="el" href="AccelStepper_8cpp-source.html#l00069">computeNewSpeed()</a>.</p>
</div>
</div><p>
<a class="anchor" name="e79c49ad69d5ccc9da0ee691fa4ca235"></a><!-- doxytag: member="AccelStepper::setSpeed" ref="e79c49ad69d5ccc9da0ee691fa4ca235" args="(float speed)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void AccelStepper::setSpeed </td>
<td>(</td>
<td class="paramtype">float&nbsp;</td>
<td class="paramname"> <em>speed</em> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Sets the desired constant speed for use with <a class="el" href="classAccelStepper.html#a4a6bdf99f698284faaeb5542b0b7514">runSpeed()</a>. <dl compact><dt><b>Parameters:</b></dt><dd>
<table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"><tt>[in]</tt>&nbsp;</td><td valign="top"><em>speed</em>&nbsp;</td><td>The desired constant speed in steps per second. Positive is clockwise. Speeds of more than 1000 steps per second are unreliable. Very slow speeds may be set (eg 0.00027777 for once per hour, approximately. Speed accuracy depends on the Arduino crystal. Jitter depends on how frequently you call the <a class="el" href="classAccelStepper.html#a4a6bdf99f698284faaeb5542b0b7514">runSpeed()</a> function. </td></tr>
</table>
</dl>
<p>Referenced by <a class="el" href="AccelStepper_8cpp-source.html#l00069">computeNewSpeed()</a>.</p>
</div>
</div><p>
<a class="anchor" name="4f0989d0ae264e7eadfe1fa720769fb6"></a><!-- doxytag: member="AccelStepper::speed" ref="4f0989d0ae264e7eadfe1fa720769fb6" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">float AccelStepper::speed </td>
<td>(</td>
<td class="paramname"> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
The most recently set speed <dl class="return" compact><dt><b>Returns:</b></dt><dd>the most recent speed in steps per second </dd></dl>
</div>
</div><p>
<a class="anchor" name="748665c3962e66fbc0e9373eb14c69c1"></a><!-- doxytag: member="AccelStepper::distanceToGo" ref="748665c3962e66fbc0e9373eb14c69c1" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">long AccelStepper::distanceToGo </td>
<td>(</td>
<td class="paramname"> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
The distance from the current position to the target position. <dl class="return" compact><dt><b>Returns:</b></dt><dd>the distance from the current position to the target position in steps. Positive is clockwise from the current position. </dd></dl>
<p>Referenced by <a class="el" href="AccelStepper_8cpp-source.html#l00084">desiredSpeed()</a>.</p>
</div>
</div><p>
<a class="anchor" name="96685e0945b7cf75d5959da679cd911e"></a><!-- doxytag: member="AccelStepper::targetPosition" ref="96685e0945b7cf75d5959da679cd911e" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">long AccelStepper::targetPosition </td>
<td>(</td>
<td class="paramname"> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
The most recently set target position. <dl class="return" compact><dt><b>Returns:</b></dt><dd>the target position in steps. Positive is clockwise from the 0 position. </dd></dl>
</div>
</div><p>
<a class="anchor" name="5dce13ab2a1b02b8f443318886bf6fc5"></a><!-- doxytag: member="AccelStepper::currentPosition" ref="5dce13ab2a1b02b8f443318886bf6fc5" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">long AccelStepper::currentPosition </td>
<td>(</td>
<td class="paramname"> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
The currently motor position. <dl class="return" compact><dt><b>Returns:</b></dt><dd>the current motor position in steps. Positive is clockwise from the 0 position. </dd></dl>
</div>
</div><p>
<a class="anchor" name="9d917f014317fb9d3b5dc14e66f6c689"></a><!-- doxytag: member="AccelStepper::setCurrentPosition" ref="9d917f014317fb9d3b5dc14e66f6c689" args="(long position)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void AccelStepper::setCurrentPosition </td>
<td>(</td>
<td class="paramtype">long&nbsp;</td>
<td class="paramname"> <em>position</em> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Resets the current position of the motor, so that wherever the mottor happens to be right now is considered to be the new position. Useful for setting a zero position on a stepper after an initial hardware positioning move. <dl compact><dt><b>Parameters:</b></dt><dd>
<table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"><tt>[in]</tt>&nbsp;</td><td valign="top"><em>position</em>&nbsp;</td><td>The position in steps of wherever the motor happens to be right now. </td></tr>
</table>
</dl>
</div>
</div><p>
<a class="anchor" name="344f58fef8cc34ac5aa75ba4b665d21c"></a><!-- doxytag: member="AccelStepper::runToPosition" ref="344f58fef8cc34ac5aa75ba4b665d21c" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void AccelStepper::runToPosition </td>
<td>(</td>
<td class="paramname"> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Moves the motor to the target position and blocks until it is at position. Dont use this in event loops, since it blocks.
<p>References <a class="el" href="AccelStepper_8cpp-source.html#l00125">run()</a>.</p>
<p>Referenced by <a class="el" href="AccelStepper_8cpp-source.html#l00311">runToNewPosition()</a>.</p>
</div>
</div><p>
<a class="anchor" name="9270d20336e76ac1fd5bcd5b9c34f301"></a><!-- doxytag: member="AccelStepper::runSpeedToPosition" ref="9270d20336e76ac1fd5bcd5b9c34f301" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">boolean AccelStepper::runSpeedToPosition </td>
<td>(</td>
<td class="paramname"> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Runs at the currently selected speed until the target position is reached Does not implement accelerations.
<p>References <a class="el" href="AccelStepper_8cpp-source.html#l00023">runSpeed()</a>.</p>
</div>
</div><p>
<a class="anchor" name="176c5d2e4c2f21e9e92b12e39a6f0e67"></a><!-- doxytag: member="AccelStepper::runToNewPosition" ref="176c5d2e4c2f21e9e92b12e39a6f0e67" args="(long position)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void AccelStepper::runToNewPosition </td>
<td>(</td>
<td class="paramtype">long&nbsp;</td>
<td class="paramname"> <em>position</em> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Moves the motor to the new target position and blocks until it is at position. Dont use this in event loops, since it blocks. <dl compact><dt><b>Parameters:</b></dt><dd>
<table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"><tt>[in]</tt>&nbsp;</td><td valign="top"><em>position</em>&nbsp;</td><td>The new target position. </td></tr>
</table>
</dl>
<p>References <a class="el" href="AccelStepper_8cpp-source.html#l00009">moveTo()</a>, and <a class="el" href="AccelStepper_8cpp-source.html#l00299">runToPosition()</a>.</p>
</div>
</div><p>
<a class="anchor" name="3591e29a236e2935afd7f64ff6c22006"></a><!-- doxytag: member="AccelStepper::disableOutputs" ref="3591e29a236e2935afd7f64ff6c22006" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void AccelStepper::disableOutputs </td>
<td>(</td>
<td class="paramname"> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Disable motor pin outputs by setting them all LOW Depending on the design of your electronics this may turn off the power to the motor coils, saving power. This is useful to support Arduino low power modes: disable the outputs during sleep and then reenable with <a class="el" href="classAccelStepper.html#a279a50d30d0413f570c692cff071643">enableOutputs()</a> before stepping again.
</div>
</div><p>
<a class="anchor" name="a279a50d30d0413f570c692cff071643"></a><!-- doxytag: member="AccelStepper::enableOutputs" ref="a279a50d30d0413f570c692cff071643" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void AccelStepper::enableOutputs </td>
<td>(</td>
<td class="paramname"> </td>
<td>&nbsp;)&nbsp;</td>
<td></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Enable motor pin outputs by setting the motor pins to OUTPUT mode. Called automatically by the constructor.
<p>Referenced by <a class="el" href="AccelStepper_8cpp-source.html#l00135">AccelStepper()</a>.</p>
</div>
</div><p>
<a class="anchor" name="ffbee789b5c19165846cf0409860ae79"></a><!-- doxytag: member="AccelStepper::computeNewSpeed" ref="ffbee789b5c19165846cf0409860ae79" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void AccelStepper::computeNewSpeed </td>
<td>(</td>
<td class="paramname"> </td>
<td>&nbsp;)&nbsp;</td>
<td><code> [protected]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Forces the library to compute a new instantaneous speed and set that as the current speed. Calls <a class="el" href="classAccelStepper.html#6e4bd79c395e69beee31d76d0d3287e4">desiredSpeed()</a>, which can be overridden by subclasses. It is called by the library: <ul>
<li>after each step </li>
<li>after change to maxSpeed through <a class="el" href="classAccelStepper.html#bee8d466229b87accba33d6ec929c18f">setMaxSpeed()</a> </li>
<li>after change to acceleration through <a class="el" href="classAccelStepper.html#dfb19e3cd2a028a1fe78131787604fd1">setAcceleration()</a> </li>
<li>after change to target position (relative or absolute) through <a class="el" href="classAccelStepper.html#68942c66e78fb7f7b5f0cdade6eb7f06">move()</a> or <a class="el" href="classAccelStepper.html#ce236ede35f87c63d18da25810ec9736">moveTo()</a> </li>
</ul>
<p>References <a class="el" href="AccelStepper_8cpp-source.html#l00084">desiredSpeed()</a>, and <a class="el" href="AccelStepper_8cpp-source.html#l00164">setSpeed()</a>.</p>
<p>Referenced by <a class="el" href="AccelStepper_8cpp-source.html#l00009">moveTo()</a>, <a class="el" href="AccelStepper_8cpp-source.html#l00125">run()</a>, <a class="el" href="AccelStepper_8cpp-source.html#l00158">setAcceleration()</a>, and <a class="el" href="AccelStepper_8cpp-source.html#l00152">setMaxSpeed()</a>.</p>
</div>
</div><p>
<a class="anchor" name="3c9a220819d2451f79ff8a0c0a395b9f"></a><!-- doxytag: member="AccelStepper::step" ref="3c9a220819d2451f79ff8a0c0a395b9f" args="(uint8_t step)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void AccelStepper::step </td>
<td>(</td>
<td class="paramtype">uint8_t&nbsp;</td>
<td class="paramname"> <em>step</em> </td>
<td>&nbsp;)&nbsp;</td>
<td><code> [protected, virtual]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Called to execute a step. Only called when a new step is required. Subclasses may override to implement new stepping interfaces. The default calls <a class="el" href="classAccelStepper.html#cc64254ea242b53588e948335fd9305f">step1()</a>, <a class="el" href="classAccelStepper.html#88f11bf6361fe002585f731d34fe2e8b">step2()</a> or <a class="el" href="classAccelStepper.html#49e448d179bbe4e0f8003a3f9993789d">step4()</a> depending on the number of pins defined for the stepper. <dl compact><dt><b>Parameters:</b></dt><dd>
<table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"><tt>[in]</tt>&nbsp;</td><td valign="top"><em>step</em>&nbsp;</td><td>The current step phase number (0 to 3) </td></tr>
</table>
</dl>
<p>References <a class="el" href="AccelStepper_8cpp-source.html#l00197">step1()</a>, <a class="el" href="AccelStepper_8cpp-source.html#l00211">step2()</a>, and <a class="el" href="AccelStepper_8cpp-source.html#l00240">step4()</a>.</p>
<p>Referenced by <a class="el" href="AccelStepper_8cpp-source.html#l00023">runSpeed()</a>.</p>
</div>
</div><p>
<a class="anchor" name="cc64254ea242b53588e948335fd9305f"></a><!-- doxytag: member="AccelStepper::step1" ref="cc64254ea242b53588e948335fd9305f" args="(uint8_t step)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void AccelStepper::step1 </td>
<td>(</td>
<td class="paramtype">uint8_t&nbsp;</td>
<td class="paramname"> <em>step</em> </td>
<td>&nbsp;)&nbsp;</td>
<td><code> [protected, virtual]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Called to execute a step on a stepper drover (ie where pins == 1). Only called when a new step is required. Subclasses may override to implement new stepping interfaces. The default sets or clears the outputs of Step pin1 to step, and sets the output of _pin2 to the desired direction. The Step pin (_pin1) is pulsed for 1 microsecond which is the minimum STEP pulse width for the 3967 driver. <dl compact><dt><b>Parameters:</b></dt><dd>
<table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"><tt>[in]</tt>&nbsp;</td><td valign="top"><em>step</em>&nbsp;</td><td>The current step phase number (0 to 3) </td></tr>
</table>
</dl>
<p>Referenced by <a class="el" href="AccelStepper_8cpp-source.html#l00176">step()</a>.</p>
</div>
</div><p>
<a class="anchor" name="88f11bf6361fe002585f731d34fe2e8b"></a><!-- doxytag: member="AccelStepper::step2" ref="88f11bf6361fe002585f731d34fe2e8b" args="(uint8_t step)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void AccelStepper::step2 </td>
<td>(</td>
<td class="paramtype">uint8_t&nbsp;</td>
<td class="paramname"> <em>step</em> </td>
<td>&nbsp;)&nbsp;</td>
<td><code> [protected, virtual]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Called to execute a step on a 2 pin motor. Only called when a new step is required. Subclasses may override to implement new stepping interfaces. The default sets or clears the outputs of pin1 and pin2 <dl compact><dt><b>Parameters:</b></dt><dd>
<table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"><tt>[in]</tt>&nbsp;</td><td valign="top"><em>step</em>&nbsp;</td><td>The current step phase number (0 to 3) </td></tr>
</table>
</dl>
<p>Referenced by <a class="el" href="AccelStepper_8cpp-source.html#l00176">step()</a>.</p>
</div>
</div><p>
<a class="anchor" name="49e448d179bbe4e0f8003a3f9993789d"></a><!-- doxytag: member="AccelStepper::step4" ref="49e448d179bbe4e0f8003a3f9993789d" args="(uint8_t step)" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">void AccelStepper::step4 </td>
<td>(</td>
<td class="paramtype">uint8_t&nbsp;</td>
<td class="paramname"> <em>step</em> </td>
<td>&nbsp;)&nbsp;</td>
<td><code> [protected, virtual]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Called to execute a step on a 4 pin motor. Only called when a new step is required. Subclasses may override to implement new stepping interfaces. The default sets or clears the outputs of pin1, pin2, pin3, pin4. <dl compact><dt><b>Parameters:</b></dt><dd>
<table border="0" cellspacing="2" cellpadding="0">
<tr><td valign="top"><tt>[in]</tt>&nbsp;</td><td valign="top"><em>step</em>&nbsp;</td><td>The current step phase number (0 to 3) </td></tr>
</table>
</dl>
<p>Referenced by <a class="el" href="AccelStepper_8cpp-source.html#l00176">step()</a>.</p>
</div>
</div><p>
<a class="anchor" name="6e4bd79c395e69beee31d76d0d3287e4"></a><!-- doxytag: member="AccelStepper::desiredSpeed" ref="6e4bd79c395e69beee31d76d0d3287e4" args="()" -->
<div class="memitem">
<div class="memproto">
<table class="memname">
<tr>
<td class="memname">float AccelStepper::desiredSpeed </td>
<td>(</td>
<td class="paramname"> </td>
<td>&nbsp;)&nbsp;</td>
<td><code> [protected, virtual]</code></td>
</tr>
</table>
</div>
<div class="memdoc">
<p>
Compute and return the desired speed. The default algorithm uses maxSpeed, acceleration and the current speed to set a new speed to move the motor from teh current position to the target position. Subclasses may override this to provide an alternate algorithm (but do not block). Called by computeNewSpeed whenever a new speed neds to be computed.
<p>References <a class="el" href="AccelStepper_8cpp-source.html#l00048">distanceToGo()</a>.</p>
<p>Referenced by <a class="el" href="AccelStepper_8cpp-source.html#l00069">computeNewSpeed()</a>.</p>
</div>
</div><p>
<hr>The documentation for this class was generated from the following files:<ul>
<li><a class="el" href="AccelStepper_8h-source.html">AccelStepper.h</a><li>AccelStepper.cpp</ul>
</div>
<hr size="1"><address style="text-align: right;"><small>Generated on Sun Oct 24 18:22:50 2010 for AccelStepper by&nbsp;
<a href="http://www.doxygen.org/index.html">
<img src="doxygen.png" alt="doxygen" align="middle" border="0"></a> 1.5.6 </small></address>
</body>
</html>

View File

@ -0,0 +1,473 @@
BODY,H1,H2,H3,H4,H5,H6,P,CENTER,TD,TH,UL,DL,DIV {
font-family: Geneva, Arial, Helvetica, sans-serif;
}
BODY,TD {
font-size: 90%;
}
H1 {
text-align: center;
font-size: 160%;
}
H2 {
font-size: 120%;
}
H3 {
font-size: 100%;
}
CAPTION {
font-weight: bold
}
DIV.qindex {
width: 100%;
background-color: #e8eef2;
border: 1px solid #84b0c7;
text-align: center;
margin: 2px;
padding: 2px;
line-height: 140%;
}
DIV.navpath {
width: 100%;
background-color: #e8eef2;
border: 1px solid #84b0c7;
text-align: center;
margin: 2px;
padding: 2px;
line-height: 140%;
}
DIV.navtab {
background-color: #e8eef2;
border: 1px solid #84b0c7;
text-align: center;
margin: 2px;
margin-right: 15px;
padding: 2px;
}
TD.navtab {
font-size: 70%;
}
A.qindex {
text-decoration: none;
font-weight: bold;
color: #1A419D;
}
A.qindex:visited {
text-decoration: none;
font-weight: bold;
color: #1A419D
}
A.qindex:hover {
text-decoration: none;
background-color: #ddddff;
}
A.qindexHL {
text-decoration: none;
font-weight: bold;
background-color: #6666cc;
color: #ffffff;
border: 1px double #9295C2;
}
A.qindexHL:hover {
text-decoration: none;
background-color: #6666cc;
color: #ffffff;
}
A.qindexHL:visited {
text-decoration: none;
background-color: #6666cc;
color: #ffffff
}
A.el {
text-decoration: none;
font-weight: bold
}
A.elRef {
font-weight: bold
}
A.code:link {
text-decoration: none;
font-weight: normal;
color: #0000FF
}
A.code:visited {
text-decoration: none;
font-weight: normal;
color: #0000FF
}
A.codeRef:link {
font-weight: normal;
color: #0000FF
}
A.codeRef:visited {
font-weight: normal;
color: #0000FF
}
A:hover {
text-decoration: none;
background-color: #f2f2ff
}
DL.el {
margin-left: -1cm
}
.fragment {
font-family: monospace, fixed;
font-size: 95%;
}
PRE.fragment {
border: 1px solid #CCCCCC;
background-color: #f5f5f5;
margin-top: 4px;
margin-bottom: 4px;
margin-left: 2px;
margin-right: 8px;
padding-left: 6px;
padding-right: 6px;
padding-top: 4px;
padding-bottom: 4px;
}
DIV.ah {
background-color: black;
font-weight: bold;
color: #ffffff;
margin-bottom: 3px;
margin-top: 3px
}
DIV.groupHeader {
margin-left: 16px;
margin-top: 12px;
margin-bottom: 6px;
font-weight: bold;
}
DIV.groupText {
margin-left: 16px;
font-style: italic;
font-size: 90%
}
BODY {
background: white;
color: black;
margin-right: 20px;
margin-left: 20px;
}
TD.indexkey {
background-color: #e8eef2;
font-weight: bold;
padding-right : 10px;
padding-top : 2px;
padding-left : 10px;
padding-bottom : 2px;
margin-left : 0px;
margin-right : 0px;
margin-top : 2px;
margin-bottom : 2px;
border: 1px solid #CCCCCC;
}
TD.indexvalue {
background-color: #e8eef2;
font-style: italic;
padding-right : 10px;
padding-top : 2px;
padding-left : 10px;
padding-bottom : 2px;
margin-left : 0px;
margin-right : 0px;
margin-top : 2px;
margin-bottom : 2px;
border: 1px solid #CCCCCC;
}
TR.memlist {
background-color: #f0f0f0;
}
P.formulaDsp {
text-align: center;
}
IMG.formulaDsp {
}
IMG.formulaInl {
vertical-align: middle;
}
SPAN.keyword { color: #008000 }
SPAN.keywordtype { color: #604020 }
SPAN.keywordflow { color: #e08000 }
SPAN.comment { color: #800000 }
SPAN.preprocessor { color: #806020 }
SPAN.stringliteral { color: #002080 }
SPAN.charliteral { color: #008080 }
SPAN.vhdldigit { color: #ff00ff }
SPAN.vhdlchar { color: #000000 }
SPAN.vhdlkeyword { color: #700070 }
SPAN.vhdllogic { color: #ff0000 }
.mdescLeft {
padding: 0px 8px 4px 8px;
font-size: 80%;
font-style: italic;
background-color: #FAFAFA;
border-top: 1px none #E0E0E0;
border-right: 1px none #E0E0E0;
border-bottom: 1px none #E0E0E0;
border-left: 1px none #E0E0E0;
margin: 0px;
}
.mdescRight {
padding: 0px 8px 4px 8px;
font-size: 80%;
font-style: italic;
background-color: #FAFAFA;
border-top: 1px none #E0E0E0;
border-right: 1px none #E0E0E0;
border-bottom: 1px none #E0E0E0;
border-left: 1px none #E0E0E0;
margin: 0px;
}
.memItemLeft {
padding: 1px 0px 0px 8px;
margin: 4px;
border-top-width: 1px;
border-right-width: 1px;
border-bottom-width: 1px;
border-left-width: 1px;
border-top-color: #E0E0E0;
border-right-color: #E0E0E0;
border-bottom-color: #E0E0E0;
border-left-color: #E0E0E0;
border-top-style: solid;
border-right-style: none;
border-bottom-style: none;
border-left-style: none;
background-color: #FAFAFA;
font-size: 80%;
}
.memItemRight {
padding: 1px 8px 0px 8px;
margin: 4px;
border-top-width: 1px;
border-right-width: 1px;
border-bottom-width: 1px;
border-left-width: 1px;
border-top-color: #E0E0E0;
border-right-color: #E0E0E0;
border-bottom-color: #E0E0E0;
border-left-color: #E0E0E0;
border-top-style: solid;
border-right-style: none;
border-bottom-style: none;
border-left-style: none;
background-color: #FAFAFA;
font-size: 80%;
}
.memTemplItemLeft {
padding: 1px 0px 0px 8px;
margin: 4px;
border-top-width: 1px;
border-right-width: 1px;
border-bottom-width: 1px;
border-left-width: 1px;
border-top-color: #E0E0E0;
border-right-color: #E0E0E0;
border-bottom-color: #E0E0E0;
border-left-color: #E0E0E0;
border-top-style: none;
border-right-style: none;
border-bottom-style: none;
border-left-style: none;
background-color: #FAFAFA;
font-size: 80%;
}
.memTemplItemRight {
padding: 1px 8px 0px 8px;
margin: 4px;
border-top-width: 1px;
border-right-width: 1px;
border-bottom-width: 1px;
border-left-width: 1px;
border-top-color: #E0E0E0;
border-right-color: #E0E0E0;
border-bottom-color: #E0E0E0;
border-left-color: #E0E0E0;
border-top-style: none;
border-right-style: none;
border-bottom-style: none;
border-left-style: none;
background-color: #FAFAFA;
font-size: 80%;
}
.memTemplParams {
padding: 1px 0px 0px 8px;
margin: 4px;
border-top-width: 1px;
border-right-width: 1px;
border-bottom-width: 1px;
border-left-width: 1px;
border-top-color: #E0E0E0;
border-right-color: #E0E0E0;
border-bottom-color: #E0E0E0;
border-left-color: #E0E0E0;
border-top-style: solid;
border-right-style: none;
border-bottom-style: none;
border-left-style: none;
color: #606060;
background-color: #FAFAFA;
font-size: 80%;
}
.search {
color: #003399;
font-weight: bold;
}
FORM.search {
margin-bottom: 0px;
margin-top: 0px;
}
INPUT.search {
font-size: 75%;
color: #000080;
font-weight: normal;
background-color: #e8eef2;
}
TD.tiny {
font-size: 75%;
}
a {
color: #1A41A8;
}
a:visited {
color: #2A3798;
}
.dirtab {
padding: 4px;
border-collapse: collapse;
border: 1px solid #84b0c7;
}
TH.dirtab {
background: #e8eef2;
font-weight: bold;
}
HR {
height: 1px;
border: none;
border-top: 1px solid black;
}
/* Style for detailed member documentation */
.memtemplate {
font-size: 80%;
color: #606060;
font-weight: normal;
margin-left: 3px;
}
.memnav {
background-color: #e8eef2;
border: 1px solid #84b0c7;
text-align: center;
margin: 2px;
margin-right: 15px;
padding: 2px;
}
.memitem {
padding: 4px;
background-color: #eef3f5;
border-width: 1px;
border-style: solid;
border-color: #dedeee;
-moz-border-radius: 8px 8px 8px 8px;
}
.memname {
white-space: nowrap;
font-weight: bold;
}
.memdoc{
padding-left: 10px;
}
.memproto {
background-color: #d5e1e8;
width: 100%;
border-width: 1px;
border-style: solid;
border-color: #84b0c7;
font-weight: bold;
-moz-border-radius: 8px 8px 8px 8px;
}
.paramkey {
text-align: right;
}
.paramtype {
white-space: nowrap;
}
.paramname {
color: #602020;
font-style: italic;
white-space: nowrap;
}
/* End Styling for detailed member documentation */
/* for the tree view */
.ftvtree {
font-family: sans-serif;
margin:0.5em;
}
/* these are for tree view when used as main index */
.directory {
font-size: 9pt;
font-weight: bold;
}
.directory h3 {
margin: 0px;
margin-top: 1em;
font-size: 11pt;
}
/* The following two styles can be used to replace the root node title */
/* with an image of your choice. Simply uncomment the next two styles, */
/* specify the name of your image and be sure to set 'height' to the */
/* proper pixel height of your image. */
/* .directory h3.swap { */
/* height: 61px; */
/* background-repeat: no-repeat; */
/* background-image: url("yourimage.gif"); */
/* } */
/* .directory h3.swap span { */
/* display: none; */
/* } */
.directory > h3 {
margin-top: 0;
}
.directory p {
margin: 0px;
white-space: nowrap;
}
.directory div {
display: none;
margin: 0px;
}
.directory img {
vertical-align: -30%;
}
/* these are for tree view when not used as main index */
.directory-alt {
font-size: 100%;
font-weight: bold;
}
.directory-alt h3 {
margin: 0px;
margin-top: 1em;
font-size: 11pt;
}
.directory-alt > h3 {
margin-top: 0;
}
.directory-alt p {
margin: 0px;
white-space: nowrap;
}
.directory-alt div {
display: none;
margin: 0px;
}
.directory-alt img {
vertical-align: -30%;
}

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.3 KiB

View File

@ -0,0 +1,26 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
<html><head><meta http-equiv="Content-Type" content="text/html;charset=UTF-8">
<title>AccelStepper: File Index</title>
<link href="doxygen.css" rel="stylesheet" type="text/css">
<link href="tabs.css" rel="stylesheet" type="text/css">
</head><body>
<!-- Generated by Doxygen 1.5.6 -->
<div class="navigation" id="top">
<div class="tabs">
<ul>
<li><a href="index.html"><span>Main&nbsp;Page</span></a></li>
<li><a href="annotated.html"><span>Classes</span></a></li>
<li class="current"><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
</div>
<div class="contents">
<h1>File List</h1>Here is a list of all documented files with brief descriptions:<table>
<tr><td class="indexkey"><b>AccelStepper.h</b> <a href="AccelStepper_8h-source.html">[code]</a></td><td class="indexvalue"></td></tr>
</table>
</div>
<hr size="1"><address style="text-align: right;"><small>Generated on Sun Oct 24 18:22:50 2010 for AccelStepper by&nbsp;
<a href="http://www.doxygen.org/index.html">
<img src="doxygen.png" alt="doxygen" align="middle" border="0"></a> 1.5.6 </small></address>
</body>
</html>

View File

@ -0,0 +1,87 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
<html><head><meta http-equiv="Content-Type" content="text/html;charset=UTF-8">
<title>AccelStepper: Class Members</title>
<link href="doxygen.css" rel="stylesheet" type="text/css">
<link href="tabs.css" rel="stylesheet" type="text/css">
</head><body>
<!-- Generated by Doxygen 1.5.6 -->
<div class="navigation" id="top">
<div class="tabs">
<ul>
<li><a href="index.html"><span>Main&nbsp;Page</span></a></li>
<li class="current"><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div class="tabs">
<ul>
<li><a href="annotated.html"><span>Class&nbsp;List</span></a></li>
<li class="current"><a href="functions.html"><span>Class&nbsp;Members</span></a></li>
</ul>
</div>
<div class="tabs">
<ul>
<li class="current"><a href="functions.html"><span>All</span></a></li>
<li><a href="functions_func.html"><span>Functions</span></a></li>
</ul>
</div>
</div>
<div class="contents">
Here is a list of all documented class members with links to the class documentation for each member:
<p>
<ul>
<li>AccelStepper()
: <a class="el" href="classAccelStepper.html#a1290897df35915069e5eca9d034038c">AccelStepper</a>
<li>computeNewSpeed()
: <a class="el" href="classAccelStepper.html#ffbee789b5c19165846cf0409860ae79">AccelStepper</a>
<li>currentPosition()
: <a class="el" href="classAccelStepper.html#5dce13ab2a1b02b8f443318886bf6fc5">AccelStepper</a>
<li>desiredSpeed()
: <a class="el" href="classAccelStepper.html#6e4bd79c395e69beee31d76d0d3287e4">AccelStepper</a>
<li>disableOutputs()
: <a class="el" href="classAccelStepper.html#3591e29a236e2935afd7f64ff6c22006">AccelStepper</a>
<li>distanceToGo()
: <a class="el" href="classAccelStepper.html#748665c3962e66fbc0e9373eb14c69c1">AccelStepper</a>
<li>enableOutputs()
: <a class="el" href="classAccelStepper.html#a279a50d30d0413f570c692cff071643">AccelStepper</a>
<li>move()
: <a class="el" href="classAccelStepper.html#68942c66e78fb7f7b5f0cdade6eb7f06">AccelStepper</a>
<li>moveTo()
: <a class="el" href="classAccelStepper.html#ce236ede35f87c63d18da25810ec9736">AccelStepper</a>
<li>run()
: <a class="el" href="classAccelStepper.html#608b2395b64ac15451d16d0371fe13ce">AccelStepper</a>
<li>runSpeed()
: <a class="el" href="classAccelStepper.html#a4a6bdf99f698284faaeb5542b0b7514">AccelStepper</a>
<li>runSpeedToPosition()
: <a class="el" href="classAccelStepper.html#9270d20336e76ac1fd5bcd5b9c34f301">AccelStepper</a>
<li>runToNewPosition()
: <a class="el" href="classAccelStepper.html#176c5d2e4c2f21e9e92b12e39a6f0e67">AccelStepper</a>
<li>runToPosition()
: <a class="el" href="classAccelStepper.html#344f58fef8cc34ac5aa75ba4b665d21c">AccelStepper</a>
<li>setAcceleration()
: <a class="el" href="classAccelStepper.html#dfb19e3cd2a028a1fe78131787604fd1">AccelStepper</a>
<li>setCurrentPosition()
: <a class="el" href="classAccelStepper.html#9d917f014317fb9d3b5dc14e66f6c689">AccelStepper</a>
<li>setMaxSpeed()
: <a class="el" href="classAccelStepper.html#bee8d466229b87accba33d6ec929c18f">AccelStepper</a>
<li>setSpeed()
: <a class="el" href="classAccelStepper.html#e79c49ad69d5ccc9da0ee691fa4ca235">AccelStepper</a>
<li>speed()
: <a class="el" href="classAccelStepper.html#4f0989d0ae264e7eadfe1fa720769fb6">AccelStepper</a>
<li>step()
: <a class="el" href="classAccelStepper.html#3c9a220819d2451f79ff8a0c0a395b9f">AccelStepper</a>
<li>step1()
: <a class="el" href="classAccelStepper.html#cc64254ea242b53588e948335fd9305f">AccelStepper</a>
<li>step2()
: <a class="el" href="classAccelStepper.html#88f11bf6361fe002585f731d34fe2e8b">AccelStepper</a>
<li>step4()
: <a class="el" href="classAccelStepper.html#49e448d179bbe4e0f8003a3f9993789d">AccelStepper</a>
<li>targetPosition()
: <a class="el" href="classAccelStepper.html#96685e0945b7cf75d5959da679cd911e">AccelStepper</a>
</ul>
</div>
<hr size="1"><address style="text-align: right;"><small>Generated on Sun Oct 24 18:22:50 2010 for AccelStepper by&nbsp;
<a href="http://www.doxygen.org/index.html">
<img src="doxygen.png" alt="doxygen" align="middle" border="0"></a> 1.5.6 </small></address>
</body>
</html>

View File

@ -0,0 +1,87 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
<html><head><meta http-equiv="Content-Type" content="text/html;charset=UTF-8">
<title>AccelStepper: Class Members - Functions</title>
<link href="doxygen.css" rel="stylesheet" type="text/css">
<link href="tabs.css" rel="stylesheet" type="text/css">
</head><body>
<!-- Generated by Doxygen 1.5.6 -->
<div class="navigation" id="top">
<div class="tabs">
<ul>
<li><a href="index.html"><span>Main&nbsp;Page</span></a></li>
<li class="current"><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
<div class="tabs">
<ul>
<li><a href="annotated.html"><span>Class&nbsp;List</span></a></li>
<li class="current"><a href="functions.html"><span>Class&nbsp;Members</span></a></li>
</ul>
</div>
<div class="tabs">
<ul>
<li><a href="functions.html"><span>All</span></a></li>
<li class="current"><a href="functions_func.html"><span>Functions</span></a></li>
</ul>
</div>
</div>
<div class="contents">
&nbsp;
<p>
<ul>
<li>AccelStepper()
: <a class="el" href="classAccelStepper.html#a1290897df35915069e5eca9d034038c">AccelStepper</a>
<li>computeNewSpeed()
: <a class="el" href="classAccelStepper.html#ffbee789b5c19165846cf0409860ae79">AccelStepper</a>
<li>currentPosition()
: <a class="el" href="classAccelStepper.html#5dce13ab2a1b02b8f443318886bf6fc5">AccelStepper</a>
<li>desiredSpeed()
: <a class="el" href="classAccelStepper.html#6e4bd79c395e69beee31d76d0d3287e4">AccelStepper</a>
<li>disableOutputs()
: <a class="el" href="classAccelStepper.html#3591e29a236e2935afd7f64ff6c22006">AccelStepper</a>
<li>distanceToGo()
: <a class="el" href="classAccelStepper.html#748665c3962e66fbc0e9373eb14c69c1">AccelStepper</a>
<li>enableOutputs()
: <a class="el" href="classAccelStepper.html#a279a50d30d0413f570c692cff071643">AccelStepper</a>
<li>move()
: <a class="el" href="classAccelStepper.html#68942c66e78fb7f7b5f0cdade6eb7f06">AccelStepper</a>
<li>moveTo()
: <a class="el" href="classAccelStepper.html#ce236ede35f87c63d18da25810ec9736">AccelStepper</a>
<li>run()
: <a class="el" href="classAccelStepper.html#608b2395b64ac15451d16d0371fe13ce">AccelStepper</a>
<li>runSpeed()
: <a class="el" href="classAccelStepper.html#a4a6bdf99f698284faaeb5542b0b7514">AccelStepper</a>
<li>runSpeedToPosition()
: <a class="el" href="classAccelStepper.html#9270d20336e76ac1fd5bcd5b9c34f301">AccelStepper</a>
<li>runToNewPosition()
: <a class="el" href="classAccelStepper.html#176c5d2e4c2f21e9e92b12e39a6f0e67">AccelStepper</a>
<li>runToPosition()
: <a class="el" href="classAccelStepper.html#344f58fef8cc34ac5aa75ba4b665d21c">AccelStepper</a>
<li>setAcceleration()
: <a class="el" href="classAccelStepper.html#dfb19e3cd2a028a1fe78131787604fd1">AccelStepper</a>
<li>setCurrentPosition()
: <a class="el" href="classAccelStepper.html#9d917f014317fb9d3b5dc14e66f6c689">AccelStepper</a>
<li>setMaxSpeed()
: <a class="el" href="classAccelStepper.html#bee8d466229b87accba33d6ec929c18f">AccelStepper</a>
<li>setSpeed()
: <a class="el" href="classAccelStepper.html#e79c49ad69d5ccc9da0ee691fa4ca235">AccelStepper</a>
<li>speed()
: <a class="el" href="classAccelStepper.html#4f0989d0ae264e7eadfe1fa720769fb6">AccelStepper</a>
<li>step()
: <a class="el" href="classAccelStepper.html#3c9a220819d2451f79ff8a0c0a395b9f">AccelStepper</a>
<li>step1()
: <a class="el" href="classAccelStepper.html#cc64254ea242b53588e948335fd9305f">AccelStepper</a>
<li>step2()
: <a class="el" href="classAccelStepper.html#88f11bf6361fe002585f731d34fe2e8b">AccelStepper</a>
<li>step4()
: <a class="el" href="classAccelStepper.html#49e448d179bbe4e0f8003a3f9993789d">AccelStepper</a>
<li>targetPosition()
: <a class="el" href="classAccelStepper.html#96685e0945b7cf75d5959da679cd911e">AccelStepper</a>
</ul>
</div>
<hr size="1"><address style="text-align: right;"><small>Generated on Sun Oct 24 18:22:50 2010 for AccelStepper by&nbsp;
<a href="http://www.doxygen.org/index.html">
<img src="doxygen.png" alt="doxygen" align="middle" border="0"></a> 1.5.6 </small></address>
</body>
</html>

View File

@ -0,0 +1,51 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
<html><head><meta http-equiv="Content-Type" content="text/html;charset=UTF-8">
<title>AccelStepper: AccelStepper library for Arduino</title>
<link href="doxygen.css" rel="stylesheet" type="text/css">
<link href="tabs.css" rel="stylesheet" type="text/css">
</head><body>
<!-- Generated by Doxygen 1.5.6 -->
<div class="navigation" id="top">
<div class="tabs">
<ul>
<li class="current"><a href="index.html"><span>Main&nbsp;Page</span></a></li>
<li><a href="annotated.html"><span>Classes</span></a></li>
<li><a href="files.html"><span>Files</span></a></li>
</ul>
</div>
</div>
<div class="contents">
<h1>AccelStepper library for Arduino</h1>
<p>
This is the Arduino <a class="el" href="classAccelStepper.html" title="Support for stepper motors with acceleration etc.">AccelStepper</a> 1.2 library. It provides an object-oriented interface for 2 or 4 pin stepper motors.<p>
The standard Arduino IDE includes the Stepper library (<a href="http://arduino.cc/en/Reference/Stepper">http://arduino.cc/en/Reference/Stepper</a>) for stepper motors. It is perfectly adequate for simple, single motor applications.<p>
<a class="el" href="classAccelStepper.html" title="Support for stepper motors with acceleration etc.">AccelStepper</a> significantly improves on the standard Arduino Stepper library in several ways: <ul>
<li>Supports acceleration and deceleration </li>
<li>Supports multiple simultaneous steppers, with independent concurrent stepping on each stepper </li>
<li>API functions never delay() or block </li>
<li>Supports 2 and 4 wire steppers </li>
<li>Supports stepper drivers such as the Sparkfun EasyDriver (based on 3967 driver chip) </li>
<li>Very slow speeds are supported </li>
<li>Extensive API </li>
<li>Subclass support</li>
</ul>
The latest version of this documentation can be downloaded from <a href="http://www.open.com.au/mikem/arduino/AccelStepper">http://www.open.com.au/mikem/arduino/AccelStepper</a><p>
Example Arduino programs are included to show the main modes of use.<p>
The version of the package that this documentation refers to can be downloaded from <a href="http://www.open.com.au/mikem/arduino/AccelStepper/AccelStepper-1.3.zip">http://www.open.com.au/mikem/arduino/AccelStepper/AccelStepper-1.3.zip</a> You can find the latest version at <a href="http://www.open.com.au/mikem/arduino/AccelStepper">http://www.open.com.au/mikem/arduino/AccelStepper</a><p>
Tested on Arduino Diecimila and Mega with arduino-0018 on OpenSuSE 11.1 and avr-libc-1.6.1-1.15, cross-avr-binutils-2.19-9.1, cross-avr-gcc-4.1.3_20080612-26.5.<p>
<dl class="user" compact><dt><b>Installation</b></dt><dd>Install in the usual way: unzip the distribution zip file to the libraries sub-folder of your sketchbook.</dd></dl>
This software is Copyright (C) 2010 Mike McCauley. Use is subject to license conditions. The main licensing options available are GPL V2 or Commercial:<p>
<dl class="user" compact><dt><b>Open Source Licensing GPL V2</b></dt><dd>This is the appropriate option if you want to share the source code of your application with everyone you distribute it to, and you also want to give them the right to share who uses it. If you wish to use this software under Open Source Licensing, you must contribute all your source code to the open source community in accordance with the GPL Version 2 when your application is distributed. See <a href="http://www.gnu.org/copyleft/gpl.html">http://www.gnu.org/copyleft/gpl.html</a></dd></dl>
<dl class="user" compact><dt><b>Commercial Licensing</b></dt><dd>This is the appropriate option if you are creating proprietary applications and you are not prepared to distribute and share the source code of your application. Contact <a href="mailto:info@open.com.au">info@open.com.au</a> for details.</dd></dl>
<dl class="user" compact><dt><b>Revision History</b></dt><dd></dd></dl>
<dl class="version" compact><dt><b>Version:</b></dt><dd>1.0 Initial release<p>
1.1 Added speed() function to get the current speed. <p>
1.2 Added runSpeedToPosition() submitted by Gunnar Arndt. <p>
1.3 Added support for stepper drivers (ie with Step and Direction inputs) with _pins == 1</dd></dl>
<dl class="author" compact><dt><b>Author:</b></dt><dd>Mike McCauley (<a href="mailto:mikem@open.com.au">mikem@open.com.au</a>) </dd></dl>
</div>
<hr size="1"><address style="text-align: right;"><small>Generated on Sun Oct 24 18:22:50 2010 for AccelStepper by&nbsp;
<a href="http://www.doxygen.org/index.html">
<img src="doxygen.png" alt="doxygen" align="middle" border="0"></a> 1.5.6 </small></address>
</body>
</html>

Binary file not shown.

After

Width:  |  Height:  |  Size: 35 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 706 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.5 KiB

View File

@ -0,0 +1,102 @@
/* tabs styles, based on http://www.alistapart.com/articles/slidingdoors */
DIV.tabs
{
float : left;
width : 100%;
background : url("tab_b.gif") repeat-x bottom;
margin-bottom : 4px;
}
DIV.tabs UL
{
margin : 0px;
padding-left : 10px;
list-style : none;
}
DIV.tabs LI, DIV.tabs FORM
{
display : inline;
margin : 0px;
padding : 0px;
}
DIV.tabs FORM
{
float : right;
}
DIV.tabs A
{
float : left;
background : url("tab_r.gif") no-repeat right top;
border-bottom : 1px solid #84B0C7;
font-size : x-small;
font-weight : bold;
text-decoration : none;
}
DIV.tabs A:hover
{
background-position: 100% -150px;
}
DIV.tabs A:link, DIV.tabs A:visited,
DIV.tabs A:active, DIV.tabs A:hover
{
color: #1A419D;
}
DIV.tabs SPAN
{
float : left;
display : block;
background : url("tab_l.gif") no-repeat left top;
padding : 5px 9px;
white-space : nowrap;
}
DIV.tabs INPUT
{
float : right;
display : inline;
font-size : 1em;
}
DIV.tabs TD
{
font-size : x-small;
font-weight : bold;
text-decoration : none;
}
/* Commented Backslash Hack hides rule from IE5-Mac \*/
DIV.tabs SPAN {float : none;}
/* End IE5-Mac hack */
DIV.tabs A:hover SPAN
{
background-position: 0% -150px;
}
DIV.tabs LI.current A
{
background-position: 100% -150px;
border-width : 0px;
}
DIV.tabs LI.current SPAN
{
background-position: 0% -150px;
padding-bottom : 6px;
}
DIV.navpath
{
background : none;
border : none;
border-bottom : 1px solid #84B0C7;
}

View File

@ -0,0 +1,37 @@
// ConstantSpeed.pde
// -*- mode: C++ -*-
//
// Shows how to run AccelStepper in the simplest,
// fixed speed mode with no accelerations
// Requires the AFMotor library (https://github.com/adafruit/Adafruit-Motor-Shield-library)
// And AccelStepper with AFMotor support (https://github.com/adafruit/AccelStepper)
// Public domain!
#include <AccelStepper.h>
#include <AFMotor.h>
AF_Stepper motor1(200, 1);
// you can change these to DOUBLE or INTERLEAVE or MICROSTEP!
void forwardstep() {
motor1.onestep(FORWARD, SINGLE);
}
void backwardstep() {
motor1.onestep(BACKWARD, SINGLE);
}
AccelStepper stepper(forwardstep, backwardstep); // use functions to step
void setup()
{
Serial.begin(9600); // set up Serial library at 9600 bps
Serial.println("Stepper test!");
stepper.setSpeed(50);
}
void loop()
{
stepper.runSpeed();
}

View File

@ -0,0 +1,56 @@
// MultiStepper
// -*- mode: C++ -*-
//
// Control both Stepper motors at the same time with different speeds
// and accelerations.
// Requires the AFMotor library (https://github.com/adafruit/Adafruit-Motor-Shield-library)
// And AccelStepper with AFMotor support (https://github.com/adafruit/AccelStepper)
// Public domain!
#include <AccelStepper.h>
#include <AFMotor.h>
// two stepper motors one on each port
AF_Stepper motor1(200, 1);
AF_Stepper motor2(200, 2);
// you can change these to DOUBLE or INTERLEAVE or MICROSTEP!
// wrappers for the first motor!
void forwardstep1() {
motor1.onestep(FORWARD, SINGLE);
}
void backwardstep1() {
motor1.onestep(BACKWARD, SINGLE);
}
// wrappers for the second motor!
void forwardstep2() {
motor2.onestep(FORWARD, SINGLE);
}
void backwardstep2() {
motor2.onestep(BACKWARD, SINGLE);
}
// Motor shield has two motor ports, now we'll wrap them in an AccelStepper object
AccelStepper stepper1(forwardstep1, backwardstep1);
AccelStepper stepper2(forwardstep2, backwardstep2);
void setup()
{
stepper1.setMaxSpeed(200.0);
stepper1.setAcceleration(100.0);
stepper1.moveTo(24);
stepper2.setMaxSpeed(300.0);
stepper2.setAcceleration(100.0);
stepper2.moveTo(1000000);
}
void loop()
{
// Change direction at the limits
if (stepper1.distanceToGo() == 0)
stepper1.moveTo(-stepper1.currentPosition());
stepper1.run();
stepper2.run();
}

View File

@ -0,0 +1,28 @@
// Blocking.pde
// -*- mode: C++ -*-
//
// Shows how to use the blocking call runToNewPosition
// Which sets a new target position and then waits until the stepper has
// achieved it.
//
// Copyright (C) 2009 Mike McCauley
// $Id: HRFMessage.h,v 1.1 2009/08/15 05:32:58 mikem Exp mikem $
#include <AccelStepper.h>
// Define a stepper and the pins it will use
AccelStepper stepper; // Defaults to 4 pins on 2, 3, 4, 5
void setup()
{
stepper.setMaxSpeed(200.0);
stepper.setAcceleration(100.0);
}
void loop()
{
stepper.runToNewPosition(0);
stepper.runToNewPosition(500);
stepper.runToNewPosition(100);
stepper.runToNewPosition(120);
}

View File

@ -0,0 +1,22 @@
// ConstantSpeed.pde
// -*- mode: C++ -*-
//
// Shows how to run AccelStepper in the simplest,
// fixed speed mode with no accelerations
/// \author Mike McCauley (mikem@open.com.au)
// Copyright (C) 2009 Mike McCauley
// $Id: HRFMessage.h,v 1.1 2009/08/15 05:32:58 mikem Exp mikem $
#include <AccelStepper.h>
AccelStepper stepper; // Defaults to 4 pins on 2, 3, 4, 5
void setup()
{
stepper.setSpeed(50);
}
void loop()
{
stepper.runSpeed();
}

View File

@ -0,0 +1,41 @@
// MultiStepper.pde
// -*- mode: C++ -*-
//
// Shows how to multiple simultaneous steppers
// Runs one stepper forwards and backwards, accelerating and decelerating
// at the limits. Runs other steppers at the same time
//
// Copyright (C) 2009 Mike McCauley
// $Id: HRFMessage.h,v 1.1 2009/08/15 05:32:58 mikem Exp mikem $
#include <AccelStepper.h>
// Define some steppers and the pins the will use
AccelStepper stepper1; // Defaults to 4 pins on 2, 3, 4, 5
AccelStepper stepper2(4, 6, 7, 8, 9);
AccelStepper stepper3(2, 10, 11);
void setup()
{
stepper1.setMaxSpeed(200.0);
stepper1.setAcceleration(100.0);
stepper1.moveTo(24);
stepper2.setMaxSpeed(300.0);
stepper2.setAcceleration(100.0);
stepper2.moveTo(1000000);
stepper3.setMaxSpeed(300.0);
stepper3.setAcceleration(100.0);
stepper3.moveTo(1000000);
}
void loop()
{
// Change direction at the limits
if (stepper1.distanceToGo() == 0)
stepper1.moveTo(-stepper1.currentPosition());
stepper1.run();
stepper2.run();
stepper3.run();
}

View File

@ -0,0 +1,31 @@
// Overshoot.pde
// -*- mode: C++ -*-
//
// Check overshoot handling
// which sets a new target position and then waits until the stepper has
// achieved it. This is used for testing the handling of overshoots
//
// Copyright (C) 2009 Mike McCauley
// $Id: HRFMessage.h,v 1.1 2009/08/15 05:32:58 mikem Exp mikem $
#include <AccelStepper.h>
// Define a stepper and the pins it will use
AccelStepper stepper; // Defaults to 4 pins on 2, 3, 4, 5
void setup()
{
}
void loop()
{
stepper.setMaxSpeed(200);
stepper.setAcceleration(50);
stepper.runToNewPosition(0);
stepper.moveTo(500);
while (stepper.currentPosition() != 300)
stepper.run();
// cause an overshoot as we whiz past 300
stepper.setCurrentPosition(600);
}

View File

@ -0,0 +1,30 @@
// Random.pde
// -*- mode: C++ -*-
//
// Make a single stepper perform random changes in speed, position and acceleration
//
// Copyright (C) 2009 Mike McCauley
// $Id: HRFMessage.h,v 1.1 2009/08/15 05:32:58 mikem Exp mikem $
#include <AccelStepper.h>
// Define a stepper and the pins it will use
AccelStepper stepper; // Defaults to 4 pins on 2, 3, 4, 5
void setup()
{
}
void loop()
{
if (stepper.distanceToGo() == 0)
{
// Random change to speed, position and acceleration
// Make sure we dont get 0 speed or accelerations
delay(1000);
stepper.moveTo(rand() % 200);
stepper.setMaxSpeed((rand() % 200) + 1);
stepper.setAcceleration((rand() % 200) + 1);
}
stepper.run();
}

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,155 @@
#ifndef _ADAFRUIT_GFX_H
#define _ADAFRUIT_GFX_H
#if ARDUINO >= 100
#include "Arduino.h"
#include "Print.h"
#else
#include "WProgram.h"
#endif
#include "gfxfont.h"
class Adafruit_GFX : public Print {
public:
Adafruit_GFX(int16_t w, int16_t h); // Constructor
// This MUST be defined by the subclass:
virtual void drawPixel(int16_t x, int16_t y, uint16_t color) = 0;
// These MAY be overridden by the subclass to provide device-specific
// optimized code. Otherwise 'generic' versions are used.
virtual void
drawLine(int16_t x0, int16_t y0, int16_t x1, int16_t y1, uint16_t color),
drawFastVLine(int16_t x, int16_t y, int16_t h, uint16_t color),
drawFastHLine(int16_t x, int16_t y, int16_t w, uint16_t color),
drawRect(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color),
fillRect(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color),
fillScreen(uint16_t color),
invertDisplay(boolean i);
// These exist only with Adafruit_GFX (no subclass overrides)
void
drawCircle(int16_t x0, int16_t y0, int16_t r, uint16_t color),
drawCircleHelper(int16_t x0, int16_t y0, int16_t r, uint8_t cornername,
uint16_t color),
fillCircle(int16_t x0, int16_t y0, int16_t r, uint16_t color),
fillCircleHelper(int16_t x0, int16_t y0, int16_t r, uint8_t cornername,
int16_t delta, uint16_t color),
drawTriangle(int16_t x0, int16_t y0, int16_t x1, int16_t y1,
int16_t x2, int16_t y2, uint16_t color),
fillTriangle(int16_t x0, int16_t y0, int16_t x1, int16_t y1,
int16_t x2, int16_t y2, uint16_t color),
drawRoundRect(int16_t x0, int16_t y0, int16_t w, int16_t h,
int16_t radius, uint16_t color),
fillRoundRect(int16_t x0, int16_t y0, int16_t w, int16_t h,
int16_t radius, uint16_t color),
drawBitmap(int16_t x, int16_t y, const uint8_t *bitmap,
int16_t w, int16_t h, uint16_t color),
drawBitmap(int16_t x, int16_t y, const uint8_t *bitmap,
int16_t w, int16_t h, uint16_t color, uint16_t bg),
drawBitmap(int16_t x, int16_t y, uint8_t *bitmap,
int16_t w, int16_t h, uint16_t color),
drawBitmap(int16_t x, int16_t y, uint8_t *bitmap,
int16_t w, int16_t h, uint16_t color, uint16_t bg),
drawXBitmap(int16_t x, int16_t y, const uint8_t *bitmap,
int16_t w, int16_t h, uint16_t color),
drawChar(int16_t x, int16_t y, unsigned char c, uint16_t color,
uint16_t bg, uint8_t size),
setCursor(int16_t x, int16_t y),
setTextColor(uint16_t c),
setTextColor(uint16_t c, uint16_t bg),
setTextSize(uint8_t s),
setTextWrap(boolean w),
setRotation(uint8_t r),
cp437(boolean x=true),
setFont(const GFXfont *f = NULL),
getTextBounds(char *string, int16_t x, int16_t y,
int16_t *x1, int16_t *y1, uint16_t *w, uint16_t *h),
getTextBounds(const __FlashStringHelper *s, int16_t x, int16_t y,
int16_t *x1, int16_t *y1, uint16_t *w, uint16_t *h);
#if ARDUINO >= 100
virtual size_t write(uint8_t);
#else
virtual void write(uint8_t);
#endif
int16_t height(void) const;
int16_t width(void) const;
uint8_t getRotation(void) const;
// get current cursor position (get rotation safe maximum values, using: width() for x, height() for y)
int16_t getCursorX(void) const;
int16_t getCursorY(void) const;
protected:
const int16_t
WIDTH, HEIGHT; // This is the 'raw' display w/h - never changes
int16_t
_width, _height, // Display w/h as modified by current rotation
cursor_x, cursor_y;
uint16_t
textcolor, textbgcolor;
uint8_t
textsize,
rotation;
boolean
wrap, // If set, 'wrap' text at right edge of display
_cp437; // If set, use correct CP437 charset (default is off)
GFXfont
*gfxFont;
};
class Adafruit_GFX_Button {
public:
Adafruit_GFX_Button(void);
void initButton(Adafruit_GFX *gfx, int16_t x, int16_t y,
uint8_t w, uint8_t h, uint16_t outline, uint16_t fill,
uint16_t textcolor, char *label, uint8_t textsize);
void drawButton(boolean inverted = false);
boolean contains(int16_t x, int16_t y);
void press(boolean p);
boolean isPressed();
boolean justPressed();
boolean justReleased();
private:
Adafruit_GFX *_gfx;
int16_t _x, _y;
uint16_t _w, _h;
uint8_t _textsize;
uint16_t _outlinecolor, _fillcolor, _textcolor;
char _label[10];
boolean currstate, laststate;
};
class GFXcanvas1 : public Adafruit_GFX {
public:
GFXcanvas1(uint16_t w, uint16_t h);
~GFXcanvas1(void);
void drawPixel(int16_t x, int16_t y, uint16_t color),
fillScreen(uint16_t color);
uint8_t *getBuffer(void);
private:
uint8_t *buffer;
};
class GFXcanvas16 : public Adafruit_GFX {
GFXcanvas16(uint16_t w, uint16_t h);
~GFXcanvas16(void);
void drawPixel(int16_t x, int16_t y, uint16_t color),
fillScreen(uint16_t color);
uint16_t *getBuffer(void);
private:
uint16_t *buffer;
};
#endif // _ADAFRUIT_GFX_H

View File

@ -0,0 +1,227 @@
const uint8_t FreeMono12pt7bBitmaps[] PROGMEM = {
0x49, 0x24, 0x92, 0x48, 0x01, 0xF8, 0xE7, 0xE7, 0x67, 0x42, 0x42, 0x42,
0x42, 0x09, 0x02, 0x41, 0x10, 0x44, 0x11, 0x1F, 0xF1, 0x10, 0x4C, 0x12,
0x3F, 0xE1, 0x20, 0x48, 0x12, 0x04, 0x81, 0x20, 0x48, 0x04, 0x07, 0xA2,
0x19, 0x02, 0x40, 0x10, 0x03, 0x00, 0x3C, 0x00, 0x80, 0x10, 0x06, 0x01,
0xE0, 0xA7, 0xC0, 0x40, 0x10, 0x04, 0x00, 0x3C, 0x19, 0x84, 0x21, 0x08,
0x66, 0x0F, 0x00, 0x0C, 0x1C, 0x78, 0x01, 0xE0, 0xCC, 0x21, 0x08, 0x43,
0x30, 0x78, 0x3E, 0x30, 0x10, 0x08, 0x02, 0x03, 0x03, 0x47, 0x14, 0x8A,
0x43, 0x11, 0x8F, 0x60, 0xFD, 0xA4, 0x90, 0x05, 0x25, 0x24, 0x92, 0x48,
0x92, 0x24, 0x11, 0x24, 0x89, 0x24, 0x92, 0x92, 0x90, 0x00, 0x04, 0x02,
0x11, 0x07, 0xF0, 0xC0, 0x50, 0x48, 0x42, 0x00, 0x08, 0x04, 0x02, 0x01,
0x00, 0x87, 0xFC, 0x20, 0x10, 0x08, 0x04, 0x02, 0x00, 0x3B, 0x9C, 0xCE,
0x62, 0x00, 0xFF, 0xE0, 0xFF, 0x80, 0x00, 0x80, 0xC0, 0x40, 0x20, 0x20,
0x10, 0x10, 0x08, 0x08, 0x04, 0x04, 0x02, 0x02, 0x01, 0x01, 0x00, 0x80,
0x80, 0x40, 0x00, 0x1C, 0x31, 0x90, 0x58, 0x38, 0x0C, 0x06, 0x03, 0x01,
0x80, 0xC0, 0x60, 0x30, 0x34, 0x13, 0x18, 0x70, 0x30, 0xE1, 0x44, 0x81,
0x02, 0x04, 0x08, 0x10, 0x20, 0x40, 0x81, 0x1F, 0xC0, 0x1E, 0x10, 0x90,
0x68, 0x10, 0x08, 0x0C, 0x04, 0x04, 0x04, 0x06, 0x06, 0x06, 0x06, 0x0E,
0x07, 0xFE, 0x3E, 0x10, 0x40, 0x08, 0x02, 0x00, 0x80, 0x40, 0xE0, 0x04,
0x00, 0x80, 0x10, 0x04, 0x01, 0x00, 0xD8, 0x63, 0xE0, 0x06, 0x0A, 0x0A,
0x12, 0x22, 0x22, 0x42, 0x42, 0x82, 0x82, 0xFF, 0x02, 0x02, 0x02, 0x0F,
0x7F, 0x20, 0x10, 0x08, 0x04, 0x02, 0xF1, 0x8C, 0x03, 0x00, 0x80, 0x40,
0x20, 0x18, 0x16, 0x18, 0xF0, 0x0F, 0x8C, 0x08, 0x08, 0x04, 0x04, 0x02,
0x79, 0x46, 0xC1, 0xE0, 0x60, 0x28, 0x14, 0x19, 0x08, 0x78, 0xFF, 0x81,
0x81, 0x02, 0x02, 0x02, 0x02, 0x04, 0x04, 0x04, 0x04, 0x08, 0x08, 0x08,
0x08, 0x3E, 0x31, 0xB0, 0x70, 0x18, 0x0C, 0x05, 0x8C, 0x38, 0x63, 0x40,
0x60, 0x30, 0x18, 0x1B, 0x18, 0xF8, 0x3C, 0x31, 0x30, 0x50, 0x28, 0x0C,
0x0F, 0x06, 0x85, 0x3C, 0x80, 0x40, 0x40, 0x20, 0x20, 0x63, 0xE0, 0xFF,
0x80, 0x07, 0xFC, 0x39, 0xCE, 0x00, 0x00, 0x06, 0x33, 0x98, 0xC4, 0x00,
0x00, 0xC0, 0x60, 0x18, 0x0C, 0x06, 0x01, 0x80, 0x0C, 0x00, 0x60, 0x03,
0x00, 0x30, 0x01, 0x00, 0xFF, 0xF0, 0x00, 0x00, 0x0F, 0xFF, 0xC0, 0x06,
0x00, 0x30, 0x01, 0x80, 0x18, 0x01, 0x80, 0xC0, 0x30, 0x18, 0x0C, 0x02,
0x00, 0x00, 0x3E, 0x60, 0xA0, 0x20, 0x10, 0x08, 0x08, 0x18, 0x10, 0x08,
0x00, 0x00, 0x00, 0x01, 0xC0, 0xE0, 0x1C, 0x31, 0x10, 0x50, 0x28, 0x14,
0x3A, 0x25, 0x22, 0x91, 0x4C, 0xA3, 0xF0, 0x08, 0x02, 0x01, 0x80, 0x7C,
0x3F, 0x00, 0x0C, 0x00, 0x48, 0x01, 0x20, 0x04, 0x40, 0x21, 0x00, 0x84,
0x04, 0x08, 0x1F, 0xE0, 0x40, 0x82, 0x01, 0x08, 0x04, 0x20, 0x13, 0xE1,
0xF0, 0xFF, 0x08, 0x11, 0x01, 0x20, 0x24, 0x04, 0x81, 0x1F, 0xC2, 0x06,
0x40, 0x68, 0x05, 0x00, 0xA0, 0x14, 0x05, 0xFF, 0x00, 0x1E, 0x48, 0x74,
0x05, 0x01, 0x80, 0x20, 0x08, 0x02, 0x00, 0x80, 0x20, 0x04, 0x01, 0x01,
0x30, 0x87, 0xC0, 0xFE, 0x10, 0x44, 0x09, 0x02, 0x40, 0x50, 0x14, 0x05,
0x01, 0x40, 0x50, 0x14, 0x0D, 0x02, 0x41, 0x3F, 0x80, 0xFF, 0xC8, 0x09,
0x01, 0x20, 0x04, 0x00, 0x88, 0x1F, 0x02, 0x20, 0x40, 0x08, 0x01, 0x00,
0xA0, 0x14, 0x03, 0xFF, 0xC0, 0xFF, 0xE8, 0x05, 0x00, 0xA0, 0x04, 0x00,
0x88, 0x1F, 0x02, 0x20, 0x40, 0x08, 0x01, 0x00, 0x20, 0x04, 0x01, 0xF0,
0x00, 0x1F, 0x46, 0x19, 0x01, 0x60, 0x28, 0x01, 0x00, 0x20, 0x04, 0x00,
0x83, 0xF0, 0x0B, 0x01, 0x20, 0x23, 0x0C, 0x3E, 0x00, 0xE1, 0xD0, 0x24,
0x09, 0x02, 0x40, 0x90, 0x27, 0xF9, 0x02, 0x40, 0x90, 0x24, 0x09, 0x02,
0x40, 0xB8, 0x70, 0xFE, 0x20, 0x40, 0x81, 0x02, 0x04, 0x08, 0x10, 0x20,
0x40, 0x81, 0x1F, 0xC0, 0x0F, 0xE0, 0x10, 0x02, 0x00, 0x40, 0x08, 0x01,
0x00, 0x20, 0x04, 0x80, 0x90, 0x12, 0x02, 0x40, 0xC6, 0x30, 0x7C, 0x00,
0xF1, 0xE4, 0x0C, 0x41, 0x04, 0x20, 0x44, 0x04, 0x80, 0x5C, 0x06, 0x60,
0x43, 0x04, 0x10, 0x40, 0x84, 0x08, 0x40, 0xCF, 0x07, 0xF8, 0x04, 0x00,
0x80, 0x10, 0x02, 0x00, 0x40, 0x08, 0x01, 0x00, 0x20, 0x04, 0x04, 0x80,
0x90, 0x12, 0x03, 0xFF, 0xC0, 0xE0, 0x3B, 0x01, 0x94, 0x14, 0xA0, 0xA4,
0x89, 0x24, 0x49, 0x14, 0x48, 0xA2, 0x45, 0x12, 0x10, 0x90, 0x04, 0x80,
0x24, 0x01, 0x78, 0x3C, 0xE0, 0xF6, 0x02, 0x50, 0x25, 0x02, 0x48, 0x24,
0xC2, 0x44, 0x24, 0x22, 0x43, 0x24, 0x12, 0x40, 0xA4, 0x0A, 0x40, 0x6F,
0x06, 0x0F, 0x03, 0x0C, 0x60, 0x64, 0x02, 0x80, 0x18, 0x01, 0x80, 0x18,
0x01, 0x80, 0x18, 0x01, 0x40, 0x26, 0x06, 0x30, 0xC0, 0xF0, 0xFF, 0x10,
0x64, 0x05, 0x01, 0x40, 0x50, 0x34, 0x19, 0xFC, 0x40, 0x10, 0x04, 0x01,
0x00, 0x40, 0x3E, 0x00, 0x0F, 0x03, 0x0C, 0x60, 0x64, 0x02, 0x80, 0x18,
0x01, 0x80, 0x18, 0x01, 0x80, 0x18, 0x01, 0x40, 0x26, 0x06, 0x30, 0xC1,
0xF0, 0x0C, 0x01, 0xF1, 0x30, 0xE0, 0xFF, 0x04, 0x18, 0x40, 0xC4, 0x04,
0x40, 0x44, 0x0C, 0x41, 0x87, 0xE0, 0x43, 0x04, 0x10, 0x40, 0x84, 0x04,
0x40, 0x4F, 0x03, 0x1F, 0x48, 0x34, 0x05, 0x01, 0x40, 0x08, 0x01, 0xC0,
0x0E, 0x00, 0x40, 0x18, 0x06, 0x01, 0xE1, 0xA7, 0xC0, 0xFF, 0xF0, 0x86,
0x10, 0x82, 0x00, 0x40, 0x08, 0x01, 0x00, 0x20, 0x04, 0x00, 0x80, 0x10,
0x02, 0x00, 0x40, 0x7F, 0x00, 0xF0, 0xF4, 0x02, 0x40, 0x24, 0x02, 0x40,
0x24, 0x02, 0x40, 0x24, 0x02, 0x40, 0x24, 0x02, 0x40, 0x22, 0x04, 0x30,
0xC0, 0xF0, 0xF8, 0x7C, 0x80, 0x22, 0x01, 0x04, 0x04, 0x10, 0x20, 0x40,
0x80, 0x82, 0x02, 0x10, 0x08, 0x40, 0x11, 0x00, 0x48, 0x01, 0xA0, 0x03,
0x00, 0x0C, 0x00, 0xF8, 0x7C, 0x80, 0x22, 0x00, 0x88, 0xC2, 0x23, 0x10,
0x8E, 0x42, 0x29, 0x09, 0x24, 0x24, 0x90, 0x91, 0x41, 0x85, 0x06, 0x14,
0x18, 0x70, 0x60, 0x80, 0xF0, 0xF2, 0x06, 0x30, 0x41, 0x08, 0x09, 0x80,
0x50, 0x06, 0x00, 0x60, 0x0D, 0x00, 0x88, 0x10, 0xC2, 0x04, 0x60, 0x2F,
0x0F, 0xF0, 0xF2, 0x02, 0x10, 0x41, 0x04, 0x08, 0x80, 0x50, 0x05, 0x00,
0x20, 0x02, 0x00, 0x20, 0x02, 0x00, 0x20, 0x02, 0x01, 0xFC, 0xFF, 0x40,
0xA0, 0x90, 0x40, 0x40, 0x40, 0x20, 0x20, 0x20, 0x10, 0x50, 0x30, 0x18,
0x0F, 0xFC, 0xF2, 0x49, 0x24, 0x92, 0x49, 0x24, 0x9C, 0x80, 0x60, 0x10,
0x08, 0x02, 0x01, 0x00, 0x40, 0x20, 0x08, 0x04, 0x01, 0x00, 0x80, 0x20,
0x10, 0x04, 0x02, 0x00, 0x80, 0x40, 0xE4, 0x92, 0x49, 0x24, 0x92, 0x49,
0x3C, 0x08, 0x0C, 0x09, 0x0C, 0x4C, 0x14, 0x04, 0xFF, 0xFC, 0x84, 0x21,
0x3E, 0x00, 0x60, 0x08, 0x02, 0x3F, 0x98, 0x28, 0x0A, 0x02, 0xC3, 0x9F,
0x30, 0xE0, 0x01, 0x00, 0x08, 0x00, 0x40, 0x02, 0x00, 0x13, 0xE0, 0xA0,
0x86, 0x02, 0x20, 0x09, 0x00, 0x48, 0x02, 0x40, 0x13, 0x01, 0x14, 0x1B,
0x9F, 0x00, 0x1F, 0x4C, 0x19, 0x01, 0x40, 0x28, 0x01, 0x00, 0x20, 0x02,
0x00, 0x60, 0x43, 0xF0, 0x00, 0xC0, 0x08, 0x01, 0x00, 0x20, 0x04, 0x3C,
0x98, 0x52, 0x06, 0x80, 0x50, 0x0A, 0x01, 0x40, 0x24, 0x0C, 0xC2, 0x87,
0x98, 0x3F, 0x18, 0x68, 0x06, 0x01, 0xFF, 0xE0, 0x08, 0x03, 0x00, 0x60,
0xC7, 0xC0, 0x0F, 0x98, 0x08, 0x04, 0x02, 0x07, 0xF8, 0x80, 0x40, 0x20,
0x10, 0x08, 0x04, 0x02, 0x01, 0x03, 0xF8, 0x1E, 0x6C, 0x39, 0x03, 0x40,
0x28, 0x05, 0x00, 0xA0, 0x12, 0x06, 0x61, 0x43, 0xC8, 0x01, 0x00, 0x20,
0x08, 0x3E, 0x00, 0xC0, 0x10, 0x04, 0x01, 0x00, 0x40, 0x13, 0x87, 0x11,
0x82, 0x40, 0x90, 0x24, 0x09, 0x02, 0x40, 0x90, 0x2E, 0x1C, 0x08, 0x04,
0x02, 0x00, 0x00, 0x03, 0xC0, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01, 0x00,
0x80, 0x43, 0xFE, 0x04, 0x08, 0x10, 0x00, 0x1F, 0xC0, 0x81, 0x02, 0x04,
0x08, 0x10, 0x20, 0x40, 0x81, 0x02, 0x0B, 0xE0, 0xE0, 0x02, 0x00, 0x20,
0x02, 0x00, 0x20, 0x02, 0x3C, 0x21, 0x02, 0x60, 0x2C, 0x03, 0x80, 0x24,
0x02, 0x20, 0x21, 0x02, 0x08, 0xE1, 0xF0, 0x78, 0x04, 0x02, 0x01, 0x00,
0x80, 0x40, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01, 0x00, 0x80, 0x43, 0xFE,
0xDC, 0xE3, 0x19, 0x90, 0x84, 0x84, 0x24, 0x21, 0x21, 0x09, 0x08, 0x48,
0x42, 0x42, 0x17, 0x18, 0xC0, 0x67, 0x83, 0x84, 0x20, 0x22, 0x02, 0x20,
0x22, 0x02, 0x20, 0x22, 0x02, 0x20, 0x2F, 0x07, 0x1F, 0x04, 0x11, 0x01,
0x40, 0x18, 0x03, 0x00, 0x60, 0x0A, 0x02, 0x20, 0x83, 0xE0, 0xCF, 0x85,
0x06, 0x60, 0x24, 0x01, 0x40, 0x14, 0x01, 0x40, 0x16, 0x02, 0x50, 0x44,
0xF8, 0x40, 0x04, 0x00, 0x40, 0x0F, 0x00, 0x1E, 0x6C, 0x3B, 0x03, 0x40,
0x28, 0x05, 0x00, 0xA0, 0x12, 0x06, 0x61, 0x43, 0xC8, 0x01, 0x00, 0x20,
0x04, 0x03, 0xC0, 0xE3, 0x8B, 0x13, 0x80, 0x80, 0x20, 0x08, 0x02, 0x00,
0x80, 0x20, 0x3F, 0x80, 0x1F, 0x58, 0x34, 0x05, 0x80, 0x1E, 0x00, 0x60,
0x06, 0x01, 0xC0, 0xAF, 0xC0, 0x20, 0x04, 0x00, 0x80, 0x10, 0x0F, 0xF0,
0x40, 0x08, 0x01, 0x00, 0x20, 0x04, 0x00, 0x80, 0x10, 0x03, 0x04, 0x3F,
0x00, 0xC1, 0xC8, 0x09, 0x01, 0x20, 0x24, 0x04, 0x80, 0x90, 0x12, 0x02,
0x61, 0xC7, 0xCC, 0xF8, 0xF9, 0x01, 0x08, 0x10, 0x60, 0x81, 0x08, 0x08,
0x40, 0x22, 0x01, 0x20, 0x05, 0x00, 0x30, 0x00, 0xF0, 0x7A, 0x01, 0x10,
0x08, 0x8C, 0x42, 0x62, 0x12, 0x90, 0xA5, 0x05, 0x18, 0x28, 0xC0, 0x86,
0x00, 0x78, 0xF3, 0x04, 0x18, 0x80, 0xD0, 0x06, 0x00, 0x70, 0x09, 0x81,
0x0C, 0x20, 0x6F, 0x8F, 0xF0, 0xF2, 0x02, 0x20, 0x41, 0x04, 0x10, 0x80,
0x88, 0x09, 0x00, 0x50, 0x06, 0x00, 0x20, 0x04, 0x00, 0x40, 0x08, 0x0F,
0xE0, 0xFF, 0x41, 0x00, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x40, 0xBF,
0xC0, 0x19, 0x08, 0x42, 0x10, 0x84, 0x64, 0x18, 0x42, 0x10, 0x84, 0x20,
0xC0, 0xFF, 0xFF, 0xC0, 0xC1, 0x08, 0x42, 0x10, 0x84, 0x10, 0x4C, 0x42,
0x10, 0x84, 0x26, 0x00, 0x38, 0x13, 0x38, 0x38 };
const GFXglyph FreeMono12pt7bGlyphs[] PROGMEM = {
{ 0, 0, 0, 14, 0, 1 }, // 0x20 ' '
{ 0, 3, 15, 14, 6, -14 }, // 0x21 '!'
{ 6, 8, 7, 14, 3, -14 }, // 0x22 '"'
{ 13, 10, 16, 14, 2, -14 }, // 0x23 '#'
{ 33, 10, 17, 14, 2, -14 }, // 0x24 '$'
{ 55, 10, 15, 14, 2, -14 }, // 0x25 '%'
{ 74, 9, 12, 14, 3, -11 }, // 0x26 '&'
{ 88, 3, 7, 14, 5, -14 }, // 0x27 '''
{ 91, 3, 18, 14, 7, -14 }, // 0x28 '('
{ 98, 3, 18, 14, 4, -14 }, // 0x29 ')'
{ 105, 9, 9, 14, 3, -14 }, // 0x2A '*'
{ 116, 9, 11, 14, 3, -11 }, // 0x2B '+'
{ 129, 5, 7, 14, 3, -3 }, // 0x2C ','
{ 134, 11, 1, 14, 2, -6 }, // 0x2D '-'
{ 136, 3, 3, 14, 5, -2 }, // 0x2E '.'
{ 138, 9, 18, 14, 3, -15 }, // 0x2F '/'
{ 159, 9, 15, 14, 3, -14 }, // 0x30 '0'
{ 176, 7, 14, 14, 4, -13 }, // 0x31 '1'
{ 189, 9, 15, 14, 2, -14 }, // 0x32 '2'
{ 206, 10, 15, 14, 2, -14 }, // 0x33 '3'
{ 225, 8, 15, 14, 3, -14 }, // 0x34 '4'
{ 240, 9, 15, 14, 3, -14 }, // 0x35 '5'
{ 257, 9, 15, 14, 3, -14 }, // 0x36 '6'
{ 274, 8, 15, 14, 3, -14 }, // 0x37 '7'
{ 289, 9, 15, 14, 3, -14 }, // 0x38 '8'
{ 306, 9, 15, 14, 3, -14 }, // 0x39 '9'
{ 323, 3, 10, 14, 5, -9 }, // 0x3A ':'
{ 327, 5, 13, 14, 3, -9 }, // 0x3B ';'
{ 336, 11, 11, 14, 2, -11 }, // 0x3C '<'
{ 352, 12, 4, 14, 1, -8 }, // 0x3D '='
{ 358, 11, 11, 14, 2, -11 }, // 0x3E '>'
{ 374, 9, 14, 14, 3, -13 }, // 0x3F '?'
{ 390, 9, 16, 14, 3, -14 }, // 0x40 '@'
{ 408, 14, 14, 14, 0, -13 }, // 0x41 'A'
{ 433, 11, 14, 14, 2, -13 }, // 0x42 'B'
{ 453, 10, 14, 14, 2, -13 }, // 0x43 'C'
{ 471, 10, 14, 14, 2, -13 }, // 0x44 'D'
{ 489, 11, 14, 14, 2, -13 }, // 0x45 'E'
{ 509, 11, 14, 14, 2, -13 }, // 0x46 'F'
{ 529, 11, 14, 14, 2, -13 }, // 0x47 'G'
{ 549, 10, 14, 14, 2, -13 }, // 0x48 'H'
{ 567, 7, 14, 14, 4, -13 }, // 0x49 'I'
{ 580, 11, 14, 14, 2, -13 }, // 0x4A 'J'
{ 600, 12, 14, 14, 2, -13 }, // 0x4B 'K'
{ 621, 11, 14, 14, 2, -13 }, // 0x4C 'L'
{ 641, 13, 14, 14, 1, -13 }, // 0x4D 'M'
{ 664, 12, 14, 14, 1, -13 }, // 0x4E 'N'
{ 685, 12, 14, 14, 1, -13 }, // 0x4F 'O'
{ 706, 10, 14, 14, 2, -13 }, // 0x50 'P'
{ 724, 12, 17, 14, 1, -13 }, // 0x51 'Q'
{ 750, 12, 14, 14, 2, -13 }, // 0x52 'R'
{ 771, 10, 14, 14, 2, -13 }, // 0x53 'S'
{ 789, 11, 14, 14, 2, -13 }, // 0x54 'T'
{ 809, 12, 14, 14, 1, -13 }, // 0x55 'U'
{ 830, 14, 14, 14, 0, -13 }, // 0x56 'V'
{ 855, 14, 14, 14, 0, -13 }, // 0x57 'W'
{ 880, 12, 14, 14, 1, -13 }, // 0x58 'X'
{ 901, 12, 14, 14, 1, -13 }, // 0x59 'Y'
{ 922, 9, 14, 14, 3, -13 }, // 0x5A 'Z'
{ 938, 3, 18, 14, 7, -14 }, // 0x5B '['
{ 945, 9, 18, 14, 3, -15 }, // 0x5C '\'
{ 966, 3, 18, 14, 5, -14 }, // 0x5D ']'
{ 973, 9, 6, 14, 3, -14 }, // 0x5E '^'
{ 980, 14, 1, 14, 0, 3 }, // 0x5F '_'
{ 982, 4, 4, 14, 4, -15 }, // 0x60 '`'
{ 984, 10, 10, 14, 2, -9 }, // 0x61 'a'
{ 997, 13, 15, 14, 0, -14 }, // 0x62 'b'
{ 1022, 11, 10, 14, 2, -9 }, // 0x63 'c'
{ 1036, 11, 15, 14, 2, -14 }, // 0x64 'd'
{ 1057, 10, 10, 14, 2, -9 }, // 0x65 'e'
{ 1070, 9, 15, 14, 4, -14 }, // 0x66 'f'
{ 1087, 11, 14, 14, 2, -9 }, // 0x67 'g'
{ 1107, 10, 15, 14, 2, -14 }, // 0x68 'h'
{ 1126, 9, 15, 14, 3, -14 }, // 0x69 'i'
{ 1143, 7, 19, 14, 3, -14 }, // 0x6A 'j'
{ 1160, 12, 15, 14, 1, -14 }, // 0x6B 'k'
{ 1183, 9, 15, 14, 3, -14 }, // 0x6C 'l'
{ 1200, 13, 10, 14, 1, -9 }, // 0x6D 'm'
{ 1217, 12, 10, 14, 1, -9 }, // 0x6E 'n'
{ 1232, 11, 10, 14, 2, -9 }, // 0x6F 'o'
{ 1246, 12, 14, 14, 1, -9 }, // 0x70 'p'
{ 1267, 11, 14, 14, 2, -9 }, // 0x71 'q'
{ 1287, 10, 10, 14, 3, -9 }, // 0x72 'r'
{ 1300, 10, 10, 14, 2, -9 }, // 0x73 's'
{ 1313, 11, 14, 14, 1, -13 }, // 0x74 't'
{ 1333, 11, 10, 14, 2, -9 }, // 0x75 'u'
{ 1347, 13, 10, 14, 1, -9 }, // 0x76 'v'
{ 1364, 13, 10, 14, 1, -9 }, // 0x77 'w'
{ 1381, 12, 10, 14, 1, -9 }, // 0x78 'x'
{ 1396, 12, 14, 14, 1, -9 }, // 0x79 'y'
{ 1417, 9, 10, 14, 3, -9 }, // 0x7A 'z'
{ 1429, 5, 18, 14, 5, -14 }, // 0x7B '{'
{ 1441, 1, 18, 14, 7, -14 }, // 0x7C '|'
{ 1444, 5, 18, 14, 5, -14 }, // 0x7D '}'
{ 1456, 10, 3, 14, 2, -7 } }; // 0x7E '~'
const GFXfont FreeMono12pt7b PROGMEM = {
(uint8_t *)FreeMono12pt7bBitmaps,
(GFXglyph *)FreeMono12pt7bGlyphs,
0x20, 0x7E, 24 };
// Approx. 2132 bytes

View File

@ -0,0 +1,363 @@
const uint8_t FreeMono18pt7bBitmaps[] PROGMEM = {
0x27, 0x77, 0x77, 0x77, 0x77, 0x22, 0x22, 0x20, 0x00, 0x6F, 0xF6, 0xF1,
0xFE, 0x3F, 0xC7, 0xF8, 0xFF, 0x1E, 0xC3, 0x98, 0x33, 0x06, 0x60, 0xCC,
0x18, 0x04, 0x20, 0x10, 0x80, 0x42, 0x01, 0x08, 0x04, 0x20, 0x10, 0x80,
0x42, 0x01, 0x10, 0x04, 0x41, 0xFF, 0xF0, 0x44, 0x02, 0x10, 0x08, 0x40,
0x21, 0x0F, 0xFF, 0xC2, 0x10, 0x08, 0x40, 0x21, 0x00, 0x84, 0x02, 0x10,
0x08, 0x40, 0x23, 0x00, 0x88, 0x02, 0x20, 0x02, 0x00, 0x10, 0x00, 0x80,
0x1F, 0xA3, 0x07, 0x10, 0x09, 0x00, 0x48, 0x00, 0x40, 0x03, 0x00, 0x0C,
0x00, 0x3C, 0x00, 0x1E, 0x00, 0x18, 0x00, 0x20, 0x01, 0x80, 0x0C, 0x00,
0x70, 0x05, 0xE0, 0xC9, 0xF8, 0x01, 0x00, 0x08, 0x00, 0x40, 0x02, 0x00,
0x10, 0x00, 0x1E, 0x00, 0x42, 0x01, 0x02, 0x02, 0x04, 0x04, 0x08, 0x08,
0x10, 0x08, 0x40, 0x0F, 0x00, 0x00, 0x1E, 0x01, 0xF0, 0x1F, 0x01, 0xE0,
0x0E, 0x00, 0x00, 0x3C, 0x00, 0x86, 0x02, 0x06, 0x04, 0x04, 0x08, 0x08,
0x10, 0x30, 0x10, 0xC0, 0x1E, 0x00, 0x0F, 0xC1, 0x00, 0x20, 0x02, 0x00,
0x20, 0x02, 0x00, 0x10, 0x01, 0x00, 0x08, 0x03, 0xC0, 0x6C, 0x3C, 0x62,
0x82, 0x68, 0x34, 0x81, 0xCC, 0x08, 0x61, 0xC3, 0xE7, 0xFF, 0xFF, 0xF6,
0x66, 0x66, 0x08, 0xC4, 0x62, 0x31, 0x8C, 0xC6, 0x31, 0x8C, 0x63, 0x18,
0xC3, 0x18, 0xC2, 0x18, 0xC3, 0x18, 0x86, 0x10, 0xC2, 0x18, 0xC6, 0x10,
0xC6, 0x31, 0x8C, 0x63, 0x18, 0x8C, 0x62, 0x31, 0x98, 0x80, 0x02, 0x00,
0x10, 0x00, 0x80, 0x04, 0x0C, 0x21, 0x9D, 0x70, 0x1C, 0x00, 0xA0, 0x0D,
0x80, 0xC6, 0x04, 0x10, 0x40, 0x80, 0x01, 0x00, 0x02, 0x00, 0x04, 0x00,
0x08, 0x00, 0x10, 0x00, 0x20, 0x00, 0x40, 0x00, 0x80, 0xFF, 0xFE, 0x02,
0x00, 0x04, 0x00, 0x08, 0x00, 0x10, 0x00, 0x20, 0x00, 0x40, 0x00, 0x80,
0x01, 0x00, 0x3E, 0x78, 0xF3, 0xC7, 0x8E, 0x18, 0x70, 0xC1, 0x80, 0xFF,
0xFE, 0x77, 0xFF, 0xF7, 0x00, 0x00, 0x08, 0x00, 0xC0, 0x04, 0x00, 0x60,
0x02, 0x00, 0x30, 0x01, 0x00, 0x18, 0x00, 0x80, 0x0C, 0x00, 0x40, 0x02,
0x00, 0x20, 0x01, 0x00, 0x10, 0x00, 0x80, 0x08, 0x00, 0x40, 0x04, 0x00,
0x20, 0x02, 0x00, 0x10, 0x01, 0x00, 0x08, 0x00, 0x80, 0x04, 0x00, 0x00,
0x0F, 0x81, 0x82, 0x08, 0x08, 0x80, 0x24, 0x01, 0x60, 0x0E, 0x00, 0x30,
0x01, 0x80, 0x0C, 0x00, 0x60, 0x03, 0x00, 0x18, 0x00, 0xC0, 0x06, 0x00,
0x30, 0x03, 0x40, 0x12, 0x00, 0x88, 0x08, 0x60, 0xC0, 0xF8, 0x00, 0x06,
0x00, 0x70, 0x06, 0x80, 0x64, 0x06, 0x20, 0x31, 0x00, 0x08, 0x00, 0x40,
0x02, 0x00, 0x10, 0x00, 0x80, 0x04, 0x00, 0x20, 0x01, 0x00, 0x08, 0x00,
0x40, 0x02, 0x00, 0x10, 0x00, 0x80, 0x04, 0x0F, 0xFF, 0x80, 0x0F, 0x80,
0xC3, 0x08, 0x04, 0x80, 0x24, 0x00, 0x80, 0x04, 0x00, 0x20, 0x02, 0x00,
0x10, 0x01, 0x00, 0x10, 0x01, 0x80, 0x18, 0x01, 0x80, 0x18, 0x01, 0x80,
0x18, 0x01, 0x80, 0x58, 0x03, 0x80, 0x1F, 0xFF, 0x80, 0x0F, 0xC0, 0xC0,
0x86, 0x01, 0x00, 0x02, 0x00, 0x08, 0x00, 0x20, 0x00, 0x80, 0x04, 0x00,
0x20, 0x0F, 0x00, 0x06, 0x00, 0x04, 0x00, 0x08, 0x00, 0x10, 0x00, 0x40,
0x01, 0x00, 0x04, 0x00, 0x2C, 0x01, 0x9C, 0x0C, 0x0F, 0xC0, 0x01, 0xC0,
0x14, 0x02, 0x40, 0x64, 0x04, 0x40, 0xC4, 0x08, 0x41, 0x84, 0x10, 0x42,
0x04, 0x20, 0x44, 0x04, 0x40, 0x48, 0x04, 0xFF, 0xF0, 0x04, 0x00, 0x40,
0x04, 0x00, 0x40, 0x04, 0x07, 0xF0, 0x3F, 0xF0, 0x80, 0x02, 0x00, 0x08,
0x00, 0x20, 0x00, 0x80, 0x02, 0x00, 0x0B, 0xF0, 0x30, 0x30, 0x00, 0x60,
0x00, 0x80, 0x01, 0x00, 0x04, 0x00, 0x10, 0x00, 0x40, 0x01, 0x00, 0x0E,
0x00, 0x2C, 0x01, 0x0C, 0x18, 0x0F, 0xC0, 0x01, 0xF0, 0x60, 0x18, 0x03,
0x00, 0x20, 0x04, 0x00, 0x40, 0x0C, 0x00, 0x80, 0x08, 0xF8, 0x98, 0x4A,
0x02, 0xE0, 0x3C, 0x01, 0x80, 0x14, 0x01, 0x40, 0x14, 0x03, 0x20, 0x21,
0x0C, 0x0F, 0x80, 0xFF, 0xF8, 0x01, 0x80, 0x18, 0x03, 0x00, 0x20, 0x02,
0x00, 0x20, 0x04, 0x00, 0x40, 0x04, 0x00, 0xC0, 0x08, 0x00, 0x80, 0x18,
0x01, 0x00, 0x10, 0x01, 0x00, 0x30, 0x02, 0x00, 0x20, 0x02, 0x00, 0x0F,
0x81, 0x83, 0x10, 0x05, 0x80, 0x38, 0x00, 0xC0, 0x06, 0x00, 0x30, 0x03,
0x40, 0x11, 0x83, 0x07, 0xF0, 0x60, 0xC4, 0x01, 0x60, 0x0E, 0x00, 0x30,
0x01, 0x80, 0x0E, 0x00, 0xD0, 0x04, 0x60, 0xC1, 0xFC, 0x00, 0x1F, 0x03,
0x08, 0x40, 0x4C, 0x02, 0x80, 0x28, 0x02, 0x80, 0x18, 0x03, 0xC0, 0x74,
0x05, 0x21, 0x91, 0xF1, 0x00, 0x10, 0x03, 0x00, 0x20, 0x02, 0x00, 0x40,
0x0C, 0x01, 0x80, 0x60, 0xF8, 0x00, 0x77, 0xFF, 0xF7, 0x00, 0x00, 0x00,
0x1D, 0xFF, 0xFD, 0xC0, 0x1C, 0x7C, 0xF9, 0xF1, 0xC0, 0x00, 0x00, 0x00,
0x00, 0xF1, 0xE3, 0x8F, 0x1C, 0x38, 0xE1, 0xC3, 0x06, 0x00, 0x00, 0x06,
0x00, 0x18, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x01, 0xC0, 0x06, 0x00, 0x38,
0x00, 0xE0, 0x00, 0x70, 0x00, 0x38, 0x00, 0x18, 0x00, 0x1C, 0x00, 0x0E,
0x00, 0x07, 0x00, 0x03, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x07, 0xFF, 0xFC, 0xC0, 0x00, 0xC0, 0x00, 0xE0, 0x00, 0x70,
0x00, 0x38, 0x00, 0x1C, 0x00, 0x0C, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x70,
0x03, 0x80, 0x0C, 0x00, 0x70, 0x03, 0x80, 0x1C, 0x00, 0x60, 0x00, 0x3F,
0x8E, 0x0C, 0x80, 0x28, 0x01, 0x80, 0x10, 0x01, 0x00, 0x10, 0x02, 0x00,
0xC0, 0x38, 0x06, 0x00, 0x40, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0E,
0x01, 0xF0, 0x1F, 0x00, 0xE0, 0x0F, 0x01, 0x86, 0x08, 0x08, 0x80, 0x24,
0x01, 0x40, 0x0A, 0x00, 0x50, 0x1E, 0x83, 0x14, 0x20, 0xA2, 0x05, 0x10,
0x28, 0x81, 0x46, 0x0A, 0x18, 0x50, 0x3F, 0x80, 0x04, 0x00, 0x10, 0x00,
0x80, 0x02, 0x00, 0x18, 0x18, 0x3F, 0x00, 0x1F, 0xF0, 0x00, 0x06, 0x80,
0x00, 0x34, 0x00, 0x01, 0x30, 0x00, 0x18, 0x80, 0x00, 0x86, 0x00, 0x04,
0x30, 0x00, 0x60, 0x80, 0x02, 0x06, 0x00, 0x10, 0x10, 0x01, 0x80, 0x80,
0x08, 0x06, 0x00, 0x7F, 0xF0, 0x06, 0x00, 0x80, 0x20, 0x06, 0x01, 0x00,
0x10, 0x18, 0x00, 0xC0, 0x80, 0x06, 0x04, 0x00, 0x11, 0xFC, 0x0F, 0xF0,
0xFF, 0xF8, 0x04, 0x01, 0x01, 0x00, 0x20, 0x40, 0x04, 0x10, 0x01, 0x04,
0x00, 0x41, 0x00, 0x10, 0x40, 0x08, 0x10, 0x0C, 0x07, 0xFF, 0x01, 0x00,
0x70, 0x40, 0x06, 0x10, 0x00, 0x84, 0x00, 0x11, 0x00, 0x04, 0x40, 0x01,
0x10, 0x00, 0x44, 0x00, 0x21, 0x00, 0x33, 0xFF, 0xF8, 0x03, 0xF1, 0x06,
0x0E, 0x8C, 0x01, 0xC4, 0x00, 0x64, 0x00, 0x12, 0x00, 0x0A, 0x00, 0x01,
0x00, 0x00, 0x80, 0x00, 0x40, 0x00, 0x20, 0x00, 0x10, 0x00, 0x08, 0x00,
0x04, 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, 0x20, 0x01, 0x88, 0x01, 0x83,
0x03, 0x80, 0x7E, 0x00, 0xFF, 0xE0, 0x20, 0x18, 0x20, 0x0C, 0x20, 0x04,
0x20, 0x02, 0x20, 0x02, 0x20, 0x01, 0x20, 0x01, 0x20, 0x01, 0x20, 0x01,
0x20, 0x01, 0x20, 0x01, 0x20, 0x01, 0x20, 0x01, 0x20, 0x02, 0x20, 0x02,
0x20, 0x04, 0x20, 0x0C, 0x20, 0x18, 0xFF, 0xE0, 0xFF, 0xFF, 0x08, 0x00,
0x84, 0x00, 0x42, 0x00, 0x21, 0x00, 0x10, 0x80, 0x00, 0x40, 0x00, 0x20,
0x40, 0x10, 0x20, 0x0F, 0xF0, 0x04, 0x08, 0x02, 0x04, 0x01, 0x00, 0x00,
0x80, 0x00, 0x40, 0x02, 0x20, 0x01, 0x10, 0x00, 0x88, 0x00, 0x44, 0x00,
0x3F, 0xFF, 0xF0, 0xFF, 0xFF, 0x88, 0x00, 0x44, 0x00, 0x22, 0x00, 0x11,
0x00, 0x08, 0x80, 0x00, 0x40, 0x00, 0x20, 0x40, 0x10, 0x20, 0x0F, 0xF0,
0x04, 0x08, 0x02, 0x04, 0x01, 0x00, 0x00, 0x80, 0x00, 0x40, 0x00, 0x20,
0x00, 0x10, 0x00, 0x08, 0x00, 0x04, 0x00, 0x1F, 0xF8, 0x00, 0x03, 0xF9,
0x06, 0x07, 0x84, 0x00, 0xC4, 0x00, 0x24, 0x00, 0x12, 0x00, 0x02, 0x00,
0x01, 0x00, 0x00, 0x80, 0x00, 0x40, 0x00, 0x20, 0x00, 0x10, 0x0F, 0xF8,
0x00, 0x14, 0x00, 0x09, 0x00, 0x04, 0x80, 0x02, 0x20, 0x01, 0x18, 0x00,
0x83, 0x01, 0xC0, 0x7F, 0x00, 0xFC, 0x3F, 0x20, 0x04, 0x20, 0x04, 0x20,
0x04, 0x20, 0x04, 0x20, 0x04, 0x20, 0x04, 0x20, 0x04, 0x20, 0x04, 0x3F,
0xFC, 0x20, 0x04, 0x20, 0x04, 0x20, 0x04, 0x20, 0x04, 0x20, 0x04, 0x20,
0x04, 0x20, 0x04, 0x20, 0x04, 0x20, 0x04, 0xFC, 0x3F, 0xFF, 0xF8, 0x10,
0x00, 0x80, 0x04, 0x00, 0x20, 0x01, 0x00, 0x08, 0x00, 0x40, 0x02, 0x00,
0x10, 0x00, 0x80, 0x04, 0x00, 0x20, 0x01, 0x00, 0x08, 0x00, 0x40, 0x02,
0x00, 0x10, 0x00, 0x81, 0xFF, 0xF0, 0x03, 0xFF, 0x80, 0x04, 0x00, 0x02,
0x00, 0x01, 0x00, 0x00, 0x80, 0x00, 0x40, 0x00, 0x20, 0x00, 0x10, 0x00,
0x08, 0x00, 0x04, 0x00, 0x02, 0x10, 0x01, 0x08, 0x00, 0x84, 0x00, 0x42,
0x00, 0x21, 0x00, 0x10, 0x80, 0x10, 0x20, 0x18, 0x0C, 0x18, 0x01, 0xF0,
0x00, 0xFF, 0x1F, 0x84, 0x01, 0x81, 0x00, 0xC0, 0x40, 0x60, 0x10, 0x30,
0x04, 0x18, 0x01, 0x0C, 0x00, 0x46, 0x00, 0x13, 0x00, 0x05, 0xF0, 0x01,
0xC6, 0x00, 0x60, 0xC0, 0x10, 0x18, 0x04, 0x06, 0x01, 0x00, 0xC0, 0x40,
0x30, 0x10, 0x04, 0x04, 0x01, 0x81, 0x00, 0x23, 0xFC, 0x0F, 0xFF, 0x80,
0x10, 0x00, 0x20, 0x00, 0x40, 0x00, 0x80, 0x01, 0x00, 0x02, 0x00, 0x04,
0x00, 0x08, 0x00, 0x10, 0x00, 0x20, 0x00, 0x40, 0x00, 0x80, 0x01, 0x00,
0x42, 0x00, 0x84, 0x01, 0x08, 0x02, 0x10, 0x04, 0x20, 0x0F, 0xFF, 0xF0,
0xF0, 0x01, 0xE7, 0x00, 0x70, 0xA0, 0x0A, 0x16, 0x03, 0x42, 0x40, 0x48,
0x4C, 0x19, 0x08, 0x82, 0x21, 0x10, 0x44, 0x23, 0x18, 0x84, 0x22, 0x10,
0x86, 0xC2, 0x10, 0x50, 0x42, 0x0E, 0x08, 0x41, 0xC1, 0x08, 0x00, 0x21,
0x00, 0x04, 0x20, 0x00, 0x84, 0x00, 0x10, 0x80, 0x02, 0x7F, 0x03, 0xF0,
0xF8, 0x1F, 0xC6, 0x00, 0x41, 0xC0, 0x10, 0x50, 0x04, 0x12, 0x01, 0x04,
0xC0, 0x41, 0x10, 0x10, 0x46, 0x04, 0x10, 0x81, 0x04, 0x10, 0x41, 0x04,
0x10, 0x40, 0x84, 0x10, 0x31, 0x04, 0x04, 0x41, 0x01, 0x90, 0x40, 0x24,
0x10, 0x05, 0x04, 0x01, 0xC1, 0x00, 0x31, 0xFC, 0x0C, 0x03, 0xE0, 0x06,
0x0C, 0x04, 0x01, 0x04, 0x00, 0x46, 0x00, 0x32, 0x00, 0x0B, 0x00, 0x05,
0x00, 0x01, 0x80, 0x00, 0xC0, 0x00, 0x60, 0x00, 0x30, 0x00, 0x18, 0x00,
0x0E, 0x00, 0x0D, 0x00, 0x04, 0xC0, 0x06, 0x20, 0x02, 0x08, 0x02, 0x03,
0x06, 0x00, 0x7C, 0x00, 0xFF, 0xF0, 0x10, 0x0C, 0x10, 0x02, 0x10, 0x03,
0x10, 0x01, 0x10, 0x01, 0x10, 0x01, 0x10, 0x03, 0x10, 0x06, 0x10, 0x0C,
0x1F, 0xF0, 0x10, 0x00, 0x10, 0x00, 0x10, 0x00, 0x10, 0x00, 0x10, 0x00,
0x10, 0x00, 0x10, 0x00, 0x10, 0x00, 0xFF, 0xC0, 0x03, 0xE0, 0x06, 0x0C,
0x04, 0x01, 0x04, 0x00, 0x46, 0x00, 0x32, 0x00, 0x0B, 0x00, 0x07, 0x00,
0x01, 0x80, 0x00, 0xC0, 0x00, 0x60, 0x00, 0x30, 0x00, 0x18, 0x00, 0x0E,
0x00, 0x0D, 0x00, 0x04, 0xC0, 0x06, 0x20, 0x02, 0x08, 0x02, 0x03, 0x06,
0x00, 0xFC, 0x00, 0x30, 0x00, 0x30, 0x00, 0x7F, 0xC6, 0x38, 0x1E, 0xFF,
0xF0, 0x02, 0x01, 0x80, 0x40, 0x08, 0x08, 0x01, 0x81, 0x00, 0x10, 0x20,
0x02, 0x04, 0x00, 0x40, 0x80, 0x18, 0x10, 0x06, 0x02, 0x03, 0x80, 0x7F,
0xC0, 0x08, 0x18, 0x01, 0x01, 0x80, 0x20, 0x18, 0x04, 0x01, 0x80, 0x80,
0x10, 0x10, 0x03, 0x02, 0x00, 0x20, 0x40, 0x06, 0x7F, 0x80, 0x70, 0x0F,
0xC8, 0x61, 0xE2, 0x01, 0x90, 0x02, 0x40, 0x09, 0x00, 0x04, 0x00, 0x08,
0x00, 0x38, 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x06, 0x00, 0x0C, 0x00, 0x18,
0x00, 0x60, 0x01, 0x80, 0x0F, 0x00, 0x2B, 0x03, 0x23, 0xF0, 0xFF, 0xFF,
0x02, 0x06, 0x04, 0x0C, 0x08, 0x18, 0x10, 0x20, 0x20, 0x00, 0x40, 0x00,
0x80, 0x01, 0x00, 0x02, 0x00, 0x04, 0x00, 0x08, 0x00, 0x10, 0x00, 0x20,
0x00, 0x40, 0x00, 0x80, 0x01, 0x00, 0x02, 0x00, 0x04, 0x01, 0xFF, 0xC0,
0xFC, 0x1F, 0x90, 0x01, 0x08, 0x00, 0x84, 0x00, 0x42, 0x00, 0x21, 0x00,
0x10, 0x80, 0x08, 0x40, 0x04, 0x20, 0x02, 0x10, 0x01, 0x08, 0x00, 0x84,
0x00, 0x42, 0x00, 0x21, 0x00, 0x10, 0x80, 0x08, 0x40, 0x04, 0x10, 0x04,
0x0C, 0x06, 0x03, 0x06, 0x00, 0x7C, 0x00, 0xFE, 0x03, 0xF8, 0x80, 0x02,
0x04, 0x00, 0x10, 0x30, 0x01, 0x80, 0x80, 0x08, 0x06, 0x00, 0xC0, 0x30,
0x06, 0x00, 0x80, 0x20, 0x06, 0x03, 0x00, 0x30, 0x10, 0x00, 0x80, 0x80,
0x06, 0x0C, 0x00, 0x10, 0x40, 0x00, 0x86, 0x00, 0x06, 0x20, 0x00, 0x11,
0x00, 0x00, 0xD8, 0x00, 0x06, 0x80, 0x00, 0x1C, 0x00, 0x00, 0xE0, 0x00,
0xFC, 0x0F, 0xE8, 0x00, 0x19, 0x00, 0x03, 0x10, 0x00, 0x62, 0x00, 0x08,
0x41, 0x81, 0x08, 0x28, 0x21, 0x05, 0x04, 0x21, 0xA0, 0x84, 0x36, 0x30,
0x84, 0x46, 0x08, 0x88, 0xC1, 0x31, 0x18, 0x24, 0x12, 0x04, 0x82, 0x40,
0xB0, 0x48, 0x14, 0x09, 0x02, 0x80, 0xA0, 0x30, 0x1C, 0x06, 0x03, 0x80,
0x7E, 0x0F, 0xC2, 0x00, 0x60, 0x60, 0x0C, 0x06, 0x03, 0x00, 0x60, 0xC0,
0x0C, 0x10, 0x00, 0xC6, 0x00, 0x0D, 0x80, 0x00, 0xA0, 0x00, 0x1C, 0x00,
0x03, 0x80, 0x00, 0xD8, 0x00, 0x11, 0x00, 0x06, 0x30, 0x01, 0x83, 0x00,
0x60, 0x30, 0x08, 0x06, 0x03, 0x00, 0x60, 0xC0, 0x06, 0x7F, 0x07, 0xF0,
0xFC, 0x1F, 0x98, 0x03, 0x04, 0x01, 0x03, 0x01, 0x80, 0xC1, 0x80, 0x20,
0x80, 0x18, 0xC0, 0x04, 0x40, 0x03, 0x60, 0x00, 0xE0, 0x00, 0x20, 0x00,
0x10, 0x00, 0x08, 0x00, 0x04, 0x00, 0x02, 0x00, 0x01, 0x00, 0x00, 0x80,
0x00, 0x40, 0x00, 0x20, 0x03, 0xFF, 0x80, 0xFF, 0xF4, 0x00, 0xA0, 0x09,
0x00, 0x48, 0x04, 0x40, 0x40, 0x02, 0x00, 0x20, 0x02, 0x00, 0x10, 0x01,
0x00, 0x10, 0x00, 0x80, 0x08, 0x04, 0x80, 0x24, 0x01, 0x40, 0x0C, 0x00,
0x60, 0x03, 0xFF, 0xF0, 0xFC, 0x21, 0x08, 0x42, 0x10, 0x84, 0x21, 0x08,
0x42, 0x10, 0x84, 0x21, 0x08, 0x42, 0x10, 0xF8, 0x80, 0x02, 0x00, 0x10,
0x00, 0xC0, 0x02, 0x00, 0x18, 0x00, 0x40, 0x03, 0x00, 0x08, 0x00, 0x40,
0x01, 0x00, 0x08, 0x00, 0x20, 0x01, 0x00, 0x04, 0x00, 0x20, 0x00, 0x80,
0x04, 0x00, 0x10, 0x00, 0x80, 0x02, 0x00, 0x10, 0x00, 0x40, 0x02, 0x00,
0x08, 0x00, 0x40, 0xF8, 0x42, 0x10, 0x84, 0x21, 0x08, 0x42, 0x10, 0x84,
0x21, 0x08, 0x42, 0x10, 0x84, 0x21, 0xF8, 0x02, 0x00, 0x38, 0x03, 0x60,
0x11, 0x01, 0x8C, 0x18, 0x31, 0x80, 0xD8, 0x03, 0x80, 0x08, 0xFF, 0xFF,
0xF8, 0xC1, 0x83, 0x06, 0x0C, 0x0F, 0xC0, 0x70, 0x30, 0x00, 0x10, 0x00,
0x08, 0x00, 0x08, 0x00, 0x08, 0x0F, 0xF8, 0x30, 0x08, 0x40, 0x08, 0x80,
0x08, 0x80, 0x08, 0x80, 0x08, 0x80, 0x38, 0x60, 0xE8, 0x3F, 0x8F, 0xF0,
0x00, 0x04, 0x00, 0x01, 0x00, 0x00, 0x40, 0x00, 0x10, 0x00, 0x04, 0x00,
0x01, 0x0F, 0x80, 0x4C, 0x18, 0x14, 0x01, 0x06, 0x00, 0x21, 0x80, 0x08,
0x40, 0x01, 0x10, 0x00, 0x44, 0x00, 0x11, 0x00, 0x04, 0x40, 0x01, 0x18,
0x00, 0x86, 0x00, 0x21, 0xC0, 0x10, 0x5C, 0x18, 0xF1, 0xF8, 0x00, 0x07,
0xE4, 0x30, 0x78, 0x80, 0x32, 0x00, 0x24, 0x00, 0x50, 0x00, 0x20, 0x00,
0x40, 0x00, 0x80, 0x01, 0x00, 0x03, 0x00, 0x02, 0x00, 0x12, 0x00, 0xC3,
0x07, 0x01, 0xF8, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x80, 0x00, 0x20, 0x00,
0x08, 0x00, 0x02, 0x00, 0x00, 0x80, 0x7C, 0x20, 0x60, 0xC8, 0x20, 0x0A,
0x10, 0x01, 0x84, 0x00, 0x62, 0x00, 0x08, 0x80, 0x02, 0x20, 0x00, 0x88,
0x00, 0x22, 0x00, 0x08, 0xC0, 0x06, 0x10, 0x01, 0x82, 0x00, 0xE0, 0x60,
0xE8, 0x0F, 0xE3, 0xC0, 0x07, 0xE0, 0x1C, 0x18, 0x30, 0x0C, 0x60, 0x06,
0x40, 0x03, 0xC0, 0x03, 0xC0, 0x01, 0xFF, 0xFF, 0xC0, 0x00, 0xC0, 0x00,
0x40, 0x00, 0x60, 0x00, 0x30, 0x03, 0x0C, 0x0E, 0x03, 0xF0, 0x03, 0xFC,
0x18, 0x00, 0x80, 0x02, 0x00, 0x08, 0x00, 0x20, 0x0F, 0xFF, 0x82, 0x00,
0x08, 0x00, 0x20, 0x00, 0x80, 0x02, 0x00, 0x08, 0x00, 0x20, 0x00, 0x80,
0x02, 0x00, 0x08, 0x00, 0x20, 0x00, 0x80, 0x02, 0x00, 0xFF, 0xF0, 0x0F,
0xC7, 0x9C, 0x3A, 0x18, 0x07, 0x08, 0x01, 0x8C, 0x00, 0xC4, 0x00, 0x22,
0x00, 0x11, 0x00, 0x08, 0x80, 0x04, 0x40, 0x02, 0x10, 0x03, 0x08, 0x01,
0x82, 0x01, 0x40, 0xC3, 0x20, 0x3F, 0x10, 0x00, 0x08, 0x00, 0x04, 0x00,
0x02, 0x00, 0x01, 0x00, 0x01, 0x00, 0x01, 0x00, 0x7F, 0x00, 0xF0, 0x00,
0x08, 0x00, 0x04, 0x00, 0x02, 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, 0x47,
0xC0, 0x2C, 0x18, 0x1C, 0x04, 0x0C, 0x01, 0x04, 0x00, 0x82, 0x00, 0x41,
0x00, 0x20, 0x80, 0x10, 0x40, 0x08, 0x20, 0x04, 0x10, 0x02, 0x08, 0x01,
0x04, 0x00, 0x82, 0x00, 0x47, 0xC0, 0xF8, 0x06, 0x00, 0x18, 0x00, 0x60,
0x01, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1F, 0x80, 0x02, 0x00, 0x08,
0x00, 0x20, 0x00, 0x80, 0x02, 0x00, 0x08, 0x00, 0x20, 0x00, 0x80, 0x02,
0x00, 0x08, 0x00, 0x20, 0x00, 0x80, 0x02, 0x03, 0xFF, 0xF0, 0x03, 0x00,
0xC0, 0x30, 0x0C, 0x00, 0x00, 0x00, 0x03, 0xFF, 0x00, 0x40, 0x10, 0x04,
0x01, 0x00, 0x40, 0x10, 0x04, 0x01, 0x00, 0x40, 0x10, 0x04, 0x01, 0x00,
0x40, 0x10, 0x04, 0x01, 0x00, 0x40, 0x10, 0x08, 0x06, 0xFE, 0x00, 0xF0,
0x00, 0x10, 0x00, 0x10, 0x00, 0x10, 0x00, 0x10, 0x00, 0x10, 0x00, 0x10,
0xFE, 0x10, 0x30, 0x10, 0xE0, 0x11, 0xC0, 0x13, 0x00, 0x16, 0x00, 0x1E,
0x00, 0x1B, 0x00, 0x11, 0x80, 0x10, 0xC0, 0x10, 0x60, 0x10, 0x30, 0x10,
0x18, 0x10, 0x1C, 0xF0, 0x3F, 0x7E, 0x00, 0x08, 0x00, 0x20, 0x00, 0x80,
0x02, 0x00, 0x08, 0x00, 0x20, 0x00, 0x80, 0x02, 0x00, 0x08, 0x00, 0x20,
0x00, 0x80, 0x02, 0x00, 0x08, 0x00, 0x20, 0x00, 0x80, 0x02, 0x00, 0x08,
0x00, 0x20, 0x00, 0x80, 0xFF, 0xFC, 0xEF, 0x9E, 0x07, 0x1E, 0x20, 0xC1,
0x82, 0x10, 0x20, 0x42, 0x04, 0x08, 0x40, 0x81, 0x08, 0x10, 0x21, 0x02,
0x04, 0x20, 0x40, 0x84, 0x08, 0x10, 0x81, 0x02, 0x10, 0x20, 0x42, 0x04,
0x08, 0x40, 0x81, 0x3E, 0x1C, 0x38, 0x71, 0xF0, 0x0B, 0x06, 0x07, 0x01,
0x03, 0x00, 0x41, 0x00, 0x20, 0x80, 0x10, 0x40, 0x08, 0x20, 0x04, 0x10,
0x02, 0x08, 0x01, 0x04, 0x00, 0x82, 0x00, 0x41, 0x00, 0x20, 0x80, 0x13,
0xF0, 0x3E, 0x07, 0xC0, 0x30, 0x60, 0x80, 0x22, 0x00, 0x24, 0x00, 0x50,
0x00, 0x60, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, 0x05, 0x00, 0x12, 0x00,
0x22, 0x00, 0x83, 0x06, 0x01, 0xF0, 0x00, 0xF1, 0xFC, 0x05, 0xC1, 0x81,
0xC0, 0x10, 0x60, 0x02, 0x18, 0x00, 0xC4, 0x00, 0x11, 0x00, 0x04, 0x40,
0x01, 0x10, 0x00, 0x44, 0x00, 0x11, 0x80, 0x08, 0x60, 0x02, 0x14, 0x01,
0x04, 0xC1, 0x81, 0x0F, 0x80, 0x40, 0x00, 0x10, 0x00, 0x04, 0x00, 0x01,
0x00, 0x00, 0x40, 0x00, 0x10, 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xE3, 0xC6,
0x0E, 0x86, 0x00, 0xE1, 0x00, 0x18, 0xC0, 0x06, 0x20, 0x00, 0x88, 0x00,
0x22, 0x00, 0x08, 0x80, 0x02, 0x20, 0x00, 0x84, 0x00, 0x61, 0x00, 0x18,
0x20, 0x0A, 0x06, 0x0C, 0x80, 0x7C, 0x20, 0x00, 0x08, 0x00, 0x02, 0x00,
0x00, 0x80, 0x00, 0x20, 0x00, 0x08, 0x00, 0x02, 0x00, 0x0F, 0xF0, 0xF8,
0x7C, 0x11, 0x8C, 0x2C, 0x00, 0x70, 0x00, 0xC0, 0x01, 0x00, 0x02, 0x00,
0x04, 0x00, 0x08, 0x00, 0x10, 0x00, 0x20, 0x00, 0x40, 0x00, 0x80, 0x01,
0x00, 0x3F, 0xFC, 0x00, 0x0F, 0xD1, 0x83, 0x98, 0x04, 0x80, 0x24, 0x00,
0x30, 0x00, 0xF0, 0x00, 0xFC, 0x00, 0x30, 0x00, 0xE0, 0x03, 0x00, 0x1C,
0x01, 0xF0, 0x1A, 0x7F, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08,
0x00, 0x08, 0x00, 0xFF, 0xFC, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08,
0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08,
0x00, 0x08, 0x00, 0x08, 0x01, 0x06, 0x0F, 0x03, 0xF8, 0xF0, 0x3E, 0x08,
0x01, 0x04, 0x00, 0x82, 0x00, 0x41, 0x00, 0x20, 0x80, 0x10, 0x40, 0x08,
0x20, 0x04, 0x10, 0x02, 0x08, 0x01, 0x04, 0x00, 0x82, 0x00, 0x41, 0x00,
0xE0, 0x41, 0xD0, 0x1F, 0x8E, 0xFE, 0x0F, 0xE2, 0x00, 0x20, 0x60, 0x0C,
0x0C, 0x01, 0x80, 0x80, 0x20, 0x18, 0x0C, 0x01, 0x01, 0x00, 0x30, 0x60,
0x02, 0x08, 0x00, 0x41, 0x00, 0x0C, 0x60, 0x00, 0x88, 0x00, 0x19, 0x00,
0x01, 0x40, 0x00, 0x38, 0x00, 0xFC, 0x07, 0xE4, 0x00, 0x10, 0x80, 0x02,
0x18, 0x20, 0xC3, 0x0E, 0x18, 0x21, 0x42, 0x04, 0x28, 0x40, 0x8D, 0x88,
0x19, 0x93, 0x03, 0x22, 0x60, 0x2C, 0x68, 0x05, 0x85, 0x00, 0xA0, 0xA0,
0x1C, 0x1C, 0x01, 0x81, 0x80, 0x7C, 0x1F, 0x18, 0x03, 0x06, 0x03, 0x01,
0x83, 0x00, 0x63, 0x00, 0x1B, 0x00, 0x07, 0x00, 0x03, 0x80, 0x03, 0x60,
0x03, 0x18, 0x03, 0x06, 0x03, 0x01, 0x83, 0x00, 0x61, 0x00, 0x33, 0xF0,
0x7E, 0xFC, 0x1F, 0x90, 0x01, 0x8C, 0x00, 0x86, 0x00, 0xC1, 0x80, 0x40,
0xC0, 0x60, 0x20, 0x20, 0x18, 0x30, 0x04, 0x10, 0x03, 0x08, 0x00, 0x8C,
0x00, 0x64, 0x00, 0x16, 0x00, 0x0E, 0x00, 0x07, 0x00, 0x01, 0x00, 0x01,
0x80, 0x00, 0x80, 0x00, 0xC0, 0x00, 0x60, 0x00, 0x20, 0x07, 0xFE, 0x00,
0xFF, 0xF4, 0x01, 0x20, 0x09, 0x00, 0x80, 0x08, 0x00, 0x80, 0x08, 0x00,
0xC0, 0x04, 0x00, 0x40, 0x04, 0x00, 0x40, 0x14, 0x00, 0xA0, 0x07, 0xFF,
0xE0, 0x07, 0x0C, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08,
0x30, 0xC0, 0x30, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08,
0x0C, 0x07, 0xFF, 0xFF, 0xFF, 0x80, 0xE0, 0x30, 0x10, 0x10, 0x10, 0x10,
0x10, 0x10, 0x10, 0x10, 0x10, 0x08, 0x07, 0x0C, 0x10, 0x10, 0x10, 0x10,
0x10, 0x10, 0x10, 0x10, 0x10, 0x30, 0xE0, 0x1C, 0x00, 0x44, 0x0D, 0x84,
0x36, 0x04, 0x40, 0x07, 0x00 };
const GFXglyph FreeMono18pt7bGlyphs[] PROGMEM = {
{ 0, 0, 0, 21, 0, 1 }, // 0x20 ' '
{ 0, 4, 22, 21, 8, -21 }, // 0x21 '!'
{ 11, 11, 10, 21, 5, -20 }, // 0x22 '"'
{ 25, 14, 24, 21, 3, -21 }, // 0x23 '#'
{ 67, 13, 26, 21, 4, -22 }, // 0x24 '$'
{ 110, 15, 21, 21, 3, -20 }, // 0x25 '%'
{ 150, 12, 18, 21, 4, -17 }, // 0x26 '&'
{ 177, 4, 10, 21, 8, -20 }, // 0x27 '''
{ 182, 5, 25, 21, 10, -20 }, // 0x28 '('
{ 198, 5, 25, 21, 6, -20 }, // 0x29 ')'
{ 214, 13, 12, 21, 4, -20 }, // 0x2A '*'
{ 234, 15, 17, 21, 3, -17 }, // 0x2B '+'
{ 266, 7, 10, 21, 5, -4 }, // 0x2C ','
{ 275, 15, 1, 21, 3, -9 }, // 0x2D '-'
{ 277, 5, 5, 21, 8, -4 }, // 0x2E '.'
{ 281, 13, 26, 21, 4, -22 }, // 0x2F '/'
{ 324, 13, 21, 21, 4, -20 }, // 0x30 '0'
{ 359, 13, 21, 21, 4, -20 }, // 0x31 '1'
{ 394, 13, 21, 21, 3, -20 }, // 0x32 '2'
{ 429, 14, 21, 21, 3, -20 }, // 0x33 '3'
{ 466, 12, 21, 21, 4, -20 }, // 0x34 '4'
{ 498, 14, 21, 21, 3, -20 }, // 0x35 '5'
{ 535, 12, 21, 21, 5, -20 }, // 0x36 '6'
{ 567, 12, 21, 21, 4, -20 }, // 0x37 '7'
{ 599, 13, 21, 21, 4, -20 }, // 0x38 '8'
{ 634, 12, 21, 21, 5, -20 }, // 0x39 '9'
{ 666, 5, 15, 21, 8, -14 }, // 0x3A ':'
{ 676, 7, 20, 21, 5, -14 }, // 0x3B ';'
{ 694, 15, 16, 21, 3, -17 }, // 0x3C '<'
{ 724, 17, 6, 21, 2, -12 }, // 0x3D '='
{ 737, 15, 16, 21, 3, -17 }, // 0x3E '>'
{ 767, 12, 20, 21, 5, -19 }, // 0x3F '?'
{ 797, 13, 23, 21, 4, -20 }, // 0x40 '@'
{ 835, 21, 20, 21, 0, -19 }, // 0x41 'A'
{ 888, 18, 20, 21, 1, -19 }, // 0x42 'B'
{ 933, 17, 20, 21, 2, -19 }, // 0x43 'C'
{ 976, 16, 20, 21, 2, -19 }, // 0x44 'D'
{ 1016, 17, 20, 21, 1, -19 }, // 0x45 'E'
{ 1059, 17, 20, 21, 1, -19 }, // 0x46 'F'
{ 1102, 17, 20, 21, 2, -19 }, // 0x47 'G'
{ 1145, 16, 20, 21, 2, -19 }, // 0x48 'H'
{ 1185, 13, 20, 21, 4, -19 }, // 0x49 'I'
{ 1218, 17, 20, 21, 3, -19 }, // 0x4A 'J'
{ 1261, 18, 20, 21, 1, -19 }, // 0x4B 'K'
{ 1306, 15, 20, 21, 3, -19 }, // 0x4C 'L'
{ 1344, 19, 20, 21, 1, -19 }, // 0x4D 'M'
{ 1392, 18, 20, 21, 1, -19 }, // 0x4E 'N'
{ 1437, 17, 20, 21, 2, -19 }, // 0x4F 'O'
{ 1480, 16, 20, 21, 1, -19 }, // 0x50 'P'
{ 1520, 17, 24, 21, 2, -19 }, // 0x51 'Q'
{ 1571, 19, 20, 21, 1, -19 }, // 0x52 'R'
{ 1619, 14, 20, 21, 3, -19 }, // 0x53 'S'
{ 1654, 15, 20, 21, 3, -19 }, // 0x54 'T'
{ 1692, 17, 20, 21, 2, -19 }, // 0x55 'U'
{ 1735, 21, 20, 21, 0, -19 }, // 0x56 'V'
{ 1788, 19, 20, 21, 1, -19 }, // 0x57 'W'
{ 1836, 19, 20, 21, 1, -19 }, // 0x58 'X'
{ 1884, 17, 20, 21, 2, -19 }, // 0x59 'Y'
{ 1927, 13, 20, 21, 4, -19 }, // 0x5A 'Z'
{ 1960, 5, 25, 21, 10, -20 }, // 0x5B '['
{ 1976, 13, 26, 21, 4, -22 }, // 0x5C '\'
{ 2019, 5, 25, 21, 6, -20 }, // 0x5D ']'
{ 2035, 13, 9, 21, 4, -20 }, // 0x5E '^'
{ 2050, 21, 1, 21, 0, 4 }, // 0x5F '_'
{ 2053, 6, 5, 21, 5, -21 }, // 0x60 '`'
{ 2057, 16, 15, 21, 3, -14 }, // 0x61 'a'
{ 2087, 18, 21, 21, 1, -20 }, // 0x62 'b'
{ 2135, 15, 15, 21, 3, -14 }, // 0x63 'c'
{ 2164, 18, 21, 21, 2, -20 }, // 0x64 'd'
{ 2212, 16, 15, 21, 2, -14 }, // 0x65 'e'
{ 2242, 14, 21, 21, 4, -20 }, // 0x66 'f'
{ 2279, 17, 22, 21, 2, -14 }, // 0x67 'g'
{ 2326, 17, 21, 21, 1, -20 }, // 0x68 'h'
{ 2371, 14, 22, 21, 4, -21 }, // 0x69 'i'
{ 2410, 10, 29, 21, 5, -21 }, // 0x6A 'j'
{ 2447, 16, 21, 21, 2, -20 }, // 0x6B 'k'
{ 2489, 14, 21, 21, 4, -20 }, // 0x6C 'l'
{ 2526, 19, 15, 21, 1, -14 }, // 0x6D 'm'
{ 2562, 17, 15, 21, 1, -14 }, // 0x6E 'n'
{ 2594, 15, 15, 21, 3, -14 }, // 0x6F 'o'
{ 2623, 18, 22, 21, 1, -14 }, // 0x70 'p'
{ 2673, 18, 22, 21, 2, -14 }, // 0x71 'q'
{ 2723, 15, 15, 21, 3, -14 }, // 0x72 'r'
{ 2752, 13, 15, 21, 4, -14 }, // 0x73 's'
{ 2777, 16, 20, 21, 1, -19 }, // 0x74 't'
{ 2817, 17, 15, 21, 1, -14 }, // 0x75 'u'
{ 2849, 19, 15, 21, 1, -14 }, // 0x76 'v'
{ 2885, 19, 15, 21, 1, -14 }, // 0x77 'w'
{ 2921, 17, 15, 21, 2, -14 }, // 0x78 'x'
{ 2953, 17, 22, 21, 2, -14 }, // 0x79 'y'
{ 3000, 13, 15, 21, 4, -14 }, // 0x7A 'z'
{ 3025, 8, 25, 21, 6, -20 }, // 0x7B '{'
{ 3050, 1, 25, 21, 10, -20 }, // 0x7C '|'
{ 3054, 8, 25, 21, 7, -20 }, // 0x7D '}'
{ 3079, 15, 5, 21, 3, -11 } }; // 0x7E '~'
const GFXfont FreeMono18pt7b PROGMEM = {
(uint8_t *)FreeMono18pt7bBitmaps,
(GFXglyph *)FreeMono18pt7bGlyphs,
0x20, 0x7E, 35 };
// Approx. 3761 bytes

View File

@ -0,0 +1,577 @@
const uint8_t FreeMono24pt7bBitmaps[] PROGMEM = {
0x73, 0x9C, 0xE7, 0x39, 0xCE, 0x73, 0x9C, 0xE7, 0x10, 0x84, 0x21, 0x08,
0x00, 0x00, 0x00, 0x03, 0xBF, 0xFF, 0xB8, 0xFE, 0x7F, 0x7C, 0x3E, 0x7C,
0x3E, 0x7C, 0x3E, 0x7C, 0x3E, 0x7C, 0x3E, 0x7C, 0x3E, 0x7C, 0x3E, 0x3C,
0x3E, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x01,
0x86, 0x00, 0x30, 0xC0, 0x06, 0x18, 0x00, 0xC3, 0x00, 0x18, 0x60, 0x03,
0x0C, 0x00, 0x61, 0x80, 0x0C, 0x70, 0x01, 0x8C, 0x00, 0x61, 0x80, 0x0C,
0x30, 0x3F, 0xFF, 0xF7, 0xFF, 0xFE, 0x06, 0x18, 0x00, 0xC3, 0x00, 0x18,
0x60, 0x03, 0x0C, 0x00, 0x61, 0x80, 0x0C, 0x30, 0x7F, 0xFF, 0xEF, 0xFF,
0xFC, 0x06, 0x18, 0x00, 0xC7, 0x00, 0x38, 0xC0, 0x06, 0x18, 0x00, 0xC3,
0x00, 0x18, 0x60, 0x03, 0x0C, 0x00, 0x61, 0x80, 0x0C, 0x30, 0x01, 0x86,
0x00, 0x30, 0xC0, 0x00, 0xC0, 0x00, 0x30, 0x00, 0x0C, 0x00, 0x0F, 0xC0,
0x0F, 0xFD, 0x87, 0x03, 0xE3, 0x80, 0x39, 0xC0, 0x06, 0x60, 0x01, 0x98,
0x00, 0x06, 0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x07, 0xC0, 0x00, 0x7F,
0x80, 0x03, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0x60, 0x00, 0x1C, 0x00, 0x03,
0x80, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x1F, 0x80, 0x0E, 0xFC, 0x0F, 0x37,
0xFF, 0x80, 0x7F, 0x80, 0x03, 0x00, 0x00, 0xC0, 0x00, 0x30, 0x00, 0x0C,
0x00, 0x03, 0x00, 0x00, 0xC0, 0x00, 0x07, 0x80, 0x01, 0xFE, 0x00, 0x38,
0x70, 0x03, 0x03, 0x00, 0x60, 0x18, 0x06, 0x01, 0x80, 0x60, 0x18, 0x06,
0x01, 0x80, 0x30, 0x30, 0x03, 0x87, 0x00, 0x1F, 0xE0, 0x30, 0x78, 0x1F,
0x00, 0x1F, 0x80, 0x0F, 0xC0, 0x07, 0xE0, 0x03, 0xF0, 0x00, 0xF8, 0x00,
0x0C, 0x01, 0xE0, 0x00, 0x7F, 0x80, 0x0E, 0x1C, 0x00, 0xC0, 0xC0, 0x18,
0x06, 0x01, 0x80, 0x60, 0x18, 0x06, 0x01, 0x80, 0x60, 0x0C, 0x0E, 0x00,
0xE1, 0xC0, 0x07, 0xF8, 0x00, 0x1E, 0x00, 0x03, 0xEC, 0x01, 0xFF, 0x00,
0xE1, 0x00, 0x70, 0x00, 0x18, 0x00, 0x06, 0x00, 0x01, 0x80, 0x00, 0x30,
0x00, 0x0C, 0x00, 0x01, 0x80, 0x00, 0x60, 0x00, 0x7C, 0x00, 0x3B, 0x83,
0xD8, 0x60, 0xFE, 0x0C, 0x33, 0x03, 0x98, 0xC0, 0x66, 0x30, 0x0D, 0x8C,
0x03, 0xC3, 0x00, 0x70, 0x60, 0x1C, 0x1C, 0x0F, 0x03, 0x87, 0x7C, 0x7F,
0x9F, 0x07, 0x80, 0x00, 0xFE, 0xF9, 0xF3, 0xE7, 0xCF, 0x9F, 0x3E, 0x3C,
0x70, 0xE1, 0xC3, 0x87, 0x00, 0x06, 0x1C, 0x30, 0xE1, 0x87, 0x0E, 0x18,
0x70, 0xE1, 0xC3, 0x0E, 0x1C, 0x38, 0x70, 0xE1, 0xC3, 0x87, 0x0E, 0x0C,
0x1C, 0x38, 0x70, 0x60, 0xE1, 0xC1, 0x83, 0x83, 0x06, 0x06, 0x04, 0xC1,
0xC1, 0x83, 0x83, 0x07, 0x0E, 0x0C, 0x1C, 0x38, 0x70, 0xE0, 0xE1, 0xC3,
0x87, 0x0E, 0x1C, 0x38, 0x70, 0xE1, 0x87, 0x0E, 0x1C, 0x30, 0x61, 0xC3,
0x0E, 0x18, 0x70, 0xC1, 0x00, 0x00, 0xC0, 0x00, 0x30, 0x00, 0x0C, 0x00,
0x03, 0x00, 0x00, 0xC0, 0x10, 0x30, 0x3F, 0x8C, 0x7C, 0xFF, 0xFC, 0x07,
0xF8, 0x00, 0x78, 0x00, 0x1F, 0x00, 0x0C, 0xC0, 0x06, 0x18, 0x03, 0x87,
0x00, 0xC0, 0xC0, 0x60, 0x18, 0x00, 0x60, 0x00, 0x06, 0x00, 0x00, 0x60,
0x00, 0x06, 0x00, 0x00, 0x60, 0x00, 0x06, 0x00, 0x00, 0x60, 0x00, 0x06,
0x00, 0x00, 0x60, 0x00, 0x06, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00,
0x60, 0x00, 0x06, 0x00, 0x00, 0x60, 0x00, 0x06, 0x00, 0x00, 0x60, 0x00,
0x06, 0x00, 0x00, 0x60, 0x00, 0x06, 0x00, 0x00, 0x60, 0x00, 0x06, 0x00,
0x1F, 0x8F, 0x87, 0xC7, 0xC3, 0xE1, 0xE1, 0xF0, 0xF0, 0x78, 0x38, 0x3C,
0x1C, 0x0E, 0x06, 0x00, 0x7F, 0xFF, 0xFD, 0xFF, 0xFF, 0xF0, 0x7D, 0xFF,
0xFF, 0xFF, 0xEF, 0x80, 0x00, 0x00, 0xC0, 0x00, 0x70, 0x00, 0x18, 0x00,
0x06, 0x00, 0x03, 0x00, 0x00, 0xC0, 0x00, 0x60, 0x00, 0x18, 0x00, 0x0C,
0x00, 0x03, 0x00, 0x01, 0x80, 0x00, 0x60, 0x00, 0x30, 0x00, 0x0C, 0x00,
0x06, 0x00, 0x01, 0x80, 0x00, 0xC0, 0x00, 0x30, 0x00, 0x18, 0x00, 0x06,
0x00, 0x03, 0x80, 0x00, 0xC0, 0x00, 0x70, 0x00, 0x18, 0x00, 0x0E, 0x00,
0x03, 0x00, 0x01, 0xC0, 0x00, 0x60, 0x00, 0x38, 0x00, 0x0C, 0x00, 0x07,
0x00, 0x01, 0x80, 0x00, 0x60, 0x00, 0x30, 0x00, 0x0C, 0x00, 0x00, 0x03,
0xF0, 0x03, 0xFF, 0x01, 0xE1, 0xE0, 0xE0, 0x18, 0x30, 0x03, 0x1C, 0x00,
0xE6, 0x00, 0x19, 0x80, 0x06, 0xE0, 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x0F,
0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0,
0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF8, 0x00,
0x76, 0x00, 0x19, 0x80, 0x06, 0x70, 0x03, 0x8C, 0x00, 0xC3, 0x80, 0x60,
0x78, 0x78, 0x0F, 0xFC, 0x00, 0xFC, 0x00, 0x03, 0x80, 0x07, 0x80, 0x0F,
0x80, 0x1D, 0x80, 0x39, 0x80, 0x71, 0x80, 0xE1, 0x80, 0xC1, 0x80, 0x01,
0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01,
0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01,
0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01,
0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xF0, 0x03, 0xFF, 0x01, 0xC0, 0xE0,
0xC0, 0x1C, 0x60, 0x03, 0xB8, 0x00, 0x6C, 0x00, 0x0F, 0x00, 0x03, 0x00,
0x00, 0xC0, 0x00, 0x30, 0x00, 0x18, 0x00, 0x06, 0x00, 0x03, 0x00, 0x01,
0x80, 0x00, 0xC0, 0x00, 0x60, 0x00, 0x30, 0x00, 0x18, 0x00, 0x0C, 0x00,
0x06, 0x00, 0x03, 0x00, 0x01, 0x80, 0x00, 0xC0, 0x00, 0x60, 0x00, 0x30,
0x00, 0xD0, 0x00, 0x38, 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x03,
0xF8, 0x01, 0xFF, 0xC0, 0x70, 0x3C, 0x18, 0x01, 0xC6, 0x00, 0x18, 0x00,
0x01, 0x80, 0x00, 0x30, 0x00, 0x06, 0x00, 0x00, 0xC0, 0x00, 0x18, 0x00,
0x06, 0x00, 0x01, 0xC0, 0x00, 0x70, 0x01, 0xFC, 0x00, 0x3F, 0x00, 0x00,
0x78, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x03, 0x00, 0x00, 0x30, 0x00,
0x06, 0x00, 0x00, 0xC0, 0x00, 0x18, 0x00, 0x03, 0x00, 0x00, 0xD8, 0x00,
0x3B, 0x80, 0x0E, 0x3E, 0x07, 0x81, 0xFF, 0xE0, 0x07, 0xE0, 0x00, 0x00,
0x3C, 0x00, 0x7C, 0x00, 0x6C, 0x00, 0xCC, 0x00, 0x8C, 0x01, 0x8C, 0x03,
0x0C, 0x03, 0x0C, 0x06, 0x0C, 0x04, 0x0C, 0x0C, 0x0C, 0x08, 0x0C, 0x10,
0x0C, 0x30, 0x0C, 0x20, 0x0C, 0x60, 0x0C, 0x40, 0x0C, 0x80, 0x0C, 0xFF,
0xFF, 0xFF, 0xFF, 0x00, 0x0C, 0x00, 0x0C, 0x00, 0x0C, 0x00, 0x0C, 0x00,
0x0C, 0x00, 0x0C, 0x00, 0xFF, 0x00, 0xFF, 0x3F, 0xFF, 0x07, 0xFF, 0xE0,
0xC0, 0x00, 0x18, 0x00, 0x03, 0x00, 0x00, 0x60, 0x00, 0x0C, 0x00, 0x01,
0x80, 0x00, 0x30, 0x00, 0x06, 0x00, 0x00, 0xC7, 0xE0, 0x1F, 0xFF, 0x03,
0x80, 0x70, 0x00, 0x03, 0x00, 0x00, 0x30, 0x00, 0x06, 0x00, 0x00, 0x60,
0x00, 0x0C, 0x00, 0x01, 0x80, 0x00, 0x30, 0x00, 0x06, 0x00, 0x00, 0xC0,
0x00, 0x30, 0x00, 0x06, 0xC0, 0x01, 0xDC, 0x00, 0x71, 0xF0, 0x3C, 0x0F,
0xFF, 0x00, 0x3F, 0x00, 0x00, 0x3F, 0x80, 0x3F, 0xF0, 0x3E, 0x00, 0x1E,
0x00, 0x0E, 0x00, 0x07, 0x00, 0x03, 0x80, 0x00, 0xC0, 0x00, 0x70, 0x00,
0x18, 0x00, 0x06, 0x00, 0x03, 0x80, 0x00, 0xC1, 0xF8, 0x31, 0xFF, 0x0C,
0xF0, 0xF3, 0x70, 0x0C, 0xD8, 0x01, 0xBC, 0x00, 0x6E, 0x00, 0x0F, 0x80,
0x03, 0xC0, 0x00, 0xD8, 0x00, 0x36, 0x00, 0x0D, 0x80, 0x03, 0x30, 0x01,
0x8E, 0x00, 0x61, 0xC0, 0x30, 0x38, 0x38, 0x07, 0xFC, 0x00, 0x7C, 0x00,
0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x01, 0xC0,
0x00, 0x60, 0x00, 0x18, 0x00, 0x0E, 0x00, 0x03, 0x00, 0x00, 0xC0, 0x00,
0x30, 0x00, 0x18, 0x00, 0x06, 0x00, 0x01, 0x80, 0x00, 0xC0, 0x00, 0x30,
0x00, 0x0C, 0x00, 0x06, 0x00, 0x01, 0x80, 0x00, 0x60, 0x00, 0x30, 0x00,
0x0C, 0x00, 0x03, 0x00, 0x01, 0x80, 0x00, 0x60, 0x00, 0x18, 0x00, 0x0C,
0x00, 0x03, 0x00, 0x03, 0xF0, 0x03, 0xFF, 0x03, 0xC0, 0xF1, 0xC0, 0x0E,
0x60, 0x01, 0xB8, 0x00, 0x7C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0,
0x00, 0x36, 0x00, 0x18, 0xC0, 0x0C, 0x1C, 0x0E, 0x03, 0xFF, 0x00, 0xFF,
0xC0, 0x70, 0x38, 0x30, 0x03, 0x18, 0x00, 0x66, 0x00, 0x1B, 0x00, 0x03,
0xC0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0x60, 0x01, 0x98,
0x00, 0xE3, 0x00, 0x70, 0x70, 0x38, 0x0F, 0xFC, 0x00, 0xFC, 0x00, 0x07,
0xE0, 0x03, 0xFE, 0x01, 0xC1, 0xC0, 0xC0, 0x38, 0x60, 0x07, 0x18, 0x00,
0xCC, 0x00, 0x1B, 0x00, 0x06, 0xC0, 0x01, 0xB0, 0x00, 0x3C, 0x00, 0x1F,
0x00, 0x07, 0x60, 0x03, 0xD8, 0x01, 0xB3, 0x00, 0xCC, 0xF0, 0xF3, 0x0F,
0xF8, 0xC1, 0xF8, 0x30, 0x00, 0x1C, 0x00, 0x06, 0x00, 0x01, 0x80, 0x00,
0xE0, 0x00, 0x30, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x07, 0x00, 0x07, 0x80,
0x07, 0xC0, 0xFF, 0xC0, 0x1F, 0xC0, 0x00, 0x7D, 0xFF, 0xFF, 0xFF, 0xEF,
0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3E, 0xFF, 0xFF, 0xFF,
0xF7, 0xC0, 0x0F, 0x87, 0xF1, 0xFC, 0x7F, 0x1F, 0xC3, 0xE0, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xF1, 0xF8, 0x7C, 0x3F, 0x0F,
0x83, 0xE0, 0xF0, 0x7C, 0x1E, 0x07, 0x81, 0xC0, 0xF0, 0x38, 0x04, 0x00,
0x00, 0x00, 0x18, 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00,
0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x00,
0x00, 0x78, 0x00, 0x07, 0x80, 0x00, 0x0F, 0x00, 0x00, 0x1E, 0x00, 0x00,
0x1E, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x1E, 0x00, 0x00,
0x3C, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x38, 0x00, 0x00,
0x20, 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF,
0xFF, 0x7F, 0xFF, 0xFF, 0xC0, 0x00, 0x07, 0x80, 0x00, 0x0F, 0x00, 0x00,
0x1E, 0x00, 0x00, 0x38, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, 0x03,
0xC0, 0x00, 0x07, 0x80, 0x00, 0x0E, 0x00, 0x00, 0x3C, 0x00, 0x01, 0xE0,
0x00, 0x3C, 0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x01, 0xE0,
0x00, 0x3C, 0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x0E, 0x00, 0x00, 0x60,
0x00, 0x00, 0x07, 0xF0, 0x1F, 0xFE, 0x3E, 0x07, 0x98, 0x00, 0xEC, 0x00,
0x36, 0x00, 0x0F, 0x00, 0x06, 0x00, 0x03, 0x00, 0x01, 0x80, 0x01, 0xC0,
0x00, 0xC0, 0x01, 0xC0, 0x03, 0xC0, 0x07, 0xC0, 0x07, 0x00, 0x03, 0x00,
0x01, 0x80, 0x00, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x07, 0x80, 0x07, 0xE0, 0x03, 0xF0, 0x01, 0xF8, 0x00,
0x78, 0x00, 0x03, 0xF0, 0x03, 0xFF, 0x01, 0xE0, 0xE0, 0xE0, 0x1C, 0x30,
0x03, 0x1C, 0x00, 0x66, 0x00, 0x19, 0x80, 0x06, 0xC0, 0x01, 0xB0, 0x07,
0xEC, 0x07, 0xFB, 0x03, 0xC6, 0xC1, 0xC1, 0xB0, 0xE0, 0x6C, 0x30, 0x1B,
0x0C, 0x06, 0xC3, 0x01, 0xB0, 0xC0, 0x6C, 0x18, 0x1B, 0x07, 0x86, 0xC0,
0xFF, 0xF0, 0x0F, 0xFC, 0x00, 0x03, 0x00, 0x00, 0x60, 0x00, 0x18, 0x00,
0x07, 0x00, 0x00, 0xC0, 0x00, 0x38, 0x00, 0x07, 0x80, 0xC0, 0xFF, 0xF0,
0x0F, 0xE0, 0x07, 0xFF, 0x00, 0x00, 0x7F, 0xF0, 0x00, 0x00, 0x1B, 0x00,
0x00, 0x01, 0x98, 0x00, 0x00, 0x11, 0x80, 0x00, 0x03, 0x0C, 0x00, 0x00,
0x30, 0xC0, 0x00, 0x06, 0x0C, 0x00, 0x00, 0x60, 0x60, 0x00, 0x06, 0x06,
0x00, 0x00, 0xC0, 0x30, 0x00, 0x0C, 0x03, 0x00, 0x00, 0x80, 0x30, 0x00,
0x18, 0x01, 0x80, 0x01, 0x80, 0x18, 0x00, 0x3F, 0xFF, 0x80, 0x03, 0xFF,
0xFC, 0x00, 0x20, 0x00, 0xC0, 0x06, 0x00, 0x06, 0x00, 0x60, 0x00, 0x60,
0x0C, 0x00, 0x06, 0x00, 0xC0, 0x00, 0x30, 0x0C, 0x00, 0x03, 0x01, 0x80,
0x00, 0x18, 0x7F, 0xC0, 0x3F, 0xF7, 0xFC, 0x03, 0xFF, 0xFF, 0xFF, 0x03,
0xFF, 0xFF, 0x01, 0x80, 0x0E, 0x06, 0x00, 0x1C, 0x18, 0x00, 0x38, 0x60,
0x00, 0x61, 0x80, 0x01, 0x86, 0x00, 0x06, 0x18, 0x00, 0x38, 0x60, 0x01,
0xC1, 0x80, 0x1E, 0x07, 0xFF, 0xE0, 0x1F, 0xFF, 0xC0, 0x60, 0x03, 0xC1,
0x80, 0x03, 0x86, 0x00, 0x06, 0x18, 0x00, 0x1C, 0x60, 0x00, 0x31, 0x80,
0x00, 0xC6, 0x00, 0x03, 0x18, 0x00, 0x0C, 0x60, 0x00, 0x61, 0x80, 0x03,
0x86, 0x00, 0x1C, 0xFF, 0xFF, 0xE3, 0xFF, 0xFE, 0x00, 0x00, 0xFC, 0x00,
0x0F, 0xFE, 0x60, 0xF0, 0x3D, 0x87, 0x00, 0x3E, 0x38, 0x00, 0x38, 0xC0,
0x00, 0xE7, 0x00, 0x01, 0x98, 0x00, 0x06, 0x60, 0x00, 0x03, 0x00, 0x00,
0x0C, 0x00, 0x00, 0x30, 0x00, 0x00, 0xC0, 0x00, 0x03, 0x00, 0x00, 0x0C,
0x00, 0x00, 0x30, 0x00, 0x00, 0xC0, 0x00, 0x03, 0x00, 0x00, 0x0C, 0x00,
0x00, 0x18, 0x00, 0x00, 0x60, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, 0x00,
0xC7, 0x00, 0x06, 0x0E, 0x00, 0x70, 0x1E, 0x07, 0x80, 0x3F, 0xFC, 0x00,
0x1F, 0x80, 0xFF, 0xFE, 0x03, 0xFF, 0xFE, 0x03, 0x00, 0x3C, 0x0C, 0x00,
0x38, 0x30, 0x00, 0x70, 0xC0, 0x00, 0xC3, 0x00, 0x03, 0x8C, 0x00, 0x06,
0x30, 0x00, 0x1C, 0xC0, 0x00, 0x33, 0x00, 0x00, 0xCC, 0x00, 0x03, 0x30,
0x00, 0x0C, 0xC0, 0x00, 0x33, 0x00, 0x00, 0xCC, 0x00, 0x03, 0x30, 0x00,
0x0C, 0xC0, 0x00, 0x33, 0x00, 0x01, 0x8C, 0x00, 0x06, 0x30, 0x00, 0x30,
0xC0, 0x01, 0xC3, 0x00, 0x0E, 0x0C, 0x00, 0xF0, 0xFF, 0xFF, 0x83, 0xFF,
0xF8, 0x00, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF, 0xE1, 0x80, 0x01, 0x86, 0x00,
0x06, 0x18, 0x00, 0x18, 0x60, 0x00, 0x61, 0x80, 0x01, 0x86, 0x00, 0x00,
0x18, 0x0C, 0x00, 0x60, 0x30, 0x01, 0x80, 0xC0, 0x07, 0xFF, 0x00, 0x1F,
0xFC, 0x00, 0x60, 0x30, 0x01, 0x80, 0xC0, 0x06, 0x03, 0x00, 0x18, 0x00,
0x00, 0x60, 0x00, 0x01, 0x80, 0x00, 0xC6, 0x00, 0x03, 0x18, 0x00, 0x0C,
0x60, 0x00, 0x31, 0x80, 0x00, 0xC6, 0x00, 0x03, 0xFF, 0xFF, 0xFF, 0xFF,
0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF1, 0x80, 0x00, 0xC6, 0x00,
0x03, 0x18, 0x00, 0x0C, 0x60, 0x00, 0x31, 0x80, 0x00, 0xC6, 0x00, 0x00,
0x18, 0x0C, 0x00, 0x60, 0x30, 0x01, 0x80, 0xC0, 0x07, 0xFF, 0x00, 0x1F,
0xFC, 0x00, 0x60, 0x30, 0x01, 0x80, 0xC0, 0x06, 0x03, 0x00, 0x18, 0x00,
0x00, 0x60, 0x00, 0x01, 0x80, 0x00, 0x06, 0x00, 0x00, 0x18, 0x00, 0x00,
0x60, 0x00, 0x01, 0x80, 0x00, 0x06, 0x00, 0x00, 0xFF, 0xF0, 0x03, 0xFF,
0xC0, 0x00, 0x00, 0xFF, 0x00, 0x07, 0xFF, 0x98, 0x1E, 0x03, 0xF0, 0x70,
0x01, 0xE1, 0x80, 0x01, 0xC6, 0x00, 0x01, 0x9C, 0x00, 0x03, 0x30, 0x00,
0x00, 0x60, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x00, 0x00, 0x06, 0x00, 0x00,
0x0C, 0x00, 0x00, 0x18, 0x00, 0x00, 0x30, 0x00, 0x00, 0x60, 0x03, 0xFF,
0xC0, 0x07, 0xFF, 0x80, 0x00, 0x1B, 0x00, 0x00, 0x37, 0x00, 0x00, 0x66,
0x00, 0x00, 0xCC, 0x00, 0x01, 0x8C, 0x00, 0x03, 0x1C, 0x00, 0x06, 0x1E,
0x00, 0x0C, 0x0F, 0x00, 0xF8, 0x0F, 0xFF, 0xC0, 0x03, 0xFC, 0x00, 0x7F,
0x01, 0xFC, 0xFE, 0x03, 0xF8, 0x60, 0x00, 0xC0, 0xC0, 0x01, 0x81, 0x80,
0x03, 0x03, 0x00, 0x06, 0x06, 0x00, 0x0C, 0x0C, 0x00, 0x18, 0x18, 0x00,
0x30, 0x30, 0x00, 0x60, 0x60, 0x00, 0xC0, 0xFF, 0xFF, 0x81, 0xFF, 0xFF,
0x03, 0x00, 0x06, 0x06, 0x00, 0x0C, 0x0C, 0x00, 0x18, 0x18, 0x00, 0x30,
0x30, 0x00, 0x60, 0x60, 0x00, 0xC0, 0xC0, 0x01, 0x81, 0x80, 0x03, 0x03,
0x00, 0x06, 0x06, 0x00, 0x0C, 0x0C, 0x00, 0x18, 0xFF, 0x01, 0xFF, 0xFE,
0x03, 0xFC, 0xFF, 0xFF, 0xFF, 0xFF, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80,
0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80,
0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80,
0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80,
0x01, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0xFF, 0xFE, 0x01, 0xFF, 0xFC,
0x00, 0x03, 0x00, 0x00, 0x06, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x18, 0x00,
0x00, 0x30, 0x00, 0x00, 0x60, 0x00, 0x00, 0xC0, 0x00, 0x01, 0x80, 0x00,
0x03, 0x00, 0x00, 0x06, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x18, 0x00, 0x00,
0x30, 0x60, 0x00, 0x60, 0xC0, 0x00, 0xC1, 0x80, 0x01, 0x83, 0x00, 0x03,
0x06, 0x00, 0x06, 0x0C, 0x00, 0x0C, 0x18, 0x00, 0x30, 0x38, 0x00, 0x60,
0x38, 0x01, 0x80, 0x3C, 0x0E, 0x00, 0x3F, 0xF8, 0x00, 0x0F, 0xC0, 0x00,
0xFF, 0x81, 0xFE, 0xFF, 0x81, 0xFE, 0x18, 0x00, 0x30, 0x18, 0x00, 0xE0,
0x18, 0x01, 0xC0, 0x18, 0x03, 0x80, 0x18, 0x07, 0x00, 0x18, 0x0E, 0x00,
0x18, 0x18, 0x00, 0x18, 0x70, 0x00, 0x18, 0xE0, 0x00, 0x19, 0xE0, 0x00,
0x1B, 0xF8, 0x00, 0x1F, 0x1C, 0x00, 0x1C, 0x06, 0x00, 0x18, 0x03, 0x00,
0x18, 0x03, 0x80, 0x18, 0x01, 0x80, 0x18, 0x00, 0xC0, 0x18, 0x00, 0xC0,
0x18, 0x00, 0x60, 0x18, 0x00, 0x60, 0x18, 0x00, 0x70, 0x18, 0x00, 0x30,
0xFF, 0x80, 0x3F, 0xFF, 0x80, 0x1F, 0xFF, 0xF0, 0x07, 0xFF, 0x80, 0x01,
0x80, 0x00, 0x0C, 0x00, 0x00, 0x60, 0x00, 0x03, 0x00, 0x00, 0x18, 0x00,
0x00, 0xC0, 0x00, 0x06, 0x00, 0x00, 0x30, 0x00, 0x01, 0x80, 0x00, 0x0C,
0x00, 0x00, 0x60, 0x00, 0x03, 0x00, 0x00, 0x18, 0x00, 0x00, 0xC0, 0x00,
0x06, 0x00, 0x18, 0x30, 0x00, 0xC1, 0x80, 0x06, 0x0C, 0x00, 0x30, 0x60,
0x01, 0x83, 0x00, 0x0C, 0x18, 0x00, 0x60, 0xC0, 0x03, 0xFF, 0xFF, 0xFF,
0xFF, 0xFF, 0xC0, 0xFC, 0x00, 0x0F, 0xFF, 0x00, 0x03, 0xF3, 0x60, 0x01,
0xB0, 0xD8, 0x00, 0x6C, 0x33, 0x00, 0x33, 0x0C, 0xC0, 0x0C, 0xC3, 0x38,
0x07, 0x30, 0xC6, 0x01, 0x8C, 0x31, 0xC0, 0xE3, 0x0C, 0x30, 0x30, 0xC3,
0x0C, 0x0C, 0x30, 0xC1, 0x86, 0x0C, 0x30, 0x61, 0x83, 0x0C, 0x0C, 0xC0,
0xC3, 0x03, 0x30, 0x30, 0xC0, 0x78, 0x0C, 0x30, 0x1E, 0x03, 0x0C, 0x03,
0x00, 0xC3, 0x00, 0x00, 0x30, 0xC0, 0x00, 0x0C, 0x30, 0x00, 0x03, 0x0C,
0x00, 0x00, 0xC3, 0x00, 0x00, 0x30, 0xC0, 0x00, 0x0C, 0xFF, 0x00, 0x3F,
0xFF, 0xC0, 0x0F, 0xF0, 0xFC, 0x00, 0xFF, 0xFC, 0x00, 0xFF, 0x1E, 0x00,
0x0C, 0x1F, 0x00, 0x0C, 0x1B, 0x00, 0x0C, 0x19, 0x80, 0x0C, 0x19, 0xC0,
0x0C, 0x18, 0xC0, 0x0C, 0x18, 0x60, 0x0C, 0x18, 0x60, 0x0C, 0x18, 0x30,
0x0C, 0x18, 0x38, 0x0C, 0x18, 0x18, 0x0C, 0x18, 0x0C, 0x0C, 0x18, 0x0E,
0x0C, 0x18, 0x06, 0x0C, 0x18, 0x03, 0x0C, 0x18, 0x03, 0x0C, 0x18, 0x01,
0x8C, 0x18, 0x01, 0xCC, 0x18, 0x00, 0xCC, 0x18, 0x00, 0x6C, 0x18, 0x00,
0x7C, 0x18, 0x00, 0x3C, 0x7F, 0x80, 0x1C, 0x7F, 0x80, 0x1C, 0x00, 0x7E,
0x00, 0x01, 0xFF, 0xC0, 0x07, 0x81, 0xE0, 0x0E, 0x00, 0x70, 0x1C, 0x00,
0x38, 0x38, 0x00, 0x1C, 0x30, 0x00, 0x0C, 0x70, 0x00, 0x0E, 0x60, 0x00,
0x06, 0x60, 0x00, 0x06, 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00,
0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00,
0x03, 0xC0, 0x00, 0x03, 0x60, 0x00, 0x06, 0x60, 0x00, 0x06, 0x70, 0x00,
0x0E, 0x30, 0x00, 0x0C, 0x38, 0x00, 0x1C, 0x1C, 0x00, 0x38, 0x0E, 0x00,
0x70, 0x07, 0x81, 0xE0, 0x03, 0xFF, 0xC0, 0x00, 0x7E, 0x00, 0xFF, 0xFF,
0x07, 0xFF, 0xFE, 0x06, 0x00, 0x78, 0x30, 0x00, 0xE1, 0x80, 0x03, 0x0C,
0x00, 0x0C, 0x60, 0x00, 0x63, 0x00, 0x03, 0x18, 0x00, 0x18, 0xC0, 0x01,
0xC6, 0x00, 0x0C, 0x30, 0x00, 0xC1, 0x80, 0x1E, 0x0F, 0xFF, 0xC0, 0x7F,
0xF8, 0x03, 0x00, 0x00, 0x18, 0x00, 0x00, 0xC0, 0x00, 0x06, 0x00, 0x00,
0x30, 0x00, 0x01, 0x80, 0x00, 0x0C, 0x00, 0x00, 0x60, 0x00, 0x03, 0x00,
0x00, 0xFF, 0xF0, 0x07, 0xFF, 0x80, 0x00, 0x00, 0x7E, 0x00, 0x01, 0xFF,
0x80, 0x07, 0x81, 0xE0, 0x0E, 0x00, 0x70, 0x1C, 0x00, 0x38, 0x38, 0x00,
0x1C, 0x30, 0x00, 0x0C, 0x70, 0x00, 0x0E, 0x60, 0x00, 0x06, 0x60, 0x00,
0x06, 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00,
0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00,
0x03, 0x60, 0x00, 0x06, 0x60, 0x00, 0x06, 0x70, 0x00, 0x0E, 0x30, 0x00,
0x0C, 0x18, 0x00, 0x1C, 0x0C, 0x00, 0x38, 0x06, 0x00, 0x70, 0x03, 0x81,
0xE0, 0x00, 0xFF, 0xC0, 0x00, 0x7E, 0x00, 0x00, 0xE0, 0x00, 0x03, 0xFF,
0x87, 0x07, 0xFF, 0xFE, 0x07, 0x00, 0xF8, 0xFF, 0xFE, 0x00, 0xFF, 0xFF,
0x80, 0x18, 0x03, 0xC0, 0x18, 0x00, 0xE0, 0x18, 0x00, 0x60, 0x18, 0x00,
0x30, 0x18, 0x00, 0x30, 0x18, 0x00, 0x30, 0x18, 0x00, 0x30, 0x18, 0x00,
0x70, 0x18, 0x00, 0x60, 0x18, 0x01, 0xC0, 0x18, 0x07, 0x80, 0x1F, 0xFF,
0x00, 0x1F, 0xFC, 0x00, 0x18, 0x0E, 0x00, 0x18, 0x07, 0x00, 0x18, 0x03,
0x80, 0x18, 0x01, 0xC0, 0x18, 0x00, 0xE0, 0x18, 0x00, 0x60, 0x18, 0x00,
0x30, 0x18, 0x00, 0x30, 0x18, 0x00, 0x18, 0xFF, 0x80, 0x1F, 0xFF, 0x80,
0x0F, 0x03, 0xF8, 0x00, 0xFF, 0xE6, 0x1E, 0x07, 0xE3, 0x80, 0x1E, 0x30,
0x00, 0xE6, 0x00, 0x06, 0x60, 0x00, 0x66, 0x00, 0x06, 0x60, 0x00, 0x07,
0x00, 0x00, 0x30, 0x00, 0x01, 0xC0, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0xC0,
0x00, 0x3F, 0x80, 0x00, 0x1C, 0x00, 0x00, 0xE0, 0x00, 0x07, 0x00, 0x00,
0x30, 0x00, 0x03, 0xC0, 0x00, 0x3C, 0x00, 0x03, 0xE0, 0x00, 0x7E, 0x00,
0x06, 0xF8, 0x01, 0xED, 0xE0, 0x7C, 0xCF, 0xFF, 0x00, 0x3F, 0xC0, 0xFF,
0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x03, 0x00, 0xF0, 0x0C, 0x03, 0xC0, 0x30,
0x0F, 0x00, 0xC0, 0x3C, 0x03, 0x00, 0xC0, 0x0C, 0x00, 0x00, 0x30, 0x00,
0x00, 0xC0, 0x00, 0x03, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x30, 0x00, 0x00,
0xC0, 0x00, 0x03, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x30, 0x00, 0x00, 0xC0,
0x00, 0x03, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x30, 0x00, 0x00, 0xC0, 0x00,
0x03, 0x00, 0x00, 0x0C, 0x00, 0x0F, 0xFF, 0xC0, 0x3F, 0xFF, 0x00, 0xFF,
0x01, 0xFF, 0xFE, 0x03, 0xFC, 0xC0, 0x00, 0x61, 0x80, 0x00, 0xC3, 0x00,
0x01, 0x86, 0x00, 0x03, 0x0C, 0x00, 0x06, 0x18, 0x00, 0x0C, 0x30, 0x00,
0x18, 0x60, 0x00, 0x30, 0xC0, 0x00, 0x61, 0x80, 0x00, 0xC3, 0x00, 0x01,
0x86, 0x00, 0x03, 0x0C, 0x00, 0x06, 0x18, 0x00, 0x0C, 0x30, 0x00, 0x18,
0x60, 0x00, 0x30, 0xC0, 0x00, 0x61, 0x80, 0x00, 0xC3, 0x80, 0x03, 0x83,
0x00, 0x06, 0x07, 0x00, 0x1C, 0x07, 0x00, 0x70, 0x07, 0x83, 0xC0, 0x07,
0xFF, 0x00, 0x03, 0xF8, 0x00, 0x7F, 0xC0, 0x3F, 0xF7, 0xFC, 0x03, 0xFF,
0x18, 0x00, 0x01, 0x80, 0xC0, 0x00, 0x30, 0x0C, 0x00, 0x03, 0x00, 0x60,
0x00, 0x30, 0x06, 0x00, 0x06, 0x00, 0x60, 0x00, 0x60, 0x03, 0x00, 0x0C,
0x00, 0x30, 0x00, 0xC0, 0x03, 0x80, 0x0C, 0x00, 0x18, 0x01, 0x80, 0x01,
0x80, 0x18, 0x00, 0x0C, 0x03, 0x00, 0x00, 0xC0, 0x30, 0x00, 0x0E, 0x03,
0x00, 0x00, 0x60, 0x60, 0x00, 0x06, 0x06, 0x00, 0x00, 0x30, 0xC0, 0x00,
0x03, 0x0C, 0x00, 0x00, 0x30, 0x80, 0x00, 0x01, 0x98, 0x00, 0x00, 0x19,
0x80, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0xE0, 0x00,
0xFF, 0x80, 0x7F, 0xFF, 0xE0, 0x1F, 0xF3, 0x00, 0x00, 0x30, 0xC0, 0x00,
0x0C, 0x30, 0x00, 0x03, 0x0C, 0x03, 0x80, 0xC3, 0x01, 0xE0, 0x30, 0x60,
0x78, 0x0C, 0x18, 0x1F, 0x02, 0x06, 0x04, 0xC0, 0x81, 0x83, 0x30, 0x60,
0x60, 0xCC, 0x18, 0x18, 0x31, 0x86, 0x06, 0x18, 0x61, 0x81, 0x86, 0x18,
0x60, 0x71, 0x87, 0x18, 0x0C, 0x40, 0xC6, 0x03, 0x30, 0x31, 0x00, 0xCC,
0x0C, 0xC0, 0x33, 0x01, 0xB0, 0x0D, 0x80, 0x6C, 0x03, 0x60, 0x1B, 0x00,
0xD8, 0x06, 0xC0, 0x34, 0x00, 0xF0, 0x07, 0x00, 0x3C, 0x01, 0xC0, 0x0E,
0x00, 0x7F, 0x00, 0xFF, 0x7F, 0x00, 0xFF, 0x18, 0x00, 0x18, 0x0C, 0x00,
0x38, 0x0E, 0x00, 0x70, 0x07, 0x00, 0x60, 0x03, 0x00, 0xC0, 0x01, 0x81,
0x80, 0x01, 0xC3, 0x80, 0x00, 0xE7, 0x00, 0x00, 0x76, 0x00, 0x00, 0x3C,
0x00, 0x00, 0x18, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x66,
0x00, 0x00, 0xC3, 0x00, 0x01, 0x81, 0x80, 0x03, 0x81, 0xC0, 0x07, 0x00,
0xE0, 0x06, 0x00, 0x60, 0x0C, 0x00, 0x30, 0x18, 0x00, 0x18, 0x38, 0x00,
0x1C, 0xFF, 0x00, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0x00,
0xFF, 0x18, 0x00, 0x18, 0x0C, 0x00, 0x30, 0x0E, 0x00, 0x70, 0x06, 0x00,
0x60, 0x03, 0x00, 0xC0, 0x03, 0x81, 0xC0, 0x01, 0x81, 0x80, 0x00, 0xC3,
0x00, 0x00, 0xE7, 0x00, 0x00, 0x66, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x3C,
0x00, 0x00, 0x18, 0x00, 0x00, 0x18, 0x00, 0x00, 0x18, 0x00, 0x00, 0x18,
0x00, 0x00, 0x18, 0x00, 0x00, 0x18, 0x00, 0x00, 0x18, 0x00, 0x00, 0x18,
0x00, 0x00, 0x18, 0x00, 0x00, 0x18, 0x00, 0x07, 0xFF, 0xE0, 0x07, 0xFF,
0xE0, 0x7F, 0xFF, 0x9F, 0xFF, 0xE6, 0x00, 0x19, 0x80, 0x0C, 0x60, 0x07,
0x18, 0x03, 0x86, 0x00, 0xC1, 0x80, 0x70, 0x00, 0x38, 0x00, 0x0C, 0x00,
0x07, 0x00, 0x03, 0x80, 0x00, 0xC0, 0x00, 0x60, 0x00, 0x38, 0x00, 0x1C,
0x00, 0x06, 0x00, 0x03, 0x80, 0x31, 0xC0, 0x0C, 0x60, 0x03, 0x30, 0x00,
0xDC, 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0,
0xFF, 0xFF, 0x06, 0x0C, 0x18, 0x30, 0x60, 0xC1, 0x83, 0x06, 0x0C, 0x18,
0x30, 0x60, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x30, 0x60, 0xC1, 0x83, 0x06,
0x0C, 0x18, 0x30, 0x60, 0xFF, 0xFC, 0xC0, 0x00, 0x30, 0x00, 0x06, 0x00,
0x01, 0x80, 0x00, 0x30, 0x00, 0x0C, 0x00, 0x01, 0x80, 0x00, 0x60, 0x00,
0x0C, 0x00, 0x03, 0x00, 0x00, 0x60, 0x00, 0x18, 0x00, 0x03, 0x00, 0x00,
0xC0, 0x00, 0x18, 0x00, 0x06, 0x00, 0x00, 0xC0, 0x00, 0x30, 0x00, 0x06,
0x00, 0x01, 0x80, 0x00, 0x30, 0x00, 0x0C, 0x00, 0x03, 0x80, 0x00, 0x60,
0x00, 0x1C, 0x00, 0x03, 0x00, 0x00, 0xE0, 0x00, 0x18, 0x00, 0x07, 0x00,
0x00, 0xC0, 0x00, 0x30, 0x00, 0x06, 0x00, 0x01, 0x80, 0x00, 0x30, 0x00,
0x0C, 0xFF, 0xFC, 0x18, 0x30, 0x60, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x30,
0x60, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x30, 0x60, 0xC1, 0x83, 0x06, 0x0C,
0x18, 0x30, 0x60, 0xC1, 0x83, 0xFF, 0xFC, 0x00, 0x40, 0x00, 0x30, 0x00,
0x1E, 0x00, 0x0E, 0xC0, 0x07, 0x38, 0x01, 0x87, 0x00, 0xC0, 0xC0, 0x60,
0x18, 0x38, 0x03, 0x1C, 0x00, 0xE6, 0x00, 0x1F, 0x00, 0x03, 0xFF, 0xFF,
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xE0, 0x70, 0x3C, 0x0E, 0x07, 0x03,
0x01, 0xFC, 0x00, 0x7F, 0xFC, 0x01, 0xC0, 0x3C, 0x00, 0x00, 0x30, 0x00,
0x00, 0x60, 0x00, 0x01, 0x80, 0x00, 0x06, 0x00, 0x00, 0x18, 0x00, 0x00,
0x60, 0x0F, 0xF9, 0x81, 0xFF, 0xFE, 0x0F, 0x80, 0x38, 0x70, 0x00, 0x63,
0x80, 0x01, 0x8C, 0x00, 0x06, 0x30, 0x00, 0x18, 0xC0, 0x00, 0xE3, 0x00,
0x07, 0x86, 0x00, 0x76, 0x1E, 0x07, 0x9F, 0x3F, 0xF8, 0x7C, 0x3F, 0x80,
0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x60, 0x00, 0x00, 0xC0, 0x00,
0x01, 0x80, 0x00, 0x03, 0x00, 0x00, 0x06, 0x00, 0x00, 0x0C, 0x1F, 0x80,
0x18, 0xFF, 0xC0, 0x33, 0x81, 0xC0, 0x6E, 0x01, 0xC0, 0xF0, 0x00, 0xC1,
0xE0, 0x01, 0xC3, 0x80, 0x01, 0x87, 0x00, 0x03, 0x8C, 0x00, 0x03, 0x18,
0x00, 0x06, 0x30, 0x00, 0x0C, 0x60, 0x00, 0x18, 0xC0, 0x00, 0x31, 0x80,
0x00, 0x63, 0x80, 0x01, 0x87, 0x00, 0x03, 0x0F, 0x00, 0x0E, 0x1F, 0x00,
0x38, 0x37, 0x00, 0xE3, 0xE7, 0x03, 0x87, 0xC7, 0xFE, 0x00, 0x03, 0xF0,
0x00, 0x01, 0xFC, 0x00, 0x3F, 0xF9, 0x83, 0xC0, 0xFC, 0x38, 0x01, 0xE3,
0x00, 0x07, 0x38, 0x00, 0x19, 0x80, 0x00, 0xDC, 0x00, 0x06, 0xC0, 0x00,
0x06, 0x00, 0x00, 0x30, 0x00, 0x01, 0x80, 0x00, 0x0C, 0x00, 0x00, 0x60,
0x00, 0x03, 0x80, 0x00, 0x0C, 0x00, 0x00, 0x70, 0x00, 0x01, 0x80, 0x00,
0xC7, 0x00, 0x1E, 0x1E, 0x03, 0xC0, 0x7F, 0xFC, 0x00, 0xFF, 0x00, 0x00,
0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x18, 0x00, 0x00, 0x18, 0x00,
0x00, 0x18, 0x00, 0x00, 0x18, 0x00, 0x00, 0x18, 0x01, 0xF8, 0x18, 0x07,
0xFE, 0x18, 0x0F, 0x07, 0x98, 0x1C, 0x01, 0xD8, 0x38, 0x00, 0xF8, 0x70,
0x00, 0x78, 0x60, 0x00, 0x38, 0xE0, 0x00, 0x38, 0xC0, 0x00, 0x18, 0xC0,
0x00, 0x18, 0xC0, 0x00, 0x18, 0xC0, 0x00, 0x18, 0xC0, 0x00, 0x18, 0xC0,
0x00, 0x18, 0x60, 0x00, 0x38, 0x60, 0x00, 0x38, 0x70, 0x00, 0x78, 0x38,
0x00, 0xD8, 0x1C, 0x01, 0xD8, 0x0F, 0x07, 0x9F, 0x07, 0xFE, 0x1F, 0x01,
0xF8, 0x00, 0x01, 0xFC, 0x00, 0x3F, 0xF8, 0x07, 0x80, 0xF0, 0x70, 0x01,
0xC3, 0x00, 0x07, 0x30, 0x00, 0x19, 0x80, 0x00, 0x78, 0x00, 0x03, 0xC0,
0x00, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0x0C, 0x00, 0x00,
0x60, 0x00, 0x01, 0x80, 0x00, 0x0C, 0x00, 0x00, 0x30, 0x00, 0x01, 0xC0,
0x00, 0xC7, 0x00, 0x0E, 0x1E, 0x03, 0xE0, 0x3F, 0xFC, 0x00, 0x7F, 0x00,
0x00, 0x7F, 0xC0, 0x3F, 0xFC, 0x0E, 0x00, 0x03, 0x80, 0x00, 0x60, 0x00,
0x0C, 0x00, 0x01, 0x80, 0x00, 0x30, 0x00, 0xFF, 0xFF, 0x9F, 0xFF, 0xF0,
0x18, 0x00, 0x03, 0x00, 0x00, 0x60, 0x00, 0x0C, 0x00, 0x01, 0x80, 0x00,
0x30, 0x00, 0x06, 0x00, 0x00, 0xC0, 0x00, 0x18, 0x00, 0x03, 0x00, 0x00,
0x60, 0x00, 0x0C, 0x00, 0x01, 0x80, 0x00, 0x30, 0x00, 0x06, 0x00, 0x00,
0xC0, 0x03, 0xFF, 0xFC, 0x7F, 0xFF, 0x80, 0x01, 0xF8, 0x00, 0x0F, 0xFC,
0x7C, 0x38, 0x1C, 0xF8, 0xE0, 0x0D, 0x83, 0x00, 0x0F, 0x0E, 0x00, 0x1E,
0x18, 0x00, 0x1C, 0x70, 0x00, 0x38, 0xC0, 0x00, 0x31, 0x80, 0x00, 0x63,
0x00, 0x00, 0xC6, 0x00, 0x01, 0x8C, 0x00, 0x03, 0x18, 0x00, 0x06, 0x18,
0x00, 0x1C, 0x30, 0x00, 0x38, 0x30, 0x00, 0xF0, 0x70, 0x03, 0x60, 0x78,
0x1C, 0xC0, 0x3F, 0xF1, 0x80, 0x1F, 0x83, 0x00, 0x00, 0x06, 0x00, 0x00,
0x0C, 0x00, 0x00, 0x18, 0x00, 0x00, 0x30, 0x00, 0x00, 0xC0, 0x00, 0x03,
0x80, 0x00, 0x0E, 0x00, 0x3F, 0xF8, 0x00, 0x7F, 0xC0, 0x00, 0xF8, 0x00,
0x01, 0xF0, 0x00, 0x00, 0x60, 0x00, 0x00, 0xC0, 0x00, 0x01, 0x80, 0x00,
0x03, 0x00, 0x00, 0x06, 0x00, 0x00, 0x0C, 0x3F, 0x00, 0x18, 0xFF, 0x80,
0x37, 0x03, 0x80, 0x7C, 0x03, 0x80, 0xF0, 0x03, 0x81, 0xC0, 0x03, 0x03,
0x00, 0x06, 0x06, 0x00, 0x0C, 0x0C, 0x00, 0x18, 0x18, 0x00, 0x30, 0x30,
0x00, 0x60, 0x60, 0x00, 0xC0, 0xC0, 0x01, 0x81, 0x80, 0x03, 0x03, 0x00,
0x06, 0x06, 0x00, 0x0C, 0x0C, 0x00, 0x18, 0x18, 0x00, 0x30, 0x30, 0x00,
0x63, 0xFC, 0x07, 0xFF, 0xF8, 0x0F, 0xF0, 0x01, 0xC0, 0x00, 0x70, 0x00,
0x1C, 0x00, 0x07, 0x00, 0x01, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x0F, 0xF0, 0x03, 0xFC, 0x00, 0x03, 0x00, 0x00, 0xC0,
0x00, 0x30, 0x00, 0x0C, 0x00, 0x03, 0x00, 0x00, 0xC0, 0x00, 0x30, 0x00,
0x0C, 0x00, 0x03, 0x00, 0x00, 0xC0, 0x00, 0x30, 0x00, 0x0C, 0x00, 0x03,
0x00, 0x00, 0xC0, 0x00, 0x30, 0x00, 0x0C, 0x03, 0xFF, 0xFF, 0xFF, 0xFF,
0xC0, 0x00, 0x70, 0x01, 0xC0, 0x07, 0x00, 0x1C, 0x00, 0x70, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xFF, 0xC0, 0x03, 0x00, 0x0C,
0x00, 0x30, 0x00, 0xC0, 0x03, 0x00, 0x0C, 0x00, 0x30, 0x00, 0xC0, 0x03,
0x00, 0x0C, 0x00, 0x30, 0x00, 0xC0, 0x03, 0x00, 0x0C, 0x00, 0x30, 0x00,
0xC0, 0x03, 0x00, 0x0C, 0x00, 0x30, 0x00, 0xC0, 0x03, 0x00, 0x0C, 0x00,
0x70, 0x03, 0x80, 0x1C, 0xFF, 0xE3, 0xFF, 0x00, 0xF8, 0x00, 0x03, 0xE0,
0x00, 0x01, 0x80, 0x00, 0x06, 0x00, 0x00, 0x18, 0x00, 0x00, 0x60, 0x00,
0x01, 0x80, 0x00, 0x06, 0x00, 0x00, 0x18, 0x1F, 0xE0, 0x60, 0x7F, 0x81,
0x80, 0x60, 0x06, 0x07, 0x00, 0x18, 0x38, 0x00, 0x61, 0xC0, 0x01, 0x8E,
0x00, 0x06, 0x70, 0x00, 0x1B, 0x80, 0x00, 0x7F, 0x00, 0x01, 0xCE, 0x00,
0x06, 0x1C, 0x00, 0x18, 0x38, 0x00, 0x60, 0x70, 0x01, 0x80, 0xE0, 0x06,
0x01, 0xC0, 0x18, 0x03, 0x80, 0x60, 0x07, 0x0F, 0x80, 0x7F, 0xFE, 0x01,
0xFF, 0x3F, 0xC0, 0x0F, 0xF0, 0x00, 0x0C, 0x00, 0x03, 0x00, 0x00, 0xC0,
0x00, 0x30, 0x00, 0x0C, 0x00, 0x03, 0x00, 0x00, 0xC0, 0x00, 0x30, 0x00,
0x0C, 0x00, 0x03, 0x00, 0x00, 0xC0, 0x00, 0x30, 0x00, 0x0C, 0x00, 0x03,
0x00, 0x00, 0xC0, 0x00, 0x30, 0x00, 0x0C, 0x00, 0x03, 0x00, 0x00, 0xC0,
0x00, 0x30, 0x00, 0x0C, 0x00, 0x03, 0x00, 0x00, 0xC0, 0x00, 0x30, 0x0F,
0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0xF0, 0x3C, 0x0F, 0x9F, 0x87, 0xE0, 0xFB,
0x1C, 0xC7, 0x01, 0xE0, 0xD8, 0x38, 0x1C, 0x07, 0x01, 0x81, 0x80, 0x60,
0x18, 0x18, 0x06, 0x01, 0x81, 0x80, 0x60, 0x18, 0x18, 0x06, 0x01, 0x81,
0x80, 0x60, 0x18, 0x18, 0x06, 0x01, 0x81, 0x80, 0x60, 0x18, 0x18, 0x06,
0x01, 0x81, 0x80, 0x60, 0x18, 0x18, 0x06, 0x01, 0x81, 0x80, 0x60, 0x18,
0x18, 0x06, 0x01, 0x81, 0x80, 0x60, 0x18, 0x18, 0x06, 0x01, 0x8F, 0xE0,
0x7C, 0x1F, 0xFE, 0x07, 0xC1, 0xF0, 0x00, 0x1F, 0x00, 0xF8, 0xFF, 0x81,
0xF3, 0x83, 0x80, 0x6C, 0x03, 0x80, 0xF0, 0x03, 0x81, 0xC0, 0x03, 0x03,
0x00, 0x06, 0x06, 0x00, 0x0C, 0x0C, 0x00, 0x18, 0x18, 0x00, 0x30, 0x30,
0x00, 0x60, 0x60, 0x00, 0xC0, 0xC0, 0x01, 0x81, 0x80, 0x03, 0x03, 0x00,
0x06, 0x06, 0x00, 0x0C, 0x0C, 0x00, 0x18, 0x18, 0x00, 0x30, 0x30, 0x00,
0x67, 0xFC, 0x03, 0xFF, 0xF8, 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0xFE,
0x00, 0xF0, 0x3C, 0x07, 0x00, 0x38, 0x38, 0x00, 0x71, 0xC0, 0x00, 0xE6,
0x00, 0x01, 0x98, 0x00, 0x06, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00,
0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x36, 0x00, 0x01,
0x98, 0x00, 0x06, 0x70, 0x00, 0x38, 0xE0, 0x01, 0xC1, 0xC0, 0x0E, 0x03,
0xC0, 0xF0, 0x07, 0xFF, 0x80, 0x03, 0xF0, 0x00, 0x00, 0x3F, 0x01, 0xF1,
0xFF, 0x83, 0xE7, 0x03, 0x80, 0xD8, 0x01, 0x81, 0xE0, 0x01, 0x83, 0xC0,
0x03, 0x87, 0x00, 0x03, 0x0E, 0x00, 0x07, 0x18, 0x00, 0x06, 0x30, 0x00,
0x0C, 0x60, 0x00, 0x18, 0xC0, 0x00, 0x31, 0x80, 0x00, 0x63, 0x00, 0x00,
0xC7, 0x00, 0x03, 0x0E, 0x00, 0x06, 0x1E, 0x00, 0x18, 0x36, 0x00, 0x70,
0x67, 0x03, 0xC0, 0xC7, 0xFE, 0x01, 0x83, 0xF0, 0x03, 0x00, 0x00, 0x06,
0x00, 0x00, 0x0C, 0x00, 0x00, 0x18, 0x00, 0x00, 0x30, 0x00, 0x00, 0x60,
0x00, 0x00, 0xC0, 0x00, 0x0F, 0xFC, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x01,
0xF8, 0x00, 0x07, 0xFF, 0x1F, 0x0F, 0x07, 0x9F, 0x1C, 0x01, 0xD8, 0x38,
0x00, 0x78, 0x70, 0x00, 0x78, 0x60, 0x00, 0x38, 0xE0, 0x00, 0x38, 0xC0,
0x00, 0x18, 0xC0, 0x00, 0x18, 0xC0, 0x00, 0x18, 0xC0, 0x00, 0x18, 0xC0,
0x00, 0x18, 0xC0, 0x00, 0x18, 0x60, 0x00, 0x38, 0x70, 0x00, 0x78, 0x30,
0x00, 0x78, 0x1C, 0x01, 0xD8, 0x0F, 0x07, 0x98, 0x07, 0xFF, 0x18, 0x01,
0xFC, 0x18, 0x00, 0x00, 0x18, 0x00, 0x00, 0x18, 0x00, 0x00, 0x18, 0x00,
0x00, 0x18, 0x00, 0x00, 0x18, 0x00, 0x00, 0x18, 0x00, 0x00, 0x18, 0x00,
0x03, 0xFF, 0x00, 0x03, 0xFF, 0x7E, 0x03, 0xC3, 0xF0, 0x7F, 0x81, 0x8F,
0x0E, 0x0C, 0xE0, 0x00, 0x7E, 0x00, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x00,
0xC0, 0x00, 0x06, 0x00, 0x00, 0x30, 0x00, 0x01, 0x80, 0x00, 0x0C, 0x00,
0x00, 0x60, 0x00, 0x03, 0x00, 0x00, 0x18, 0x00, 0x00, 0xC0, 0x00, 0x06,
0x00, 0x00, 0x30, 0x00, 0x3F, 0xFF, 0xC1, 0xFF, 0xFE, 0x00, 0x07, 0xF0,
0x07, 0xFF, 0x63, 0xC0, 0xF9, 0xC0, 0x0E, 0x60, 0x01, 0x98, 0x00, 0x66,
0x00, 0x19, 0xC0, 0x00, 0x38, 0x00, 0x07, 0xC0, 0x00, 0x7F, 0xC0, 0x00,
0x7C, 0x00, 0x03, 0x80, 0x00, 0x70, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00,
0xF8, 0x00, 0x7F, 0x00, 0x3B, 0xF0, 0x3C, 0xDF, 0xFE, 0x00, 0xFE, 0x00,
0x0C, 0x00, 0x00, 0x60, 0x00, 0x03, 0x00, 0x00, 0x18, 0x00, 0x00, 0xC0,
0x00, 0x06, 0x00, 0x03, 0xFF, 0xFE, 0x1F, 0xFF, 0xF0, 0x0C, 0x00, 0x00,
0x60, 0x00, 0x03, 0x00, 0x00, 0x18, 0x00, 0x00, 0xC0, 0x00, 0x06, 0x00,
0x00, 0x30, 0x00, 0x01, 0x80, 0x00, 0x0C, 0x00, 0x00, 0x60, 0x00, 0x03,
0x00, 0x00, 0x18, 0x00, 0x00, 0xC0, 0x00, 0x06, 0x00, 0x00, 0x30, 0x00,
0x00, 0xC0, 0x07, 0x07, 0x01, 0xF0, 0x1F, 0xFF, 0x00, 0x3F, 0x80, 0xF8,
0x03, 0xF1, 0xF0, 0x07, 0xE0, 0x60, 0x00, 0xC0, 0xC0, 0x01, 0x81, 0x80,
0x03, 0x03, 0x00, 0x06, 0x06, 0x00, 0x0C, 0x0C, 0x00, 0x18, 0x18, 0x00,
0x30, 0x30, 0x00, 0x60, 0x60, 0x00, 0xC0, 0xC0, 0x01, 0x81, 0x80, 0x03,
0x03, 0x00, 0x06, 0x06, 0x00, 0x0C, 0x0C, 0x00, 0x38, 0x18, 0x00, 0xF0,
0x18, 0x03, 0x60, 0x38, 0x3C, 0xF8, 0x3F, 0xF1, 0xF0, 0x1F, 0x00, 0x00,
0x7F, 0xC0, 0xFF, 0xDF, 0xF0, 0x3F, 0xF0, 0xC0, 0x00, 0xC0, 0x30, 0x00,
0x30, 0x06, 0x00, 0x1C, 0x01, 0x80, 0x06, 0x00, 0x30, 0x01, 0x80, 0x0C,
0x00, 0xC0, 0x03, 0x80, 0x30, 0x00, 0x60, 0x18, 0x00, 0x18, 0x06, 0x00,
0x03, 0x03, 0x00, 0x00, 0xC0, 0xC0, 0x00, 0x18, 0x30, 0x00, 0x06, 0x18,
0x00, 0x00, 0xC6, 0x00, 0x00, 0x33, 0x00, 0x00, 0x0E, 0xC0, 0x00, 0x01,
0xE0, 0x00, 0x00, 0x78, 0x00, 0x7F, 0x00, 0x3F, 0xDF, 0xC0, 0x0F, 0xF1,
0x80, 0x00, 0x20, 0x60, 0x00, 0x18, 0x18, 0x00, 0x06, 0x06, 0x03, 0x01,
0x80, 0x81, 0xE0, 0x60, 0x30, 0x78, 0x10, 0x0C, 0x1E, 0x0C, 0x03, 0x0C,
0xC3, 0x00, 0xC3, 0x30, 0xC0, 0x10, 0xCC, 0x30, 0x06, 0x61, 0x98, 0x01,
0x98, 0x66, 0x00, 0x66, 0x19, 0x80, 0x0B, 0x03, 0x60, 0x03, 0xC0, 0xD0,
0x00, 0xF0, 0x1C, 0x00, 0x38, 0x07, 0x00, 0x0E, 0x01, 0xC0, 0x3F, 0x81,
0xFE, 0x3F, 0x81, 0xFE, 0x0C, 0x00, 0x38, 0x06, 0x00, 0x70, 0x03, 0x00,
0xE0, 0x01, 0x81, 0xC0, 0x00, 0xC3, 0x80, 0x00, 0x67, 0x00, 0x00, 0x3C,
0x00, 0x00, 0x18, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x67, 0x00, 0x00, 0xC3,
0x80, 0x01, 0x81, 0xC0, 0x03, 0x00, 0xE0, 0x06, 0x00, 0x70, 0x0C, 0x00,
0x38, 0x18, 0x00, 0x1C, 0x7F, 0x81, 0xFF, 0x7F, 0x81, 0xFF, 0x7F, 0x00,
0xFF, 0x7F, 0x00, 0xFF, 0x18, 0x00, 0x0C, 0x18, 0x00, 0x18, 0x0C, 0x00,
0x18, 0x0C, 0x00, 0x30, 0x06, 0x00, 0x30, 0x06, 0x00, 0x60, 0x03, 0x00,
0x60, 0x03, 0x00, 0xC0, 0x01, 0x80, 0xC0, 0x01, 0x81, 0x80, 0x00, 0xC1,
0x80, 0x00, 0xC3, 0x00, 0x00, 0x63, 0x00, 0x00, 0x66, 0x00, 0x00, 0x36,
0x00, 0x00, 0x34, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x18, 0x00, 0x00, 0x18,
0x00, 0x00, 0x18, 0x00, 0x00, 0x30, 0x00, 0x00, 0x30, 0x00, 0x00, 0x60,
0x00, 0x00, 0x60, 0x00, 0x00, 0xC0, 0x00, 0x7F, 0xFC, 0x00, 0x7F, 0xFC,
0x00, 0xFF, 0xFF, 0x7F, 0xFF, 0xB0, 0x01, 0x98, 0x01, 0xCC, 0x01, 0xC0,
0x00, 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0xE0,
0x00, 0x60, 0x00, 0x60, 0x00, 0x60, 0x00, 0x60, 0x00, 0x60, 0x03, 0x70,
0x01, 0xB0, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0xE0, 0x7C, 0x0C,
0x03, 0x00, 0x60, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x00, 0xC0, 0x18, 0x03,
0x00, 0x60, 0x0C, 0x03, 0x00, 0xE0, 0xF0, 0x1E, 0x00, 0x70, 0x06, 0x00,
0x60, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x00, 0xC0, 0x18, 0x03, 0x00, 0x60,
0x0C, 0x01, 0x80, 0x18, 0x03, 0xE0, 0x1C, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
0xFF, 0xFF, 0xFF, 0xF0, 0xE0, 0x1F, 0x00, 0x60, 0x06, 0x00, 0xC0, 0x18,
0x03, 0x00, 0x60, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x00, 0xC0, 0x18, 0x01,
0x80, 0x38, 0x01, 0xE0, 0x3C, 0x1C, 0x03, 0x00, 0xC0, 0x18, 0x03, 0x00,
0x60, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x00, 0xC0, 0x18, 0x03, 0x00, 0xC0,
0xF8, 0x1C, 0x00, 0x0F, 0x00, 0x03, 0xFC, 0x03, 0x70, 0xE0, 0x76, 0x07,
0x8E, 0xC0, 0x1F, 0xC0, 0x00, 0xF0 };
const GFXglyph FreeMono24pt7bGlyphs[] PROGMEM = {
{ 0, 0, 0, 28, 0, 1 }, // 0x20 ' '
{ 0, 5, 30, 28, 11, -28 }, // 0x21 '!'
{ 19, 16, 14, 28, 6, -28 }, // 0x22 '"'
{ 47, 19, 32, 28, 4, -29 }, // 0x23 '#'
{ 123, 18, 33, 28, 5, -29 }, // 0x24 '$'
{ 198, 20, 29, 28, 4, -27 }, // 0x25 '%'
{ 271, 18, 25, 28, 5, -23 }, // 0x26 '&'
{ 328, 7, 14, 28, 11, -28 }, // 0x27 '''
{ 341, 7, 34, 28, 14, -27 }, // 0x28 '('
{ 371, 7, 34, 28, 8, -27 }, // 0x29 ')'
{ 401, 18, 16, 28, 5, -27 }, // 0x2A '*'
{ 437, 20, 22, 28, 4, -23 }, // 0x2B '+'
{ 492, 9, 14, 28, 6, -6 }, // 0x2C ','
{ 508, 22, 2, 28, 3, -13 }, // 0x2D '-'
{ 514, 7, 6, 28, 11, -4 }, // 0x2E '.'
{ 520, 18, 35, 28, 5, -30 }, // 0x2F '/'
{ 599, 18, 30, 28, 5, -28 }, // 0x30 '0'
{ 667, 16, 29, 28, 6, -28 }, // 0x31 '1'
{ 725, 18, 29, 28, 5, -28 }, // 0x32 '2'
{ 791, 19, 30, 28, 5, -28 }, // 0x33 '3'
{ 863, 16, 28, 28, 6, -27 }, // 0x34 '4'
{ 919, 19, 29, 28, 5, -27 }, // 0x35 '5'
{ 988, 18, 30, 28, 6, -28 }, // 0x36 '6'
{ 1056, 18, 28, 28, 5, -27 }, // 0x37 '7'
{ 1119, 18, 30, 28, 5, -28 }, // 0x38 '8'
{ 1187, 18, 30, 28, 6, -28 }, // 0x39 '9'
{ 1255, 7, 21, 28, 11, -19 }, // 0x3A ':'
{ 1274, 10, 27, 28, 7, -19 }, // 0x3B ';'
{ 1308, 22, 22, 28, 3, -23 }, // 0x3C '<'
{ 1369, 24, 9, 28, 2, -17 }, // 0x3D '='
{ 1396, 21, 22, 28, 4, -23 }, // 0x3E '>'
{ 1454, 17, 28, 28, 6, -26 }, // 0x3F '?'
{ 1514, 18, 32, 28, 5, -28 }, // 0x40 '@'
{ 1586, 28, 26, 28, 0, -25 }, // 0x41 'A'
{ 1677, 22, 26, 28, 3, -25 }, // 0x42 'B'
{ 1749, 22, 28, 28, 3, -26 }, // 0x43 'C'
{ 1826, 22, 26, 28, 3, -25 }, // 0x44 'D'
{ 1898, 22, 26, 28, 3, -25 }, // 0x45 'E'
{ 1970, 22, 26, 28, 3, -25 }, // 0x46 'F'
{ 2042, 23, 28, 28, 3, -26 }, // 0x47 'G'
{ 2123, 23, 26, 28, 3, -25 }, // 0x48 'H'
{ 2198, 16, 26, 28, 6, -25 }, // 0x49 'I'
{ 2250, 23, 27, 28, 4, -25 }, // 0x4A 'J'
{ 2328, 24, 26, 28, 3, -25 }, // 0x4B 'K'
{ 2406, 21, 26, 28, 4, -25 }, // 0x4C 'L'
{ 2475, 26, 26, 28, 1, -25 }, // 0x4D 'M'
{ 2560, 24, 26, 28, 2, -25 }, // 0x4E 'N'
{ 2638, 24, 28, 28, 2, -26 }, // 0x4F 'O'
{ 2722, 21, 26, 28, 3, -25 }, // 0x50 'P'
{ 2791, 24, 32, 28, 2, -26 }, // 0x51 'Q'
{ 2887, 24, 26, 28, 3, -25 }, // 0x52 'R'
{ 2965, 20, 28, 28, 4, -26 }, // 0x53 'S'
{ 3035, 22, 26, 28, 3, -25 }, // 0x54 'T'
{ 3107, 23, 27, 28, 3, -25 }, // 0x55 'U'
{ 3185, 28, 26, 28, 0, -25 }, // 0x56 'V'
{ 3276, 26, 26, 28, 1, -25 }, // 0x57 'W'
{ 3361, 24, 26, 28, 2, -25 }, // 0x58 'X'
{ 3439, 24, 26, 28, 2, -25 }, // 0x59 'Y'
{ 3517, 18, 26, 28, 5, -25 }, // 0x5A 'Z'
{ 3576, 7, 34, 28, 13, -27 }, // 0x5B '['
{ 3606, 18, 35, 28, 5, -30 }, // 0x5C '\'
{ 3685, 7, 34, 28, 8, -27 }, // 0x5D ']'
{ 3715, 18, 12, 28, 5, -28 }, // 0x5E '^'
{ 3742, 28, 2, 28, 0, 5 }, // 0x5F '_'
{ 3749, 8, 7, 28, 7, -29 }, // 0x60 '`'
{ 3756, 22, 22, 28, 3, -20 }, // 0x61 'a'
{ 3817, 23, 29, 28, 2, -27 }, // 0x62 'b'
{ 3901, 21, 22, 28, 4, -20 }, // 0x63 'c'
{ 3959, 24, 29, 28, 3, -27 }, // 0x64 'd'
{ 4046, 21, 22, 28, 3, -20 }, // 0x65 'e'
{ 4104, 19, 28, 28, 6, -27 }, // 0x66 'f'
{ 4171, 23, 30, 28, 3, -20 }, // 0x67 'g'
{ 4258, 23, 28, 28, 3, -27 }, // 0x68 'h'
{ 4339, 18, 29, 28, 5, -28 }, // 0x69 'i'
{ 4405, 14, 38, 28, 6, -28 }, // 0x6A 'j'
{ 4472, 22, 28, 28, 4, -27 }, // 0x6B 'k'
{ 4549, 18, 28, 28, 5, -27 }, // 0x6C 'l'
{ 4612, 28, 21, 28, 0, -20 }, // 0x6D 'm'
{ 4686, 23, 21, 28, 2, -20 }, // 0x6E 'n'
{ 4747, 22, 22, 28, 3, -20 }, // 0x6F 'o'
{ 4808, 23, 30, 28, 2, -20 }, // 0x70 'p'
{ 4895, 24, 30, 28, 3, -20 }, // 0x71 'q'
{ 4985, 21, 20, 28, 5, -19 }, // 0x72 'r'
{ 5038, 18, 22, 28, 5, -20 }, // 0x73 's'
{ 5088, 21, 27, 28, 3, -25 }, // 0x74 't'
{ 5159, 23, 21, 28, 3, -19 }, // 0x75 'u'
{ 5220, 26, 20, 28, 1, -19 }, // 0x76 'v'
{ 5285, 26, 20, 28, 1, -19 }, // 0x77 'w'
{ 5350, 24, 20, 28, 2, -19 }, // 0x78 'x'
{ 5410, 24, 29, 28, 2, -19 }, // 0x79 'y'
{ 5497, 17, 20, 28, 6, -19 }, // 0x7A 'z'
{ 5540, 11, 34, 28, 8, -27 }, // 0x7B '{'
{ 5587, 2, 34, 28, 13, -27 }, // 0x7C '|'
{ 5596, 11, 34, 28, 9, -27 }, // 0x7D '}'
{ 5643, 20, 6, 28, 4, -15 } }; // 0x7E '~'
const GFXfont FreeMono24pt7b PROGMEM = {
(uint8_t *)FreeMono24pt7bBitmaps,
(GFXglyph *)FreeMono24pt7bGlyphs,
0x20, 0x7E, 47 };
// Approx. 6330 bytes

Some files were not shown because too many files have changed in this diff Show More